10 #include <units/units.h>
12 #include "frc/controller/SimpleMotorFeedforward.h"
13 #include "frc/kinematics/DifferentialDriveKinematics.h"
14 #include "frc/trajectory/constraint/TrajectoryConstraint.h"
41 units::meters_per_second_t velocity)
override;
44 units::meters_per_second_t speed)
override;
49 units::volt_t m_maxVoltage;
units::meters_per_second_t MaxVelocity(const Pose2d &pose, curvature_t curvature, units::meters_per_second_t velocity) override
Returns the max velocity given the current pose and curvature.
Represents a minimum and maximum acceleration.
Definition: TrajectoryConstraint.h:37
MinMax MinMaxAcceleration(const Pose2d &pose, curvature_t curvature, units::meters_per_second_t speed) override
Returns the minimum and maximum allowable acceleration for the trajectory given pose,...
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition: TrajectoryConstraint.h:22
Represents a 2d pose containing translational and rotational elements.
Definition: Pose2d.h:23
units::unit_t< units::compound_unit< units::radian, units::inverse< units::meter > >> curvature_t
Define a unit for curvature.
Definition: Trajectory.h:27
DifferentialDriveVoltageConstraint(SimpleMotorFeedforward< units::meter > feedforward, DifferentialDriveKinematics kinematics, units::volt_t maxVoltage)
Creates a new DifferentialDriveVoltageConstraint.
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:25
A class that enforces constraints on differential drive voltage expenditure based on the motor dynami...
Definition: DifferentialDriveVoltageConstraint.h:23
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16