Skip to content

Commit

Permalink
Update tool srvs (#71)
Browse files Browse the repository at this point in the history
* Add AddTool Srv
* Consolidate DetachTool/RemoveTool srvs
* Remove no longer needed fields in AttachTool srv
  • Loading branch information
dyackzan authored Nov 14, 2024
1 parent d16616e commit c7d7baa
Show file tree
Hide file tree
Showing 5 changed files with 41 additions and 20 deletions.
3 changes: 2 additions & 1 deletion moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,9 @@ set(msg_files
)

set(srv_files
"srv/AddTool.srv"
"srv/AttachTool.srv"
"srv/DetachTool.srv"
"srv/DetachOrRemoveTool.srv"
"srv/ClearStoredParameters.srv"
"srv/EditWaypoints.srv"
"srv/GetAgentInfo.srv"
Expand Down
22 changes: 22 additions & 0 deletions moveit_studio_msgs/moveit_studio_agent_msgs/srv/AddTool.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
# Service to add tools in the planning scene.
# The tool is given as a URDF string, and is attached to a specific frame in the planning scene with a relative pose.
# Once the tool is added, 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 add to the planning scene.
# It must not be in the planning scene already, otherwise an error will be returned.
string tool_name

# The tool URDF.
string tool_urdf

# The pose at which the tool will be added.
# Use a pose stamped so we can define the frame relative to which the tool will be added.
geometry_msgs/PoseStamped tool_pose

---
# If the operation was successful.
bool success

# If the operation was not successful, a message describing the error.
string message
Original file line number Diff line number Diff line change
@@ -1,22 +1,17 @@
# 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.
# The tool given must already exist in the planning scene, and is attached to a specific link on the robot at the
# current transform between the link and the tool.
# 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

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# Service to detach tools from the robot or remove them from the scene.

# The name of the tool to detach or remove.
# If using this srv with the 'detach_tool' service, the tool must have been
# attached to the robot previously.
# If using this srv with the 'remove_tool_from_scene', the tool must have been
# added to the scene previously.
string tool_name

---
# If the operation was successful.
bool success

# If the operation was not successful, a message describing the error.
string message
12 changes: 0 additions & 12 deletions moveit_studio_msgs/moveit_studio_agent_msgs/srv/DetachTool.srv

This file was deleted.

0 comments on commit c7d7baa

Please sign in to comment.