Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allow unlimited global constraints #845

Merged
merged 6 commits into from
Oct 8, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file modified Writerside/images/global_constraints_tree.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
3 changes: 3 additions & 0 deletions Writerside/topics/gui-Editing-Paths-and-Autos.md
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,9 @@ Max Angular Acceleration
Use Default Constraints
: Ties these constraints to the default constraints in the settings menu.

Unlimited
: Use unlimited constraints for this path. If unlimited, the robot will move as fast as the torque output will allow.

### Ideal Starting State

The ideal starting state defines the state the robot should be at when starting the path. This will be used to
Expand Down
4 changes: 4 additions & 0 deletions Writerside/topics/gui-Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,10 @@ other configuration options.
These values will be used as the default global constraints when creating new paths. Updating these values will also
update the constraints of any paths set to use the defaults.

The default constraints do not support being unlimited, as a conscious decision should be made per-path to have
unlimited constraints. Running a path as fast as possible is not only dangerous, but can lead to the path following
controller falling behind.

Max Velocity
: Max linear velocity in meters per second.

Expand Down
12 changes: 9 additions & 3 deletions lib/path/path_constraints.dart
Original file line number Diff line number Diff line change
Expand Up @@ -3,26 +3,30 @@ class PathConstraints {
num maxAccelerationMPSSq;
num maxAngularVelocityDeg;
num maxAngularAccelerationDeg;
bool unlimited;

PathConstraints({
this.maxVelocityMPS = 3,
this.maxAccelerationMPSSq = 3,
this.maxAngularVelocityDeg = 540,
this.maxAngularAccelerationDeg = 720,
this.unlimited = false,
});

PathConstraints.fromJson(Map<String, dynamic> json)
: maxVelocityMPS = json['maxVelocity'] ?? 3,
maxAccelerationMPSSq = json['maxAcceleration'] ?? 3,
maxAngularVelocityDeg = json['maxAngularVelocity'] ?? 540,
maxAngularAccelerationDeg = json['maxAngularAcceleration'] ?? 720;
maxAngularAccelerationDeg = json['maxAngularAcceleration'] ?? 720,
unlimited = json['unlimited'] ?? false;

PathConstraints clone() {
return PathConstraints(
maxVelocityMPS: maxVelocityMPS,
maxAccelerationMPSSq: maxAccelerationMPSSq,
maxAngularVelocityDeg: maxAngularVelocityDeg,
maxAngularAccelerationDeg: maxAngularAccelerationDeg,
unlimited: unlimited,
);
}

Expand All @@ -32,6 +36,7 @@ class PathConstraints {
'maxAcceleration': maxAccelerationMPSSq,
'maxAngularVelocity': maxAngularVelocityDeg,
'maxAngularAcceleration': maxAngularAccelerationDeg,
'unlimited': unlimited,
};
}

Expand All @@ -42,9 +47,10 @@ class PathConstraints {
other.maxVelocityMPS == maxVelocityMPS &&
other.maxAccelerationMPSSq == maxAccelerationMPSSq &&
other.maxAngularVelocityDeg == maxAngularVelocityDeg &&
other.maxAngularAccelerationDeg == other.maxAngularAccelerationDeg;
other.maxAngularAccelerationDeg == other.maxAngularAccelerationDeg &&
other.unlimited == unlimited;

@override
int get hashCode => Object.hash(maxVelocityMPS, maxAccelerationMPSSq,
maxAngularVelocityDeg, maxAngularAccelerationDeg);
maxAngularVelocityDeg, maxAngularAccelerationDeg, unlimited);
}
12 changes: 12 additions & 0 deletions lib/path/pathplanner_path.dart
Original file line number Diff line number Diff line change
Expand Up @@ -364,6 +364,18 @@
return z.constraints;
}
}

// Check if the constraints should be unlimited
if (globalConstraints.unlimited) {
return PathConstraints(

Check warning on line 370 in lib/path/pathplanner_path.dart

View check run for this annotation

Codecov / codecov/patch

lib/path/pathplanner_path.dart#L370

Added line #L370 was not covered by tests
maxVelocityMPS: double.infinity,
maxAccelerationMPSSq: double.infinity,
maxAngularVelocityDeg: double.infinity,
maxAngularAccelerationDeg: double.infinity,
unlimited: true,
);
}

return globalConstraints;
}

