MecanumDrive
- class wpilib.MecanumDrive(*args, **kwargs)
Bases:
RobotDriveBase,SendableOverloaded function.
__init__(self: wpilib._wpilib.MecanumDrive, frontLeftMotor: wpilib._wpilib.MotorController, rearLeftMotor: wpilib._wpilib.MotorController, frontRightMotor: wpilib._wpilib.MotorController, rearRightMotor: wpilib._wpilib.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.
__init__(self: wpilib._wpilib.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 WheelVelocities
Bases:
pybind11_objectWheel velocities for a mecanum drive.
Uses normalized voltage [-1.0..1.0].
- driveCartesian(xVelocity: SupportsFloat | SupportsIndex, yVelocity: SupportsFloat | SupportsIndex, zRotation: SupportsFloat | SupportsIndex, gyroAngle: wpimath._wpimath.Rotation2d = Rotation2d(0.000000)) None
Drive method for Mecanum platform.
Angles are measured counterclockwise from the positive X axis. The robot’s velocity is independent from its angle or rotation rate.
- Parameters:
xVelocity – The robot’s velocity along the X axis [-1.0..1.0]. Forward is positive.
yVelocity – The robot’s velocity 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(xVelocity: SupportsFloat | SupportsIndex, yVelocity: SupportsFloat | SupportsIndex, zRotation: SupportsFloat | SupportsIndex, gyroAngle: wpimath._wpimath.Rotation2d = Rotation2d(0.000000)) wpilib._wpilib.MecanumDrive.WheelVelocities
Cartesian inverse kinematics for Mecanum platform.
Angles are measured counterclockwise from the positive X axis. The robot’s velocity is independent from its angle or rotation rate.
- Parameters:
xVelocity – The robot’s velocity along the X axis [-1.0..1.0]. Forward is positive.
yVelocity – The robot’s velocity 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 velocities [-1.0..1.0].
- drivePolar(magnitude: SupportsFloat | SupportsIndex, angle: wpimath._wpimath.Rotation2d, zRotation: SupportsFloat | SupportsIndex) None
Drive method for Mecanum platform.
Angles are measured counterclockwise from the positive X axis. The robot’s velocity is independent from its angle or rotation rate.
- Parameters:
magnitude – The robot’s velocity 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