Skip to content

Commit

Permalink
new GraspPlanning service to replace manipulation_msgs version (#32)
Browse files Browse the repository at this point in the history
* 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
  • Loading branch information
Jntzko authored and v4hn committed Oct 4, 2016
1 parent 47f90aa commit 0c135aa
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ ExecuteKnownTrajectory.srv
GetStateValidity.srv
GetCartesianPath.srv
GetPlanningScene.srv
GraspPlanning.srv
ApplyPlanningScene.srv
QueryPlannerInterfaces.srv
GetConstraintAwarePositionIK.srv
Expand Down
27 changes: 27 additions & 0 deletions srv/GraspPlanning.srv
Original file line number Diff line number Diff line change
@@ -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

0 comments on commit 0c135aa

Please # to comment.