manipulation_msgs

Summary

manipulation_msgs
Version:

0.2.0

Description:

The manipulation_msgs package

Maintainers:
  • Jon Binney <jbinney AT willowgarage DOT com>
Licenses:
  • BSD
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:

Types

Message types

manipulation_msgs/GraspPlanningErrorCode
Constant:
  • SUCCESS (int32):0
  • TF_ERROR (int32):1
  • OTHER_ERROR (int32):2
Field:
  • value (int32) –

Error codes for grasp and place planning

plan completed as expected

# Error codes for grasp and place planning

# plan completed as expected
int32 SUCCESS = 0

# tf error encountered while transforming
int32 TF_ERROR = 1 

# some other error
int32 OTHER_ERROR = 2

# the actual value of this error code
int32 value
manipulation_msgs/CartesianGains
Field:
  • header (std_msgs/Header) –
  • gains[] (float64) –
  • fixed_frame[] (float64) –
Header header

float64[] gains
float64[] fixed_frame
manipulation_msgs/GripperTranslation
Field:

defines a translation for the gripper, used in pickup or place tasks for example for lifting an object off a table or approaching the table for placing

the direction of the translation

# defines a translation for the gripper, used in pickup or place tasks
# for example for lifting an object off a table or approaching the table for placing

# the direction of the translation
geometry_msgs/Vector3Stamped direction

# the desired translation distance
float32 desired_distance

# the min distance that must be considered feasible before the
# grasp is even attempted
float32 min_distance
manipulation_msgs/SceneRegion
Field:

Point cloud

# Point cloud
sensor_msgs/PointCloud2 cloud

# Indices for the region of interest
int32[] mask

# One of the corresponding 2D images, if applicable
sensor_msgs/Image image

# The disparity image, if applicable
sensor_msgs/Image disparity_image

# Camera info for the camera that took the image
sensor_msgs/CameraInfo cam_info

# a 3D region of interest for grasp planning
geometry_msgs/PoseStamped  roi_box_pose
geometry_msgs/Vector3 	   roi_box_dims
manipulation_msgs/ManipulationResult
Constant:
  • SUCCESS (int32):1
  • UNFEASIBLE (int32):-1
  • FAILED (int32):-2
  • ERROR (int32):-3
  • ARM_MOVEMENT_PREVENTED (int32):-4
  • LIFT_FAILED (int32):-5
  • RETREAT_FAILED (int32):-6
  • CANCELLED (int32):-7
Field:
  • value (int32) –

Result codes for manipulation tasks

task completed as expected generally means you can proceed as planned

# Result codes for manipulation tasks

# task completed as expected
# generally means you can proceed as planned
int32 SUCCESS = 1

# task not possible (e.g. out of reach or obstacles in the way)
# generally means that the world was not disturbed, so you can try another task
int32 UNFEASIBLE = -1

# task was thought possible, but failed due to unexpected events during execution
# it is likely that the world was disturbed, so you are encouraged to refresh
# your sensed world model before proceeding to another task
int32 FAILED = -2

# a lower level error prevented task completion (e.g. joint controller not responding)
# generally requires human attention
int32 ERROR = -3

# means that at some point during execution we ended up in a state that the collision-aware
# arm navigation module will not move out of. The world was likely not disturbed, but you 
# probably need a new collision map to move the arm out of the stuck position
int32 ARM_MOVEMENT_PREVENTED = -4

# specific to grasp actions
# the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested
# it is likely that the collision environment will see collisions between the hand/object and the support surface
int32 LIFT_FAILED = -5

# specific to place actions
# the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested
# it is likely that the collision environment will see collisions between the hand and the object
int32 RETREAT_FAILED = -6

# indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else"
int32 CANCELLED = -7

# the actual value of this error code
int32 value
manipulation_msgs/PlaceLocation
Field:

A name for this grasp

# A name for this grasp
string id

# The internal posture of the hand for the grasp
# positions and efforts are used
sensor_msgs/JointState post_place_posture

# The position of the end-effector for the grasp relative to a reference frame 
# (that is always specified elsewhere, not in this message)
geometry_msgs/PoseStamped place_pose

# The approach motion
GripperTranslation approach

# The retreat motion
GripperTranslation retreat

