MecanumDrive

class wpilib.drive.MecanumDrive(*args, **kwargs)

Bases: RobotDriveBase, 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:

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

Each Drive() function provides different inverse kinematic relations for a Mecanum drive robot.

This library uses the NWU axes convention (North-West-Up as external reference in the world frame). The positive X axis points ahead, the positive Y axis points to the left, and the positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation around the Z axis is positive.

Note: the axis conventions used in this class differ from DifferentialDrive. This may change in a future year’s WPILib release.

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().

MotorSafety is enabled by default. The DriveCartesian or DrivePolar methods should be called periodically to avoid Motor Safety timeouts.

Overloaded function.

  1. __init__(self: wpilib.drive._drive.MecanumDrive, frontLeftMotor: wpilib.interfaces._interfaces.MotorController, rearLeftMotor: wpilib.interfaces._interfaces.MotorController, frontRightMotor: wpilib.interfaces._interfaces.MotorController, rearRightMotor: wpilib.interfaces._interfaces.MotorController) -> None

Construct a MecanumDrive.

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

Parameters:
  • frontLeftMotor – Front-left motor.

  • rearLeftMotor – Rear-left motor.

  • frontRightMotor – Front-right motor.

  • rearRightMotor – Rear-right motor.

  1. __init__(self: wpilib.drive._drive.MecanumDrive, frontLeftMotor: Callable[[float], None], rearLeftMotor: Callable[[float], None], frontRightMotor: Callable[[float], None], rearRightMotor: Callable[[float], None]) -> None

Construct a MecanumDrive.

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

Parameters:
  • frontLeftMotor – Front-left motor setter.

  • rearLeftMotor – Rear-left motor setter.

  • frontRightMotor – Front-right motor setter.

  • rearRightMotor – Rear-right motor setter.

class WheelSpeeds

Bases: pybind11_object

Wheel speeds for a mecanum drive.

Uses normalized voltage [-1.0..1.0].

property frontLeft float

Front-left wheel speed.

property frontRight float

Front-right wheel speed.

property rearLeft float

Rear-left wheel speed.

property rearRight float

Rear-right wheel speed.

driveCartesian(xSpeed: float, ySpeed: float, zRotation: float, gyroAngle: wpimath.geometry._geometry.Rotation2d = Rotation2d(0.000000)) None

Drive method for Mecanum platform.

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

Parameters:
  • xSpeed – The robot’s speed along the X axis [-1.0..1.0]. Forward is positive.

  • ySpeed – The robot’s speed along the Y axis [-1.0..1.0]. Left is positive.

  • zRotation – The robot’s rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive.

  • gyroAngle – The gyro heading around the Z axis. Use this to implement field-oriented controls.

static driveCartesianIK(xSpeed: float, ySpeed: float, zRotation: float, gyroAngle: wpimath.geometry._geometry.Rotation2d = Rotation2d(0.000000)) wpilib.drive._drive.MecanumDrive.WheelSpeeds

Cartesian inverse kinematics for Mecanum platform.

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

Parameters:
  • xSpeed – The robot’s speed along the X axis [-1.0..1.0]. Forward is positive.

  • ySpeed – The robot’s speed along the Y axis [-1.0..1.0]. Left is positive.

  • zRotation – The robot’s rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive.

  • gyroAngle – The gyro heading around the Z axis. Use this to implement field-oriented controls.

Returns:

Wheel speeds [-1.0..1.0].

drivePolar(magnitude: float, angle: wpimath.geometry._geometry.Rotation2d, zRotation: float) None

Drive method for Mecanum platform.

Angles are measured counterclockwise 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.

  • zRotation – The robot’s rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive.

getDescription() str
initSendable(builder: wpiutil._wpiutil.SendableBuilder) None
stopMotor() None