![]() |
WPILibC++ 2027.0.0-alpha-4
|
A class that enforces constraints on the swerve drive kinematics. More...
#include <wpi/math/trajectory/constraint/SwerveDriveKinematicsConstraint.hpp>
Public Member Functions | |
| SwerveDriveKinematicsConstraint (const wpi::math::SwerveDriveKinematics< NumModules > &kinematics, wpi::units::meters_per_second_t maxVelocity) | |
| wpi::units::meters_per_second_t | MaxVelocity (const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const override |
| Returns the max velocity given the current pose and curvature. | |
| MinMax | MinMaxAcceleration (const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const override |
| Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity. | |
| Public Member Functions inherited from wpi::math::TrajectoryConstraint | |
| constexpr | TrajectoryConstraint ()=default |
| constexpr | TrajectoryConstraint (const TrajectoryConstraint &)=default |
| constexpr TrajectoryConstraint & | operator= (const TrajectoryConstraint &)=default |
| constexpr | TrajectoryConstraint (TrajectoryConstraint &&)=default |
| constexpr TrajectoryConstraint & | operator= (TrajectoryConstraint &&)=default |
| virtual constexpr | ~TrajectoryConstraint ()=default |
A class that enforces constraints on the swerve drive kinematics.
This can be used to ensure that the trajectory is constructed so that the commanded velocities of the wheels stay below a certain limit.
|
inline |
|
inlineoverridevirtual |
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 wpi::math::TrajectoryConstraint.
|
inlineoverridevirtual |
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity.
| 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. |
Implements wpi::math::TrajectoryConstraint.