# an optional list of obstacles that we have semantic information about
# and that can be touched/pushed/moved in the course of grasping
string[] allowed_touch_objects
manipulation_msgs/GraspResult
Constant:
  • SUCCESS (int32):1
  • GRASP_OUT_OF_REACH (int32):2
  • GRASP_IN_COLLISION (int32):3
  • GRASP_UNFEASIBLE (int32):4
  • PREGRASP_OUT_OF_REACH (int32):5
  • PREGRASP_IN_COLLISION (int32):6
  • PREGRASP_UNFEASIBLE (int32):7
  • LIFT_OUT_OF_REACH (int32):8
  • LIFT_IN_COLLISION (int32):9
  • LIFT_UNFEASIBLE (int32):10
  • MOVE_ARM_FAILED (int32):11
  • GRASP_FAILED (int32):12
  • LIFT_FAILED (int32):13
  • RETREAT_FAILED (int32):14
Field:
  • result_code (int32) –
  • continuation_possible (bool) –
int32 SUCCESS = 1
int32 GRASP_OUT_OF_REACH = 2
int32 GRASP_IN_COLLISION = 3
int32 GRASP_UNFEASIBLE = 4
int32 PREGRASP_OUT_OF_REACH = 5
int32 PREGRASP_IN_COLLISION = 6
int32 PREGRASP_UNFEASIBLE = 7
int32 LIFT_OUT_OF_REACH = 8
int32 LIFT_IN_COLLISION = 9
int32 LIFT_UNFEASIBLE = 10
int32 MOVE_ARM_FAILED = 11
int32 GRASP_FAILED = 12
int32 LIFT_FAILED = 13
int32 RETREAT_FAILED = 14
int32 result_code

# whether the state of the world was disturbed by this attempt. generally, this flag
# shows if another task can be attempted, or a new sensed world model is recommeded
# before proceeding
bool continuation_possible
manipulation_msgs/ClusterBoundingBox
Field:

the pose of the box frame

# contains a bounding box, which is essentially a box somewhere in space
# used here ususally for the outlier-invariant bounding box of a cluster of points

#the pose of the box frame
geometry_msgs/PoseStamped pose_stamped

#the dimensions of the box
geometry_msgs/Vector3 dimensions
manipulation_msgs/ManipulationPhase
Constant:
  • CHECKING_FEASIBILITY (int32):0
  • MOVING_TO_PREGRASP (int32):1
  • MOVING_TO_GRASP (int32):2
  • CLOSING (int32):3
  • ADJUSTING_GRASP (int32):4
  • LIFTING (int32):5
  • MOVING_WITH_OBJECT (int32):6
  • MOVING_TO_PLACE (int32):7
  • PLACING (int32):8
  • OPENING (int32):9
  • RETREATING (int32):10
  • MOVING_WITHOUT_OBJECT (int32):11
  • SHAKING (int32):12
  • SUCCEEDED (int32):13
  • FAILED (int32):14
  • ABORTED (int32):15
  • HOLDING_OBJECT (int32):16
Field:
  • phase (int32) –
int32 CHECKING_FEASIBILITY = 0
int32 MOVING_TO_PREGRASP = 1
int32 MOVING_TO_GRASP = 2
int32 CLOSING = 3 
int32 ADJUSTING_GRASP = 4
int32 LIFTING = 5
int32 MOVING_WITH_OBJECT = 6
int32 MOVING_TO_PLACE = 7
int32 PLACING = 8
int32 OPENING = 9
int32 RETREATING = 10
int32 MOVING_WITHOUT_OBJECT = 11
int32 SHAKING = 12
int32 SUCCEEDED = 13
int32 FAILED = 14
int32 ABORTED = 15
int32 HOLDING_OBJECT = 16

int32 phase
manipulation_msgs/PlaceLocationResult
Constant:
  • SUCCESS (int32):1
  • PLACE_OUT_OF_REACH (int32):2
  • PLACE_IN_COLLISION (int32):3
  • PLACE_UNFEASIBLE (int32):4
  • PREPLACE_OUT_OF_REACH (int32):5
  • PREPLACE_IN_COLLISION (int32):6
  • PREPLACE_UNFEASIBLE (int32):7
  • RETREAT_OUT_OF_REACH (int32):8
  • RETREAT_IN_COLLISION (int32):9
  • RETREAT_UNFEASIBLE (int32):10
  • MOVE_ARM_FAILED (int32):11
  • PLACE_FAILED (int32):12
  • RETREAT_FAILED (int32):13
Field:
  • result_code (int32) –
  • continuation_possible (bool) –
int32 SUCCESS = 1
int32 PLACE_OUT_OF_REACH = 2
int32 PLACE_IN_COLLISION = 3
int32 PLACE_UNFEASIBLE = 4
int32 PREPLACE_OUT_OF_REACH = 5
int32 PREPLACE_IN_COLLISION = 6
int32 PREPLACE_UNFEASIBLE = 7
int32 RETREAT_OUT_OF_REACH = 8
int32 RETREAT_IN_COLLISION = 9
int32 RETREAT_UNFEASIBLE = 10
int32 MOVE_ARM_FAILED = 11
int32 PLACE_FAILED = 12
int32 RETREAT_FAILED = 13
int32 result_code

