WPILibC++ 2024.3.2
|
A class that enforces constraints on differential drive voltage expenditure based on the motor dynamics and the drive kinematics. More...
#include <frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h>
Public Member Functions | |
DifferentialDriveVoltageConstraint (const SimpleMotorFeedforward< units::meter > &feedforward, DifferentialDriveKinematics kinematics, units::volt_t maxVoltage) | |
Creates a new DifferentialDriveVoltageConstraint. More... | |
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. More... | |
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, curvature, and speed. More... | |
Public Member Functions inherited from frc::TrajectoryConstraint | |
TrajectoryConstraint ()=default | |
TrajectoryConstraint (const TrajectoryConstraint &)=default | |
TrajectoryConstraint & | operator= (const TrajectoryConstraint &)=default |
TrajectoryConstraint (TrajectoryConstraint &&)=default | |
TrajectoryConstraint & | operator= (TrajectoryConstraint &&)=default |
virtual | ~TrajectoryConstraint ()=default |
virtual units::meters_per_second_t | MaxVelocity (const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t velocity) const =0 |
Returns the max velocity given the current pose and curvature. More... | |
virtual MinMax | MinMaxAcceleration (const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t speed) const =0 |
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed. More... | |
A class that enforces constraints on differential drive voltage expenditure based on the motor dynamics and the drive kinematics.
Ensures that the acceleration of any wheel of the robot while following the trajectory is never higher than what can be achieved with the given maximum voltage.
frc::DifferentialDriveVoltageConstraint::DifferentialDriveVoltageConstraint | ( | const SimpleMotorFeedforward< units::meter > & | feedforward, |
DifferentialDriveKinematics | kinematics, | ||
units::volt_t | maxVoltage | ||
) |
Creates a new DifferentialDriveVoltageConstraint.
feedforward | A feedforward component describing the behavior of the drive. |
kinematics | A kinematics component describing the drive geometry. |
maxVoltage | The maximum voltage available to the motors while following the path. Should be somewhat less than the nominal battery voltage (12V) to account for "voltage sag" due to current draw. |
|
overridevirtual |
Returns the max velocity given the current pose and curvature.
pose | The pose at the current point in the trajectory. |
curvature | The curvature at the current point in the trajectory. |
velocity | The velocity at the current point in the trajectory before constraints are applied. |
Implements frc::TrajectoryConstraint.
|
overridevirtual |
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
pose | The pose at the current point in the trajectory. |
curvature | The curvature at the current point in the trajectory. |
speed | The speed at the current point in the trajectory. |
Implements frc::TrajectoryConstraint.