27 units::meters_per_second_t maxSpeed)
28 : m_kinematics(
std::move(kinematics)), m_maxSpeed(maxSpeed) {}
32 units::meters_per_second_t velocity)
const override {
34 m_kinematics.ToWheelSpeeds({velocity, 0_mps, velocity * curvature});
35 wheelSpeeds.Desaturate(m_maxSpeed);
37 return m_kinematics.ToChassisSpeeds(wheelSpeeds).vx;
42 units::meters_per_second_t speed)
const override {
48 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:23
constexpr DifferentialDriveKinematicsConstraint(DifferentialDriveKinematics kinematics, units::meters_per_second_t maxSpeed)
Definition DifferentialDriveKinematicsConstraint.h:25
constexpr 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,...
Definition DifferentialDriveKinematicsConstraint.h:40
constexpr 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.
Definition DifferentialDriveKinematicsConstraint.h:30
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.h:31
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition TrajectoryConstraint.h:21
Implement std::hash so that hash_code can be used in STL containers.
Definition PointerIntPair.h:280
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.h:37