# whether the state of the world was disturbed by this attempt. generally, this flag
# shows if another task can be attempted, or a new sensed world model is recommeded
# before proceeding
bool continuation_possible
manipulation_msgs/GraspableObject
Field:

an object that the object_manipulator can work on

a graspable object can be represented in multiple ways. This message can contain all of them. Which one is actually used is up to the receiver of this message. When adding new representations, one must be careful that they have reasonable lightweight defaults indicating that that particular representation is not available.

the tf frame to be used as a reference frame when combining information from the different representations below

# an object that the object_manipulator can work on

# a graspable object can be represented in multiple ways. This message
# can contain all of them. Which one is actually used is up to the receiver
# of this message. When adding new representations, one must be careful that
# they have reasonable lightweight defaults indicating that that particular
# representation is not available.

# the tf frame to be used as a reference frame when combining information from
# the different representations below
string reference_frame_id

# potential recognition results from a database of models
# all poses are relative to the object reference pose
household_objects_database_msgs/DatabaseModelPose[] potential_models

# the point cloud itself
sensor_msgs/PointCloud cluster

# a region of a PointCloud2 of interest
SceneRegion region

# the name that this object has in the collision environment
string collision_name
manipulation_msgs/GraspableObjectList
Field:
manipulation_msgs/GraspableObject[] graspable_objects

#Information required for visualization

sensor_msgs/Image image
sensor_msgs/CameraInfo camera_info

#Holds a single mesh for each recognized graspable object, an empty mesh otherwise
shape_msgs/Mesh[] meshes

#pose to transform the frame of the clusters/object poses into camera coordinates
geometry_msgs/Pose reference_to_camera
manipulation_msgs/Grasp
Field:

A name for this grasp

# A name for this grasp
string id

# The internal posture of the hand for the pre-grasp
# only positions are used
sensor_msgs/JointState pre_grasp_posture

# The internal posture of the hand for the grasp
# positions and efforts are used
sensor_msgs/JointState grasp_posture

# The position of the end-effector for the grasp 
geometry_msgs/PoseStamped grasp_pose

# The estimated probability of success for this grasp, or some other
# measure of how "good" it is.
float64 grasp_quality

# The approach motion
GripperTranslation approach

# The retreat motion
GripperTranslation retreat

# the maximum contact force to use while grasping (<=0 to disable)
float32 max_contact_force

# an optional list of obstacles that we have semantic information about
# and that can be touched/pushed/moved in the course of grasping
string[] allowed_touch_objects

Service types

manipulation_msgs/GraspPlanning
Field (Request):
 
Field (Response):
 

Requests that grasp planning be performed on the object to be grasped returns a list of grasps to be tested and executed

the arm being used

# Requests that grasp planning be performed on the object to be grasped
# returns a list of grasps to be tested and executed

# the arm being used
string arm_name

# the object to be grasped
GraspableObject target

# the name that the target object has in the collision environment
# can be left empty if no name is available
string collision_object_name

# the name that the support surface (e.g. table) has in the collision map
# can be left empty if no name is available
string collision_support_surface_name

# an optional list of grasps to be evaluated by the planner
Grasp[] grasps_to_evaluate

# an optional list of obstacles that we have semantic information about
# and that can be moved in the course of grasping
GraspableObject[] movable_obstacles

---

# the list of planned grasps
Grasp[] grasps

# whether an error occurred
GraspPlanningErrorCode error_code

Action types

manipulation_msgs/GraspPlanning
Field (Goal):
Field (Result):
Field (Feedback):
 

Requests that grasp planning be performed on the object to be grasped returns a list of grasps to be tested and executed

the arm being used

# Requests that grasp planning be performed on the object to be grasped
# returns a list of grasps to be tested and executed

# the arm being used
string arm_name

# the object to be grasped
GraspableObject target

# the name that the target object has in the collision environment
# can be left empty if no name is available
string collision_object_name

# the name that the support surface (e.g. table) has in the collision map
# can be left empty if no name is available
string collision_support_surface_name

# an optional list of grasps to be evaluated by the planner
Grasp[] grasps_to_evaluate

# an optional list of obstacles that we have semantic information about
# and that can be moved in the course of grasping
GraspableObject[] movable_obstacles

---

# the list of planned grasps
Grasp[] grasps

# whether an error occurred
GraspPlanningErrorCode error_code

---

# grasps planned so far
Grasp[] grasps