File: tabletop_object_detector/SegmentObjectInHand.srv
# The name of the wrist frame for the arm in question (the region of interest in the params are relative to this)
string wrist_frame
---
# The resulting cluster of points in the hand
sensor_msgs/PointCloud2 cluster
# Whether the segmentation succeeded or failed
int32 SUCCESS = 0
int32 NO_CLOUD_RECEIVED = 1
int32 TF_ERROR = 2
int32 OTHER_ERROR = 3
int32 result
Expanded Definition
string wrist_frame
int32 SUCCESS=0
int32 NO_CLOUD_RECEIVED=1
int32 TF_ERROR=2
int32 OTHER_ERROR=3
sensor_msgs/PointCloud2 cluster
Header header
uint32 seq
time stamp
string frame_id
uint32 height
uint32 width
sensor_msgs/PointField[] fields
uint8 INT8=1
uint8 UINT8=2
uint8 INT16=3
uint8 UINT16=4
uint8 INT32=5
uint8 UINT32=6
uint8 FLOAT32=7
uint8 FLOAT64=8
string name
uint32 offset
uint8 datatype
uint32 count
bool is_bigendian
uint32 point_step
uint32 row_step
uint8[] data
bool is_dense
int32 result