WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
frc::RectangularRegionConstraint< Constraint > Class Template Reference

Enforces a particular constraint only within a rectangular region. More...

#include <frc/trajectory/constraint/RectangularRegionConstraint.h>

Inheritance diagram for frc::RectangularRegionConstraint< Constraint >:
frc::TrajectoryConstraint

Public Member Functions

constexpr RectangularRegionConstraint (const Translation2d &bottomLeftPoint, const Translation2d &topRightPoint, const Constraint &constraint)
 Constructs a new RectangularRegionConstraint.
 
constexpr RectangularRegionConstraint (const Rectangle2d &rectangle, const Constraint &constraint)
 Constructs a new RectangularRegionConstraint.
 
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.
 
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, curvature, and speed.
 
- Public Member Functions inherited from frc::TrajectoryConstraint
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
 

Detailed Description

template<std::derived_from< TrajectoryConstraint > Constraint>
class frc::RectangularRegionConstraint< Constraint >

Enforces a particular constraint only within a rectangular region.

Constructor & Destructor Documentation

◆ RectangularRegionConstraint() [1/2]

template<std::derived_from< TrajectoryConstraint > Constraint>
frc::RectangularRegionConstraint< Constraint >::RectangularRegionConstraint ( const Translation2d & bottomLeftPoint,
const Translation2d & topRightPoint,
const Constraint & constraint )
inlineconstexpr

Constructs a new RectangularRegionConstraint.

Parameters
bottomLeftPointThe bottom left point of the rectangular region in which to enforce the constraint.
topRightPointThe top right point of the rectangular region in which to enforce the constraint.
constraintThe constraint to enforce when the robot is within the region.
Deprecated
Use constructor taking Rectangle2d instead.

◆ RectangularRegionConstraint() [2/2]

template<std::derived_from< TrajectoryConstraint > Constraint>
frc::RectangularRegionConstraint< Constraint >::RectangularRegionConstraint ( const Rectangle2d & rectangle,
const Constraint & constraint )
inlineconstexpr

Constructs a new RectangularRegionConstraint.

Parameters
rectangleThe rectangular region in which to enforce the constraint.
constraintThe constraint to enforce when the robot is within the region.

Member Function Documentation

◆ MaxVelocity()

template<std::derived_from< TrajectoryConstraint > Constraint>
units::meters_per_second_t frc::RectangularRegionConstraint< Constraint >::MaxVelocity ( const Pose2d & pose,
units::curvature_t curvature,
units::meters_per_second_t velocity ) const
inlineconstexproverridevirtual

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.

Implements frc::TrajectoryConstraint.

◆ MinMaxAcceleration()

template<std::derived_from< TrajectoryConstraint > Constraint>
MinMax frc::RectangularRegionConstraint< Constraint >::MinMaxAcceleration ( const Pose2d & pose,
units::curvature_t curvature,
units::meters_per_second_t speed ) const
inlineconstexproverridevirtual

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

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

Implements frc::TrajectoryConstraint.


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