diff --git a/msg/MotionPlanRequest.msg b/msg/MotionPlanRequest.msg index ac386e2..120222a 100644 --- a/msg/MotionPlanRequest.msg +++ b/msg/MotionPlanRequest.msg @@ -47,3 +47,7 @@ float64 allowed_planning_time float64 max_velocity_scaling_factor float64 max_acceleration_scaling_factor +# Maximum cartesian speed for the given end effector. +# If max_cartesian_speed <= 0 the trajectory is not modified. +string cartesian_speed_end_effector_link +float64 max_cartesian_speed # m/s