From 0c135aa86db29050719854376bb784690531efda Mon Sep 17 00:00:00 2001 From: Jntzko <5jonetzk@informatik.uni-hamburg.de> Date: Tue, 4 Oct 2016 09:50:01 +0200 Subject: [PATCH] new GraspPlanning service to replace manipulation_msgs version (#32) * new GraspPlanning service to replace manipulation_msgs version Until now the move group pick action uses the grasp planning service from manipulation_msgs. However, this doesn't use moveit_msgs::Grasp which has evolved since then. The new service in moveit_msgs uses its own Grasp.msg and overall aims to replace the old functionality using moveit types. * Adapt variable names and comments --- CMakeLists.txt | 1 + srv/GraspPlanning.srv | 27 +++++++++++++++++++++++++++ 2 files changed, 28 insertions(+) create mode 100644 srv/GraspPlanning.srv diff --git a/CMakeLists.txt b/CMakeLists.txt index 5c95521..b1a2c21 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -60,6 +60,7 @@ ExecuteKnownTrajectory.srv GetStateValidity.srv GetCartesianPath.srv GetPlanningScene.srv +GraspPlanning.srv ApplyPlanningScene.srv QueryPlannerInterfaces.srv GetConstraintAwarePositionIK.srv diff --git a/srv/GraspPlanning.srv b/srv/GraspPlanning.srv new file mode 100644 index 0000000..c16738b --- /dev/null +++ b/srv/GraspPlanning.srv @@ -0,0 +1,27 @@ +# Requests that grasp planning be performed for the target object +# returns a list of candidate grasps to be tested and executed + +# the planning group used +string group_name + +# the object to be grasped +CollisionObject target + +# the names of the relevant support surfaces (e.g. tables) in the collision map +# can be left empty if no names are available +string[] support_surfaces + +# an optional list of grasps to be evaluated by the planner +Grasp[] candidate_grasps + +# an optional list of obstacles that we have semantic information about +# and that can be moved in the course of grasping +CollisionObject[] movable_obstacles + +--- + +# the list of planned grasps +Grasp[] grasps + +# whether an error occurred +MoveItErrorCodes error_code