13#include "wpi/units/angle.hpp"
103 std::function<
void(
double)> rearLeftMotor,
104 std::function<
void(
double)> frontRightMotor,
105 std::function<
void(
double)> rearRightMotor);
162 double xVelocity,
double yVelocity,
double zRotation,
171 std::function<void(
double)> m_frontLeftMotor;
172 std::function<void(
double)> m_rearLeftMotor;
173 std::function<void(
double)> m_frontRightMotor;
174 std::function<void(
double)> m_rearRightMotor;
177 double m_frontLeftOutput = 0.0;
178 double m_rearLeftOutput = 0.0;
179 double m_frontRightOutput = 0.0;
180 double m_rearRightOutput = 0.0;
182 bool reported =
false;
void DrivePolar(double magnitude, wpi::math::Rotation2d angle, double zRotation)
Drive method for Mecanum platform.
std::string GetDescription() const override
Returns a description to print when an error occurs.
void StopMotor() override
Called to stop the motor when the timeout expires.
~MecanumDrive() override=default
WPI_IGNORE_DEPRECATED MecanumDrive(MotorController &frontLeftMotor, MotorController &rearLeftMotor, MotorController &frontRightMotor, MotorController &rearRightMotor)
Construct a MecanumDrive.
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(MecanumDrive &&)=default
static WheelVelocities DriveCartesianIK(double xVelocity, double yVelocity, double zRotation, wpi::math::Rotation2d gyroAngle=0_rad)
Cartesian inverse kinematics for Mecanum platform.
void DriveCartesian(double xVelocity, double yVelocity, double zRotation, wpi::math::Rotation2d gyroAngle=0_rad)
Drive method for Mecanum platform.
void InitSendable(wpi::util::SendableBuilder &builder) override
Initializes this Sendable object.
MecanumDrive & operator=(MecanumDrive &&)=default
Interface for motor controlling devices.
Definition MotorController.hpp:14
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.hpp:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.hpp:21
Interface for Sendable objects.
Definition Sendable.hpp:16
#define WPI_IGNORE_DEPRECATED
Definition deprecated.hpp:15
#define WPI_UNIGNORE_DEPRECATED
Definition deprecated.hpp:26
Definition CvSource.hpp:15
Wheel velocities for a mecanum drive.
Definition MecanumDrive.hpp:63
double frontRight
Front-right wheel velocity.
Definition MecanumDrive.hpp:67
double rearLeft
Rear-left wheel velocity.
Definition MecanumDrive.hpp:69
double frontLeft
Front-left wheel velocity.
Definition MecanumDrive.hpp:65
double rearRight
Rear-right wheel velocity.
Definition MecanumDrive.hpp:71