diff --git a/CMakeLists.txt b/CMakeLists.txt index ff23ff2..dcfd0c1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -99,6 +99,7 @@ set(srv_files "srv/RenameRobotStateInWarehouse.srv" "srv/DeleteRobotStateFromWarehouse.srv" "srv/ServoCommandType.srv" + "srv/ChangeJointLimits.srv" ) set(action_files diff --git a/action/GlobalPlanner.action b/action/GlobalPlanner.action index 8500f62..5e71190 100644 --- a/action/GlobalPlanner.action +++ b/action/GlobalPlanner.action @@ -1,5 +1,6 @@ # Motion planning request to the global planner string planning_group +trajectory_msgs/JointTrajectory trajectory moveit_msgs/MotionSequenceRequest motion_sequence --- # Motion planning response from the global planner diff --git a/action/HybridPlanner.action b/action/HybridPlanner.action index ff1b917..eee7482 100644 --- a/action/HybridPlanner.action +++ b/action/HybridPlanner.action @@ -1,5 +1,6 @@ # Motion planning request to the hybrid planning architecture string planning_group +trajectory_msgs/JointTrajectory trajectory moveit_msgs/MotionSequenceRequest motion_sequence --- # Result of the hybrid planning diff --git a/msg/MotionPlanRequest.msg b/msg/MotionPlanRequest.msg index c2e1b4b..fa54f51 100644 --- a/msg/MotionPlanRequest.msg +++ b/msg/MotionPlanRequest.msg @@ -51,6 +51,16 @@ float64 allowed_planning_time float64 max_velocity_scaling_factor float64 max_acceleration_scaling_factor +# New joint limits to use when running time-parameterization and smoothing. +# Note, this does not replace the values in the robot model. +# Set the 'has_limits' field to true for velocity, acceleration, and/or jerk +# in order for that limit to be applied. Position limits are not supported. +JointLimits[] joint_limits + +# If true, smoothing will be skipped when applying a smoothing adapter during +# trajectory processing (if it is defined as a request adapter). +bool skip_smoothing + # Maximum cartesian speed for the given link. # If max_cartesian_speed <= 0 the trajectory is not modified. # These fields require the following planning request adapter: default_planner_request_adapters/LimitMaxCartesianLinkSpeed diff --git a/srv/ChangeJointLimits.srv b/srv/ChangeJointLimits.srv new file mode 100644 index 0000000..6855dcd --- /dev/null +++ b/srv/ChangeJointLimits.srv @@ -0,0 +1,4 @@ +# A list of joint limits to modify +JointLimits[] limits +--- +bool success \ No newline at end of file