WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
wpi::math::TrajectoryConstraint Class Referenceabstract

An interface for defining user-defined velocity and acceleration constraints while generating trajectories. More...

#include <wpi/math/trajectory/constraint/TrajectoryConstraint.hpp>

Inheritance diagram for wpi::math::TrajectoryConstraint:
wpi::math::CentripetalAccelerationConstraint wpi::math::DifferentialDriveKinematicsConstraint wpi::math::DifferentialDriveVoltageConstraint wpi::math::EllipticalRegionConstraint< Constraint > wpi::math::MaxVelocityConstraint wpi::math::MecanumDriveKinematicsConstraint wpi::math::RectangularRegionConstraint< Constraint > wpi::math::SwerveDriveKinematicsConstraint< NumModules >

Classes

struct  MinMax
 Represents a minimum and maximum acceleration. More...

Public Member Functions

constexpr TrajectoryConstraint ()=default
constexpr TrajectoryConstraint (const TrajectoryConstraint &)=default
constexpr TrajectoryConstraintoperator= (const TrajectoryConstraint &)=default
constexpr TrajectoryConstraint (TrajectoryConstraint &&)=default
constexpr TrajectoryConstraintoperator= (TrajectoryConstraint &&)=default
virtual constexpr ~TrajectoryConstraint ()=default
virtual constexpr wpi::units::meters_per_second_t MaxVelocity (const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const =0
 Returns the max velocity given the current pose and curvature.
virtual constexpr MinMax MinMaxAcceleration (const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const =0
 Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity.

Detailed Description

An interface for defining user-defined velocity and acceleration constraints while generating trajectories.

Constructor & Destructor Documentation

◆ TrajectoryConstraint() [1/3]

wpi::math::TrajectoryConstraint::TrajectoryConstraint ( )
constexprdefault

◆ TrajectoryConstraint() [2/3]

wpi::math::TrajectoryConstraint::TrajectoryConstraint ( const TrajectoryConstraint & )
constexprdefault

◆ TrajectoryConstraint() [3/3]

wpi::math::TrajectoryConstraint::TrajectoryConstraint ( TrajectoryConstraint && )
constexprdefault

◆ ~TrajectoryConstraint()

virtual constexpr wpi::math::TrajectoryConstraint::~TrajectoryConstraint ( )
constexprvirtualdefault

Member Function Documentation

◆ MaxVelocity()

virtual constexpr wpi::units::meters_per_second_t wpi::math::TrajectoryConstraint::MaxVelocity ( const Pose2d & pose,
wpi::units::curvature_t curvature,
wpi::units::meters_per_second_t velocity ) const
constexprpure virtual

Returns the max velocity given the current pose and curvature.

Parameters
poseThe pose at the current point in the trajectory.
curvatureThe curvature at the current point in the trajectory.
velocityThe velocity at the current point in the trajectory before constraints are applied.
Returns
The absolute maximum velocity.

Implemented in wpi::math::CentripetalAccelerationConstraint, wpi::math::DifferentialDriveKinematicsConstraint, wpi::math::DifferentialDriveVoltageConstraint, wpi::math::EllipticalRegionConstraint< Constraint >, wpi::math::MaxVelocityConstraint, wpi::math::MecanumDriveKinematicsConstraint, wpi::math::RectangularRegionConstraint< Constraint >, and wpi::math::SwerveDriveKinematicsConstraint< NumModules >.

◆ MinMaxAcceleration()

virtual constexpr MinMax wpi::math::TrajectoryConstraint::MinMaxAcceleration ( const Pose2d & pose,
wpi::units::curvature_t curvature,
wpi::units::meters_per_second_t velocity ) const
constexprpure virtual

Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity.

Parameters
poseThe pose at the current point in the trajectory.
curvatureThe curvature at the current point in the trajectory.
velocityThe velocity at the current point in the trajectory.
Returns
The min and max acceleration bounds.

Implemented in wpi::math::CentripetalAccelerationConstraint, wpi::math::DifferentialDriveKinematicsConstraint, wpi::math::DifferentialDriveVoltageConstraint, wpi::math::EllipticalRegionConstraint< Constraint >, wpi::math::MaxVelocityConstraint, wpi::math::MecanumDriveKinematicsConstraint, wpi::math::RectangularRegionConstraint< Constraint >, and wpi::math::SwerveDriveKinematicsConstraint< NumModules >.

◆ operator=() [1/2]

TrajectoryConstraint & wpi::math::TrajectoryConstraint::operator= ( const TrajectoryConstraint & )
constexprdefault

◆ operator=() [2/2]

TrajectoryConstraint & wpi::math::TrajectoryConstraint::operator= ( TrajectoryConstraint && )
constexprdefault

The documentation for this class was generated from the following file: