Skip to content

Commit

Permalink
Add AttachTool and DetachTool service definitions (#61)
Browse files Browse the repository at this point in the history
  • Loading branch information
marioprats authored Sep 16, 2024
1 parent 00d8bff commit a047556
Show file tree
Hide file tree
Showing 3 changed files with 42 additions and 0 deletions.
2 changes: 2 additions & 0 deletions moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
28 changes: 28 additions & 0 deletions moveit_studio_msgs/moveit_studio_agent_msgs/srv/AttachTool.srv
Original file line number Diff line number Diff line change
@@ -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
12 changes: 12 additions & 0 deletions moveit_studio_msgs/moveit_studio_agent_msgs/srv/DetachTool.srv
Original file line number Diff line number Diff line change
@@ -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

0 comments on commit a047556

Please sign in to comment.