Class Path.PathConstraints
- Enclosing class:
- Path
This class allows setting velocity and acceleration limits that apply only to a specific path. Constraints can be set as single values (applying to the entire path) or as ranged constraints (applying to specific sections).
Uses a fluent API for easy configuration:
PathConstraints constraints = new PathConstraints()
.setMaxVelocityMetersPerSec(3.0)
.setMaxAccelerationMetersPerSec2(2.0)
.setEndTranslationToleranceMeters(0.05);
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptioncopy()Creates a deep copy of these constraints.setEndRotationToleranceDeg(double value) Sets the rotation tolerance for path completion.setEndTranslationToleranceMeters(double value) Sets the translation tolerance for path completion.setMaxAccelerationDegPerSec2(double value) Sets a global maximum rotational acceleration for the entire path.setMaxAccelerationDegPerSec2(Path.RangedConstraint... constraints) Sets ranged maximum rotational acceleration constraints.setMaxAccelerationMetersPerSec2(double value) Sets a global maximum translational acceleration for the entire path.setMaxAccelerationMetersPerSec2(Path.RangedConstraint... constraints) Sets ranged maximum translational acceleration constraints.setMaxVelocityDegPerSec(double value) Sets a global maximum rotational velocity for the entire path.setMaxVelocityDegPerSec(Path.RangedConstraint... constraints) Sets ranged maximum rotational velocity constraints.setMaxVelocityMetersPerSec(double value) Sets a global maximum translational velocity for the entire path.setMaxVelocityMetersPerSec(Path.RangedConstraint... constraints) Sets ranged maximum translational velocity constraints.setMinVelocityDegPerSec(double value) Sets a global minimum rotational velocity baseline for the entire path.setMinVelocityDegPerSec(Path.RangedConstraint... constraints) Sets ranged minimum rotational velocity baseline constraints.setMinVelocityMetersPerSec(double value) Sets a global minimum translational velocity baseline for the entire path.setMinVelocityMetersPerSec(Path.RangedConstraint... constraints) Sets ranged minimum translational velocity baseline constraints.
-
Constructor Details
-
PathConstraints
public PathConstraints()Creates an empty PathConstraints with no overrides set.
-
-
Method Details
-
setMaxVelocityMetersPerSec
Sets a global maximum translational velocity for the entire path.- Parameters:
value- The maximum velocity in meters per second- Returns:
- This PathConstraints for chaining
-
setMaxVelocityMetersPerSec
Sets ranged maximum translational velocity constraints.- Parameters:
constraints- The ranged constraints to apply- Returns:
- This PathConstraints for chaining
-
setMaxAccelerationMetersPerSec2
Sets a global maximum translational acceleration for the entire path.- Parameters:
value- The maximum acceleration in meters per second squared- Returns:
- This PathConstraints for chaining
-
setMaxAccelerationMetersPerSec2
Sets ranged maximum translational acceleration constraints.- Parameters:
constraints- The ranged constraints to apply- Returns:
- This PathConstraints for chaining
-
setMaxVelocityDegPerSec
Sets a global maximum rotational velocity for the entire path.- Parameters:
value- The maximum angular velocity in degrees per second- Returns:
- This PathConstraints for chaining
-
setMaxVelocityDegPerSec
Sets ranged maximum rotational velocity constraints.- Parameters:
constraints- The ranged constraints to apply- Returns:
- This PathConstraints for chaining
-
setMaxAccelerationDegPerSec2
Sets a global maximum rotational acceleration for the entire path.- Parameters:
value- The maximum angular acceleration in degrees per second squared- Returns:
- This PathConstraints for chaining
-
setMaxAccelerationDegPerSec2
Sets ranged maximum rotational acceleration constraints.- Parameters:
constraints- The ranged constraints to apply- Returns:
- This PathConstraints for chaining
-
setMinVelocityMetersPerSec
Sets a global minimum translational velocity baseline for the entire path.This is an advanced feature. Minimum output baselines can help overcome static friction, but values that are too high may cause overshoot or controller oscillation near targets.
- Parameters:
value- The minimum velocity in meters per second- Returns:
- This PathConstraints for chaining
-
setMinVelocityMetersPerSec
Sets ranged minimum translational velocity baseline constraints.This is an advanced feature. Minimum output baselines can help overcome static friction, but values that are too high may cause overshoot or controller oscillation near targets.
- Parameters:
constraints- The ranged constraints to apply- Returns:
- This PathConstraints for chaining
-
setMinVelocityDegPerSec
Sets a global minimum rotational velocity baseline for the entire path.This is an advanced feature. Minimum output baselines can help overcome static friction, but values that are too high may cause overshoot or controller oscillation near targets.
- Parameters:
value- The minimum angular velocity in degrees per second- Returns:
- This PathConstraints for chaining
-
setMinVelocityDegPerSec
Sets ranged minimum rotational velocity baseline constraints.This is an advanced feature. Minimum output baselines can help overcome static friction, but values that are too high may cause overshoot or controller oscillation near targets.
- Parameters:
constraints- The ranged constraints to apply- Returns:
- This PathConstraints for chaining
-
setEndTranslationToleranceMeters
Sets the translation tolerance for path completion.- Parameters:
value- The tolerance in meters- Returns:
- This PathConstraints for chaining
-
setEndRotationToleranceDeg
Sets the rotation tolerance for path completion.- Parameters:
value- The tolerance in degrees- Returns:
- This PathConstraints for chaining
-
getMaxVelocityMetersPerSec
- Returns:
- Optional ranged constraints for maximum translational velocity
-
getMaxAccelerationMetersPerSec2
- Returns:
- Optional ranged constraints for maximum translational acceleration
-
getMaxVelocityDegPerSec
- Returns:
- Optional ranged constraints for maximum rotational velocity
-
getMaxAccelerationDegPerSec2
- Returns:
- Optional ranged constraints for maximum rotational acceleration
-
getMinVelocityMetersPerSec
- Returns:
- Optional ranged constraints for minimum translational velocity
-
getMinVelocityDegPerSec
- Returns:
- Optional ranged constraints for minimum rotational velocity
-
getEndTranslationToleranceMeters
- Returns:
- Optional end translation tolerance override
-
getEndRotationToleranceDeg
- Returns:
- Optional end rotation tolerance override
-
copy
Creates a deep copy of these constraints.- Returns:
- A new PathConstraints with the same values
-