10 #include <wpi/raw_ostream.h>
12 #include "frc/drive/RobotDriveBase.h"
13 #include "frc/smartdashboard/Sendable.h"
14 #include "frc/smartdashboard/SendableHelper.h"
18 class SpeedController;
105 static constexpr
double kDefaultQuickStopThreshold = 0.2;
106 static constexpr
double kDefaultQuickStopAlpha = 0.1;
133 void ArcadeDrive(
double xSpeed,
double zRotation,
bool squareInputs =
true);
150 void CurvatureDrive(
double xSpeed,
double zRotation,
bool isQuickTurn);
161 void TankDrive(
double leftSpeed,
double rightSpeed,
bool squareInputs =
true);
209 void StopMotor()
override;
218 double m_quickStopThreshold = kDefaultQuickStopThreshold;
219 double m_quickStopAlpha = kDefaultQuickStopAlpha;
220 double m_quickStopAccumulator = 0.0;
221 double m_rightSideInvertMultiplier = -1.0;
DifferentialDrive(SpeedController &leftMotor, SpeedController &rightMotor)
Construct a DifferentialDrive.
Common base class for drive platforms.
Definition: RobotDriveBase.h:24
void ArcadeDrive(double xSpeed, double zRotation, bool squareInputs=true)
Arcade drive method for differential drive platform.
void SetQuickStopAlpha(double alpha)
Sets the low-pass filter gain for QuickStop in curvature drive.
bool IsRightSideInverted() const
Gets if the power sent to the right side of the drivetrain is multipled by -1.
A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base...
Definition: DifferentialDrive.h:101
void TankDrive(double leftSpeed, double rightSpeed, bool squareInputs=true)
Tank drive method for differential drive platform.
void SetRightSideInverted(bool rightSideInverted)
Sets if the power sent to the right side of the drivetrain should be multipled by -1.
void SetQuickStopThreshold(double threshold)
Sets the QuickStop speed threshold in curvature drive.
void InitSendable(SendableBuilder &builder) override
Initializes this Sendable object.
Interface for Sendable objects.
Definition: Sendable.h:17
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16
Interface for speed controlling devices.
Definition: SpeedController.h:19
This class implements an extremely fast bulk output stream that can only output to a stream.
Definition: raw_ostream.h:47
void CurvatureDrive(double xSpeed, double zRotation, bool isQuickTurn)
Curvature drive method for differential drive platform.
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:28
Definition: SendableBuilder.h:23