diff --git a/moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt b/moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt index 3591872..3e14d6e 100644 --- a/moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt +++ b/moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt @@ -29,6 +29,8 @@ set(msg_files ) set(srv_files + "srv/AttachTool.srv" + "srv/DetachTool.srv" "srv/ClearStoredParameters.srv" "srv/EditWaypoints.srv" "srv/GetAgentInfo.srv" diff --git a/moveit_studio_msgs/moveit_studio_agent_msgs/srv/AttachTool.srv b/moveit_studio_msgs/moveit_studio_agent_msgs/srv/AttachTool.srv new file mode 100644 index 0000000..99d32a7 --- /dev/null +++ b/moveit_studio_msgs/moveit_studio_agent_msgs/srv/AttachTool.srv @@ -0,0 +1,28 @@ +# Service to attach articulated tools to the robot. +# The tool is given as a URDF string, and is attached to a specific link on the robot with a relative pose. +# Once the tool is attached, its collision shapes will be updated in the planning scene according to the tool +# joint values, if those are published in /joint_states. + +# The name of the tool to attach. +# It must not be attached already, otherwise an error will be returned. +string tool_name + +# The tool URDF. +string tool_urdf + +# The name of the robot link to attach to. +# It must exist in the robot URDF, otherwise an error will be returned. +string parent_link_name + +# The relative transform of the tool with respect to the parent link. +geometry_msgs/Transform tool_pose + +# Robot links this tool is allowed to collide with. +string[] allowed_collision_links + +--- +# If the operation was successful. +bool success + +# If the operation was not successful, a message describing the error. +string message diff --git a/moveit_studio_msgs/moveit_studio_agent_msgs/srv/DetachTool.srv b/moveit_studio_msgs/moveit_studio_agent_msgs/srv/DetachTool.srv new file mode 100644 index 0000000..191aa00 --- /dev/null +++ b/moveit_studio_msgs/moveit_studio_agent_msgs/srv/DetachTool.srv @@ -0,0 +1,12 @@ +# Service to detach tools from the robot. + +# The name of the tool to detach. +# It must have been attached previously. Otherwise an error will be returned. +string tool_name + +--- +# If the operation was successful. +bool success + +# If the operation was not successful, a message describing the error. +string message