MecanumDrive

class wpilib.drive.MecanumDrive(frontLeftMotor, rearLeftMotor, frontRightMotor, rearRightMotor)[source]

Bases: wpilib.drive.RobotDriveBase

A class for driving Mecanum drive platforms.

Mecanum drives are rectangular with one wheel on each corner. Each wheel has rollers toed in 45 degrees toward the front or back. When looking at the wheels from the top, the roller axles should form an X across the robot. Each drive() function provides different inverse kinematic relations for a Mecanum drive robot.

Drive base diagram:

\_______/
\ |   | /
  |   |
/_|___|_\
/       \

Each drive() function provides different inverse kinematic relations for a Mecanum drive robot. Motor outputs for the right side are negated, so motor direction inversion by the user is usually unnecessary.

This library uses the NED axes convention (North-East-Down as external reference in the world frame): http://www.nuclearprojects.com/ins/images/axis_big.png.

The positive X axis points ahead, the positive Y axis points right, and the positive Z axis points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is positive.

Note

RobotDrive porting guide:

In MecanumDrive, the right side speed controllers are automatically inverted, while in RobotDrive, no speed controllers are automatically inverted.

driveCartesian() is equivalent to RobotDrive.mecanumDrive_Cartesian() if a deadband of 0 is used, and the ySpeed and gyroAngle values are inverted compared to RobotDrive (i.e driveCartesian(xSpeed, -ySpeed, zRotation, -gyroAngle).

drivePolar() is equivalent to RobotDrive.mecanumPolar() if a deadband of 0 is used.

Constructor for MecanumDrive.

If motors need to be inverted, do so beforehand. Motor outputs for the right side are negated, so motor direction inversion by the user is usually unnecessary

Parameters:
  • frontLeftMotor – Front Left Motor
  • rearLeftMotor – Rear Left Motor
  • frontRightMotor – Front Right Motor
  • rearRightMotor – Rear Right Motor
driveCartesian(ySpeed, xSpeed, zRotation, gyroAngle=0.0)[source]

Drive method for Mecanum platform.

Angles are measured clockwise from the positive X axis. The robot’s speed is independent from its angle or rotation rate.

Parameters:
  • ySpeed – The robot’s speed along the Y axis [-1.0..1.0]. Right is positive.
  • xSpeed – The robot’s speed along the X axis [-1.0..1.0]. Forward is positive.
  • zRotation – The robot’s rotation rate around the Z axis [-1.0..1.0]. Clockwise is positive.
  • gyroAngle – The current angle reading from the gyro in degrees around the Z axis. Use this to implement field-oriented controls.
drivePolar(magnitude, angle, zRotation)[source]

Drive method for Mecanum platform.

Angles are measured counter-clockwise from straight ahead. The speed at which the robot drives (translation) is independent from its angle or rotation rate.

Parameters:
  • magnitude – The robot’s speed at a given angle [-1.0..1.0]. Forward is positive.
  • angle – The angle around the Z axis at which the robot drives in degrees [-180..180].
  • zRotation – The robot’s rotation rate around the Z axis [-1.0..1.0]. Clockwise is positive.
getDescription()[source]
initSendable(builder)[source]
instances = 0
stopMotor()[source]