TrajectoryConstraint
- class wpimath.trajectory.constraint.TrajectoryConstraint
Bases:
pybind11_object
An interface for defining user-defined velocity and acceleration constraints while generating trajectories.
- class MinMax
Bases:
pybind11_object
Represents a minimum and maximum acceleration.
- property maxAcceleration
- property minAcceleration
- maxVelocity(pose: wpimath.geometry._geometry.Pose2d, curvature: radians_per_meter, velocity: meters_per_second) meters_per_second
Returns the max velocity given the current pose and curvature.
- Parameters:
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.
- Returns:
The absolute maximum velocity.
- minMaxAcceleration(pose: wpimath.geometry._geometry.Pose2d, curvature: radians_per_meter, speed: meters_per_second) wpimath._controls._controls.constraint.TrajectoryConstraint.MinMax
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
- Parameters:
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.
- Returns:
The min and max acceleration bounds.