From f0032eb9e9b730e07aae27b6354a9d7bae431acb Mon Sep 17 00:00:00 2001 From: liamcarlos <142509545+liamcarlos@users.noreply.github.com> Date: Wed, 30 Oct 2024 11:17:09 -0400 Subject: [PATCH] Added vel and acc scaling to GetCartesianPath.srv on Humble I'm adding these to match a pull request on moveit/moveit2 to add velocity and acceleration control to cartesian path planning on the Humble branch. I found this portion on the Iron branch here but couldn't find references to them in moveit/moveit2 so I just left them out if anybody's wondering. # Maximum cartesian speed for the given link. # If max_cartesian_speed <= 0 the trajectory is not modified. string cartesian_speed_limited_link float64 max_cartesian_speed # m/s --- srv/GetCartesianPath.srv | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/srv/GetCartesianPath.srv b/srv/GetCartesianPath.srv index 29a4c8f..fc2dffb 100644 --- a/srv/GetCartesianPath.srv +++ b/srv/GetCartesianPath.srv @@ -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