12 #include <wpi/raw_ostream.h> 14 #include "Drive/RobotDriveBase.h" 18 class SpeedController;
96 void DriveCartesian(
double ySpeed,
double xSpeed,
double zRotation,
97 double gyroAngle = 0.0);
112 void DrivePolar(
double magnitude,
double angle,
double zRotation);
130 void StopMotor()
override;
141 double m_rightSideInvertMultiplier = -1.0;
143 bool reported =
false;
This class implements an extremely fast bulk output stream that can only output to a stream...
Definition: raw_ostream.h:45
Interface for speed controlling devices.
Definition: SpeedController.h:17
Definition: Utility.cpp:119
A class for driving Mecanum drive platforms.
Definition: MecanumDrive.h:65
void DriveCartesian(double ySpeed, double xSpeed, double zRotation, double gyroAngle=0.0)
Drive method for Mecanum platform.
Definition: MecanumDrive.cpp:40
bool IsRightSideInverted() const
Gets if the power sent to the right side of the drivetrain is multipled by -1.
Definition: MecanumDrive.cpp:88
MecanumDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor, SpeedController &frontRightMotor, SpeedController &rearRightMotor)
Construct a MecanumDrive.
Definition: MecanumDrive.cpp:23
void SetRightSideInverted(bool rightSideInverted)
Sets if the power sent to the right side of the drivetrain should be multipled by -1...
Definition: MecanumDrive.cpp:92
Definition: SendableBuilder.h:23
void InitSendable(SendableBuilder &builder) override
Initializes this Sendable object.
Definition: MecanumDrive.cpp:108
Common base class for drive platforms.
Definition: RobotDriveBase.h:26
void DrivePolar(double magnitude, double angle, double zRotation)
Drive method for Mecanum platform.
Definition: MecanumDrive.cpp:76