rc_pick_client/ComputeBoxGrasps Service

File: rc_pick_client/ComputeBoxGrasps.srv

Raw Message Definition

# Description: Triggers the computation of grasp poses for the given box items and suction surface.

# A valid pose_frame (either camera or external) is required in the request.
# It can be provided either with the pose_frame field, as pose_frame of the selected region of interest
# or as pose_frame of the selected load carrier.
# If more than one pose_frame is provided, they must to be consistent.

# Optional. Pose frame for output poses.
string pose_frame

# Optional
string region_of_interest_id

# Optional
string load_carrier_id

# Optional
Compartment load_carrier_compartment

# Required
ItemModel[] item_models

# Required. Dimensions of the gripper suction surface
# In case of circular suction cups, the two values are expected to be the same and set to the suction cup diameter
# Different values are expected for grippers with multiple suction cups or non-circular suction cups (e.g. oval cups)
float64 suction_surface_length
float64 suction_surface_width

# Required only if reference frame = external and sensor is robot-mounted
geometry_msgs/Pose robot_pose

# Optional. Enables collision checking of grasps with load carrier
CollisionDetection collision_detection

---

time timestamp

Item[] items

SuctionGrasp[] grasps

LoadCarrier[] load_carriers

rc_common_msgs/ReturnCode return_code

Compact Message Definition

string pose_frame
string region_of_interest_id
string load_carrier_id
rc_pick_client/Compartment load_carrier_compartment
rc_pick_client/ItemModel[] item_models
float64 suction_surface_length
float64 suction_surface_width
geometry_msgs/Pose robot_pose
rc_pick_client/CollisionDetection collision_detection

time timestamp
rc_pick_client/Item[] items
rc_pick_client/SuctionGrasp[] grasps
rc_pick_client/LoadCarrier[] load_carriers
rc_common_msgs/ReturnCode return_code