MecanumDrive

class wpilib.drive.MecanumDrive(frontLeftMotor: wpilib.interfaces.SpeedController, rearLeftMotor: wpilib.interfaces.SpeedController, frontRightMotor: wpilib.interfaces.SpeedController, rearRightMotor: wpilib.interfaces.SpeedController)

Bases: wpilib.drive.RobotDriveBase, wpilib.Sendable

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.

Drive base diagram:

\\_______/
\\ |   | /
  |   |
/_|___|_\ * /       \ * </pre>

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 to the right,
and the positive Z axis points down. Rotations follow the right-hand rule, so
clockwise rotation around the Z axis is positive.

Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
so that the full range is still used. This deadband value can be changed
with SetDeadband().

RobotDrive porting guide:
<br>In MecanumDrive, the right side speed controllers are automatically
inverted, while in RobotDrive, no speed controllers are automatically
inverted.
<br>DriveCartesian(double, double, double, double) is equivalent to
RobotDrive#MecanumDrive_Cartesian(double, double, double, double)
if a deadband of 0 is used, and the ySpeed and gyroAngle values are inverted
compared to RobotDrive (eg DriveCartesian(xSpeed, -ySpeed, zRotation,
-gyroAngle).
<br>DrivePolar(double, double, double) is equivalent to
RobotDrive#MecanumDrive_Polar(double, double, double) if a
deadband of 0 is used.

Construct a MecanumDrive.

If a motor needs to be inverted, do so before passing it in.

driveCartesian(ySpeed: float, xSpeed: float, zRotation: float, gyroAngle: float = 0.0)None

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: float, angle: float, zRotation: float)None

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
  • 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()str
initSendable(builder: wpilib.SendableBuilder)None
isRightSideInverted()bool

Gets if the power sent to the right side of the drivetrain is multiplied by -1.

Returns

true if the right side is inverted

setRightSideInverted(rightSideInverted: bool)None

Sets if the power sent to the right side of the drivetrain should be multiplied by -1.

Parameters

rightSideInverted – true if right side power should be multiplied by -1

stopMotor()None