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

Add fields in GetCartesianPath srv to scale velocity and acceleration #154

Merged
merged 3 commits into from
Mar 23, 2023
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
8 changes: 4 additions & 4 deletions msg/MotionPlanRequest.msg
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,10 @@ int32 num_planning_attempts
float64 allowed_planning_time

# Scaling factors for optionally reducing the maximum joint velocities and
# accelerations. Allowed values are in (0,1]. The maximum joint velocity and
# acceleration specified in the robot model are multiplied by thier respective
# factors. If either are outside their valid ranges (importantly, this
# includes being set to 0.0), the factor is set to the default value of 1.0
# accelerations. Allowed values are in (0,1]. The maximum joint velocity and
# acceleration specified in the robot model are multiplied by their respective
# factors. If a factor is outside its valid range (importantly, this
# includes being set to 0.0), this factor is set to the default value of 1.0
# internally (i.e., maximum joint velocity or maximum joint acceleration).
float64 max_velocity_scaling_factor
float64 max_acceleration_scaling_factor
Expand Down
9 changes: 9 additions & 0 deletions srv/GetCartesianPath.srv
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,15 @@ bool avoid_collisions
# Specify additional constraints to be met by the Cartesian path
Constraints path_constraints

# Scaling factors for optionally reducing the maximum joint velocities and
# accelerations. Allowed values are in (0,1]. The maximum joint velocity and
# acceleration specified in the robot model are multiplied by their respective
# factors. If a factor is outside its valid range (importantly, this
# includes being set to 0.0), this factor is set to the default value of 1.0
# internally (i.e., maximum joint velocity or maximum joint acceleration).
float64 max_velocity_scaling_factor
float64 max_acceleration_scaling_factor

---

# The state at which the computed path starts
Expand Down