149 bool reported =
false;
A class for driving Mecanum drive platforms.
Definition: MecanumDrive.h:58
MecanumDrive(MotorController &frontLeftMotor, MotorController &rearLeftMotor, MotorController &frontRightMotor, MotorController &rearRightMotor)
Construct a MecanumDrive.
MecanumDrive & operator=(MecanumDrive &&)=default
void StopMotor() override
void DrivePolar(double magnitude, Rotation2d angle, double zRotation)
Drive method for Mecanum platform.
MecanumDrive(MecanumDrive &&)=default
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
static WheelSpeeds DriveCartesianIK(double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle=0_rad)
Cartesian inverse kinematics for Mecanum platform.
std::string GetDescription() const override
The return value from this method is printed out when an error occurs.
~MecanumDrive() override=default
void DriveCartesian(double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle=0_rad)
Drive method for Mecanum platform.
Interface for motor controlling devices.
Definition: MotorController.h:14
Common base class for drive platforms.
Definition: RobotDriveBase.h:20
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Definition: SendableBuilder.h:18
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagFieldLayout.h:22
Wheel speeds for a mecanum drive.
Definition: MecanumDrive.h:65
double rearRight
Definition: MecanumDrive.h:69
double frontRight
Definition: MecanumDrive.h:67
double frontLeft
Definition: MecanumDrive.h:66
double rearLeft
Definition: MecanumDrive.h:68