107 std::function<
void(
double)> rearLeftMotor,
108 std::function<
void(
double)> frontRightMotor,
109 std::function<
void(
double)> rearRightMotor);
174 std::function<void(
double)> m_frontLeftMotor;
175 std::function<void(
double)> m_rearLeftMotor;
176 std::function<void(
double)> m_frontRightMotor;
177 std::function<void(
double)> m_rearRightMotor;
180 double m_frontLeftOutput = 0.0;
181 double m_rearLeftOutput = 0.0;
182 double m_frontRightOutput = 0.0;
183 double m_rearRightOutput = 0.0;
185 bool reported =
false;
A class for driving Mecanum drive platforms.
Definition: MecanumDrive.h:60
WPI_UNIGNORE_DEPRECATED MecanumDrive(std::function< void(double)> frontLeftMotor, std::function< void(double)> rearLeftMotor, std::function< void(double)> frontRightMotor, std::function< void(double)> rearRightMotor)
Construct a MecanumDrive.
MecanumDrive & operator=(MecanumDrive &&)=default
void StopMotor() override
Called to stop the motor when the timeout expires.
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.
WPI_IGNORE_DEPRECATED MecanumDrive(MotorController &frontLeftMotor, MotorController &rearLeftMotor, MotorController &frontRightMotor, MotorController &rearRightMotor)
Construct a MecanumDrive.
std::string GetDescription() const override
Returns a description to print 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:23
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
#define WPI_IGNORE_DEPRECATED
Definition: deprecated.h:20
#define WPI_UNIGNORE_DEPRECATED
Definition: deprecated.h:31
Definition: AprilTagPoseEstimator.h:15
Wheel speeds for a mecanum drive.
Definition: MecanumDrive.h:67
double rearRight
Rear-right wheel speed.
Definition: MecanumDrive.h:75
double frontRight
Front-right wheel speed.
Definition: MecanumDrive.h:71
double frontLeft
Front-left wheel speed.
Definition: MecanumDrive.h:69
double rearLeft
Rear-left wheel speed.
Definition: MecanumDrive.h:73