MecanumDrive

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

Bases: RobotDriveBase, Sendable

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: collections.abc.Callable[[typing.SupportsFloat | typing.SupportsIndex], None], rearLeftMotor: collections.abc.Callable[[typing.SupportsFloat | typing.SupportsIndex], None], frontRightMotor: collections.abc.Callable[[typing.SupportsFloat | typing.SupportsIndex], None], rearRightMotor: collections.abc.Callable[[typing.SupportsFloat | typing.SupportsIndex], 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].

driveCartesian(xSpeed: SupportsFloat | SupportsIndex, ySpeed: SupportsFloat | SupportsIndex, zRotation: SupportsFloat | SupportsIndex, 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: SupportsFloat | SupportsIndex, ySpeed: SupportsFloat | SupportsIndex, zRotation: SupportsFloat | SupportsIndex, 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: SupportsFloat | SupportsIndex, angle: wpimath.geometry._geometry.Rotation2d, zRotation: SupportsFloat | SupportsIndex) 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