TrajectoryConstraint
- class wpimath.TrajectoryConstraint
Bases:
pybind11_objectAn interface for defining user-defined velocity and acceleration constraints while generating trajectories.
- class MinMax(*args, **kwargs)
Bases:
pybind11_objectRepresents a minimum and maximum acceleration.
Overloaded function.
__init__(self: wpimath._wpimath.TrajectoryConstraint.MinMax) -> None
__init__(self: wpimath._wpimath.TrajectoryConstraint.MinMax, minAcceleration: wpimath.units.meters_per_second_squared, maxAcceleration: wpimath.units.meters_per_second_squared) -> None
- maxVelocity(pose: wpimath._wpimath.Pose2d, curvature: wpimath.units.radians_per_meter, velocity: wpimath.units.meters_per_second) wpimath.units.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._wpimath.Pose2d, curvature: wpimath.units.radians_per_meter, velocity: wpimath.units.meters_per_second) wpimath._wpimath.TrajectoryConstraint.MinMax
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity.
- 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.
- Returns:
The min and max acceleration bounds.