25 units::meters_per_second_t maxSpeed);
29 units::meters_per_second_t velocity)
const override;
32 units::meters_per_second_t speed)
const override;
36 units::meters_per_second_t m_maxSpeed;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A class that enforces constraints on the differential drive kinematics.
Definition: DifferentialDriveKinematicsConstraint.h:21
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,...
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.
DifferentialDriveKinematicsConstraint(const DifferentialDriveKinematics &kinematics, units::meters_per_second_t maxSpeed)
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:25
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition: TrajectoryConstraint.h:22
Definition: AprilTagFieldLayout.h:22
Represents a minimum and maximum acceleration.
Definition: TrajectoryConstraint.h:37