10 #include <wpi/raw_ostream.h> 12 #include "Drive/RobotDriveBase.h" 16 class SpeedController;
101 static constexpr
double kDefaultQuickStopThreshold = 0.2;
102 static constexpr
double kDefaultQuickStopAlpha = 0.1;
129 void ArcadeDrive(
double xSpeed,
double zRotation,
bool squaredInputs =
true);
146 void CurvatureDrive(
double xSpeed,
double zRotation,
bool isQuickTurn);
157 void TankDrive(
double leftSpeed,
double rightSpeed,
158 bool squaredInputs =
true);
206 void StopMotor()
override;
215 double m_quickStopThreshold = kDefaultQuickStopThreshold;
216 double m_quickStopAlpha = kDefaultQuickStopAlpha;
217 double m_quickStopAccumulator = 0.0;
218 double m_rightSideInvertMultiplier = -1.0;
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
void TankDrive(double leftSpeed, double rightSpeed, bool squaredInputs=true)
Tank drive method for differential drive platform.
Definition: DifferentialDrive.cpp:158
A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base...
Definition: DifferentialDrive.h:99
void InitSendable(SendableBuilder &builder) override
Initializes this Sendable object.
Definition: DifferentialDrive.cpp:212
void SetRightSideInverted(bool rightSideInverted)
Sets if the power sent to the right side of the drivetrain should be multipled by -1...
Definition: DifferentialDrive.cpp:198
bool IsRightSideInverted() const
Gets if the power sent to the right side of the drivetrain is multipled by -1.
Definition: DifferentialDrive.cpp:194
void SetQuickStopAlpha(double alpha)
Sets the low-pass filter gain for QuickStop in curvature drive.
Definition: DifferentialDrive.cpp:190
void CurvatureDrive(double xSpeed, double zRotation, bool isQuickTurn)
Curvature drive method for differential drive platform.
Definition: DifferentialDrive.cpp:85
void SetQuickStopThreshold(double threshold)
Sets the QuickStop speed threshold in curvature drive.
Definition: DifferentialDrive.cpp:186
Definition: SendableBuilder.h:23
DifferentialDrive(SpeedController &leftMotor, SpeedController &rightMotor)
Construct a DifferentialDrive.
Definition: DifferentialDrive.cpp:20
void ArcadeDrive(double xSpeed, double zRotation, bool squaredInputs=true)
Arcade drive method for differential drive platform.
Definition: DifferentialDrive.cpp:30
Common base class for drive platforms.
Definition: RobotDriveBase.h:26