41 units::meters_per_second_t velocity)
const override;
44 units::meters_per_second_t speed)
const override;
49 units::volt_t m_maxVoltage;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:29
A class that enforces constraints on differential drive voltage expenditure based on the motor dynami...
Definition: DifferentialDriveVoltageConstraint.h:23
units::meters_per_second_t MaxVelocity(const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t velocity) const override
Returns the max velocity given the current pose and curvature.
DifferentialDriveVoltageConstraint(const SimpleMotorFeedforward< units::meter > &feedforward, DifferentialDriveKinematics kinematics, units::volt_t maxVoltage)
Creates a new DifferentialDriveVoltageConstraint.
MinMax MinMaxAcceleration(const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t speed) const override
Returns the minimum and maximum allowable acceleration for the trajectory given pose,...
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition: TrajectoryConstraint.h:22
Definition: AprilTagPoseEstimator.h:15
Represents a minimum and maximum acceleration.
Definition: TrajectoryConstraint.h:37