Expand Down
4 changes: 3 additions & 1 deletion lib/widgets/editor/tree_widgets/constraint_zones_tree.dart
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,10 @@ class _ConstraintZonesTreeState extends State<ConstraintZonesTree> {
widget.undoStack.add(Change(
PathPlannerPath.cloneConstraintZones(constraintZones),
() {
final constraints = widget.path.globalConstraints.clone();
constraints.unlimited = false;
constraintZones.add(ConstraintsZone.defaultZone(
constraints: widget.path.globalConstraints.clone(),
constraints: constraints,
));
widget.onPathChangedNoSim?.call();
},
Expand Down
94 changes: 67 additions & 27 deletions lib/widgets/editor/tree_widgets/global_constraints_tree.dart
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@ class GlobalConstraintsTree extends StatelessWidget {
child: NumberTextField(
initialValue: path.globalConstraints.maxVelocityMPS,
label: 'Max Velocity (M/S)',
enabled: !path.useDefaultConstraints,
enabled: !path.useDefaultConstraints &&
!path.globalConstraints.unlimited,
minValue: 0.1,
onSubmitted: (value) {
if (value != null) {
Expand All @@ -55,7 +56,8 @@ class GlobalConstraintsTree extends StatelessWidget {
child: NumberTextField(
initialValue: path.globalConstraints.maxAccelerationMPSSq,
label: 'Max Acceleration (M/S²)',
enabled: !path.useDefaultConstraints,
enabled: !path.useDefaultConstraints &&
!path.globalConstraints.unlimited,
minValue: 0.1,
onSubmitted: (value) {
if (value != null) {
Expand All @@ -78,7 +80,8 @@ class GlobalConstraintsTree extends StatelessWidget {
initialValue: path.globalConstraints.maxAngularVelocityDeg,
label: 'Max Angular Velocity (Deg/S)',
arrowKeyIncrement: 1.0,
enabled: !path.useDefaultConstraints,
enabled: !path.useDefaultConstraints &&
!path.globalConstraints.unlimited,
minValue: 0.1,
onSubmitted: (value) {
if (value != null) {
Expand All @@ -95,7 +98,8 @@ class GlobalConstraintsTree extends StatelessWidget {
path.globalConstraints.maxAngularAccelerationDeg,
label: 'Max Angular Acceleration (Deg/S²)',
arrowKeyIncrement: 1.0,
enabled: !path.useDefaultConstraints,
enabled: !path.useDefaultConstraints &&
!path.globalConstraints.unlimited,
minValue: 0.1,
onSubmitted: (value) {
if (value != null) {
Expand All @@ -113,31 +117,67 @@ class GlobalConstraintsTree extends StatelessWidget {
padding: const EdgeInsets.symmetric(horizontal: 6.0),
child: Row(
children: [
Checkbox(
value: path.useDefaultConstraints,
onChanged: (value) {
undoStack.add(Change(
(
path.useDefaultConstraints,
path.globalConstraints.clone()
Expanded(
child: Row(
children: [
Checkbox(
value: path.useDefaultConstraints,
onChanged: path.globalConstraints.unlimited
? null
: (value) {
undoStack.add(Change(
(
path.useDefaultConstraints,
path.globalConstraints.clone()
),
() {
path.useDefaultConstraints = value ?? false;
path.globalConstraints =
defaultConstraints.clone();
onPathChanged?.call();
},
(oldValue) {
path.useDefaultConstraints = oldValue.$1;
path.globalConstraints = oldValue.$2.clone();
onPathChanged?.call();
},
));
},
),
const SizedBox(width: 4),
const Text(
'Use Default Constraints',
style: TextStyle(fontSize: 15),
),
() {
path.useDefaultConstraints = value ?? false;
path.globalConstraints = defaultConstraints.clone();
onPathChanged?.call();
},
(oldValue) {
path.useDefaultConstraints = oldValue.$1;
path.globalConstraints = oldValue.$2.clone();
onPathChanged?.call();
},
));
},
],
),
),
const SizedBox(width: 4),
const Text(
'Use Default Constraints',
style: TextStyle(fontSize: 15),
Expanded(
child: Row(
children: [
Checkbox(
value: path.globalConstraints.unlimited,
onChanged: (value) {
undoStack.add(Change(
path.globalConstraints.unlimited,
() {
path.globalConstraints.unlimited = value ?? false;
onPathChanged?.call();
},
(oldValue) {
path.globalConstraints.unlimited = oldValue;
onPathChanged?.call();
},
));
},
),
const SizedBox(width: 4),
const Text(
'Unlimited',
style: TextStyle(fontSize: 15),
),
],
),
),
],
),
Expand Down
55 changes: 27 additions & 28 deletions pathplannerlib-python/pathplannerlib/path.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,31 +34,46 @@ class PathConstraints:
maxAccelerationMpsSq (float): Max linear acceleration (M/S^2)
maxAngularVelocityRps (float): Max angular velocity (Rad/S)
maxAngularAccelerationRpsSq (float): Max angular acceleration (Rad/S^2)
unlimited (bool): Should the constraints be unlimited
"""
maxVelocityMps: float
maxAccelerationMpsSq: float
maxAngularVelocityRps: float
maxAngularAccelerationRpsSq: float
unlimited: bool = False

@staticmethod
def fromJson(json_dict: dict) -> PathConstraints:
maxVel = float(json_dict['maxVelocity'])
maxAccel = float(json_dict['maxAcceleration'])
maxAngularVel = float(json_dict['maxAngularVelocity'])
maxAngularAccel = float(json_dict['maxAngularAcceleration'])
unlimited = bool(json_dict['unlimited']) if 'unlimited' in json_dict else False

return PathConstraints(
maxVel,
maxAccel,
units.degreesToRadians(maxAngularVel),
units.degreesToRadians(maxAngularAccel))
units.degreesToRadians(maxAngularAccel),
unlimited)

@staticmethod
def unlimitedConstraints() -> PathConstraints:
return PathConstraints(
float('inf'),
float('inf'),
float('inf'),
float('inf'),
True
)

def __eq__(self, other):
return (isinstance(other, PathConstraints)
and other.maxVelocityMps == self.maxVelocityMps
and other.maxAccelerationMpsSq == self.maxAccelerationMpsSq
and other.maxAngularVelocityRps == self.maxAngularVelocityRps
and other.maxAngularAccelerationRpsSq == self.maxAngularAccelerationRpsSq)
and other.maxAngularAccelerationRpsSq == self.maxAngularAccelerationRpsSq
and other.unlimited == self.unlimited)


@dataclass(frozen=True)
Expand Down Expand Up @@ -543,12 +558,9 @@ def _loadChoreoTrajectoryIntoCache(trajectory_name: str) -> None:
fullEvents.sort(key=lambda e: e.getTimestamp())

# Add the full path to the cache
fullPath = PathPlannerPath([], PathConstraints(
float('inf'),
float('inf'),
float('inf'),
float('inf')
), None, GoalEndState(fullTrajStates[-1].linearVelocity, fullTrajStates[-1].pose.rotation()))
fullPath = PathPlannerPath([], PathConstraints.unlimitedConstraints(), None,
GoalEndState(fullTrajStates[-1].linearVelocity,
fullTrajStates[-1].pose.rotation()))
fullPathPoints = [PathPoint(state.pose.translation()) for state in fullTrajStates]
fullPath._allPoints = fullPathPoints
fullPath._isChoreoPath = True
Expand Down Expand Up @@ -580,12 +592,8 @@ def _loadChoreoTrajectoryIntoCache(trajectory_name: str) -> None:
if startTime <= originalEvent.getTimestamp() < endTime:
events.append(originalEvent.copyWithTime(originalEvent.getTimestamp() - startTime))

path = PathPlannerPath([], PathConstraints(
float('inf'),
float('inf'),
float('inf'),
float('inf')
), None, GoalEndState(states[-1].linearVelocity, states[-1].pose.rotation()))
path = PathPlannerPath([], PathConstraints.unlimitedConstraints(), None,
GoalEndState(states[-1].linearVelocity, states[-1].pose.rotation()))
pathPoints = [PathPoint(state.pose.translation()) for state in states]
path._allPoints = pathPoints
path._isChoreoPath = True
Expand Down Expand Up @@ -662,18 +670,6 @@ def getPoint(self, index: int) -> PathPoint:
"""
return self._allPoints[index]

def getConstraintsForPoint(self, idx: int) -> PathConstraints:
"""
Get the constraints for a point along the path

:param idx: Index of the point to get constraints for
:return: The constraints that should apply to the point
"""
if self.getPoint(idx).constraints is None:
return self.getPoint(idx).constraints

return self._globalConstraints

def getGlobalConstraints(self) -> PathConstraints:
"""
Get the global constraints for this path
Expand Down Expand Up @@ -859,6 +855,11 @@ def _constraintsForWaypointPos(self, pos: float) -> PathConstraints:
for z in self._constraintZones:
if z.minWaypointPos <= pos <= z.maxWaypointPos:
return z.constraints

# Check if constraints should be unlimited
if self._globalConstraints.unlimited:
return PathConstraints.unlimitedConstraints()

return self._globalConstraints

def _pointZoneForWaypointPos(self, pos: float) -> Union[PointTowardsZone, None]:
Expand Down Expand Up @@ -1079,8 +1080,6 @@ def _precalcValues(self) -> None:
if self.numPoints() > 0:
for i in range(self.numPoints()):
point = self.getPoint(i)
if point.constraints is None:
point.constraints = self._globalConstraints
curveRadius = self._getCurveRadiusAtPoint(i)

if math.isfinite(curveRadius):
Expand Down
2 changes: 1 addition & 1 deletion pathplannerlib-python/pathplannerlib/trajectory.py
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,7 @@ def _generateStates(states: List[PathPlannerTrajectoryState], path: PathPlannerP
robotPose = Pose2d(p.position, holonomicRot)
state = PathPlannerTrajectoryState()
state.pose = robotPose
state.constraints = path.getConstraintsForPoint(i)
state.constraints = p.constraints
state.waypointRelativePos = p.waypointRelativePos

# Calculate robot heading
Expand Down
Loading
Loading