00001 """autogenerated by genmsg_py from FindClusterBoundingBoxRequest.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import std_msgs.msg
00007 import sensor_msgs.msg
00008
00009 class FindClusterBoundingBoxRequest(roslib.message.Message):
00010 _md5sum = "c9b8a24dd6ede958d3710cdb47643a01"
00011 _type = "object_manipulation_msgs/FindClusterBoundingBoxRequest"
00012 _has_header = False
00013 _full_text = """sensor_msgs/PointCloud cluster
00014
00015
00016 ================================================================================
00017 MSG: sensor_msgs/PointCloud
00018 # This message holds a collection of 3d points, plus optional additional
00019 # information about each point.
00020
00021 # Time of sensor data acquisition, coordinate frame ID.
00022 Header header
00023
00024 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00025 # in the frame given in the header.
00026 geometry_msgs/Point32[] points
00027
00028 # Each channel should have the same number of elements as points array,
00029 # and the data in each channel should correspond 1:1 with each point.
00030 # Channel names in common practice are listed in ChannelFloat32.msg.
00031 ChannelFloat32[] channels
00032
00033 ================================================================================
00034 MSG: std_msgs/Header
00035 # Standard metadata for higher-level stamped data types.
00036 # This is generally used to communicate timestamped data
00037 # in a particular coordinate frame.
00038 #
00039 # sequence ID: consecutively increasing ID
00040 uint32 seq
00041 #Two-integer timestamp that is expressed as:
00042 # * stamp.secs: seconds (stamp_secs) since epoch
00043 # * stamp.nsecs: nanoseconds since stamp_secs
00044 # time-handling sugar is provided by the client library
00045 time stamp
00046 #Frame this data is associated with
00047 # 0: no frame
00048 # 1: global frame
00049 string frame_id
00050
00051 ================================================================================
00052 MSG: geometry_msgs/Point32
00053 # This contains the position of a point in free space(with 32 bits of precision).
00054 # It is recommeded to use Point wherever possible instead of Point32.
00055 #
00056 # This recommendation is to promote interoperability.
00057 #
00058 # This message is designed to take up less space when sending
00059 # lots of points at once, as in the case of a PointCloud.
00060
00061 float32 x
00062 float32 y
00063 float32 z
00064 ================================================================================
00065 MSG: sensor_msgs/ChannelFloat32
00066 # This message is used by the PointCloud message to hold optional data
00067 # associated with each point in the cloud. The length of the values
00068 # array should be the same as the length of the points array in the
00069 # PointCloud, and each value should be associated with the corresponding
00070 # point.
00071
00072 # Channel names in existing practice include:
00073 # "u", "v" - row and column (respectively) in the left stereo image.
00074 # This is opposite to usual conventions but remains for
00075 # historical reasons. The newer PointCloud2 message has no
00076 # such problem.
00077 # "rgb" - For point clouds produced by color stereo cameras. uint8
00078 # (R,G,B) values packed into the least significant 24 bits,
00079 # in order.
00080 # "intensity" - laser or pixel intensity.
00081 # "distance"
00082
00083 # The channel name should give semantics of the channel (e.g.
00084 # "intensity" instead of "value").
00085 string name
00086
00087 # The values array should be 1-1 with the elements of the associated
00088 # PointCloud.
00089 float32[] values
00090
00091 """
00092 __slots__ = ['cluster']
00093 _slot_types = ['sensor_msgs/PointCloud']
00094
00095 def __init__(self, *args, **kwds):
00096 """
00097 Constructor. Any message fields that are implicitly/explicitly
00098 set to None will be assigned a default value. The recommend
00099 use is keyword arguments as this is more robust to future message
00100 changes. You cannot mix in-order arguments and keyword arguments.
00101
00102 The available fields are:
00103 cluster
00104
00105 @param args: complete set of field values, in .msg order
00106 @param kwds: use keyword arguments corresponding to message field names
00107 to set specific fields.
00108 """
00109 if args or kwds:
00110 super(FindClusterBoundingBoxRequest, self).__init__(*args, **kwds)
00111 #message fields cannot be None, assign default values for those that are
00112 if self.cluster is None:
00113 self.cluster = sensor_msgs.msg.PointCloud()
00114 else:
00115 self.cluster = sensor_msgs.msg.PointCloud()
00116
00117 def _get_types(self):
00118 """
00119 internal API method
00120 """
00121 return self._slot_types
00122
00123 def serialize(self, buff):
00124 """
00125 serialize message into buffer
00126 @param buff: buffer
00127 @type buff: StringIO
00128 """
00129 try:
00130 _x = self
00131 buff.write(_struct_3I.pack(_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs))
00132 _x = self.cluster.header.frame_id
00133 length = len(_x)
00134 buff.write(struct.pack('<I%ss'%length, length, _x))
00135 length = len(self.cluster.points)
00136 buff.write(_struct_I.pack(length))
00137 for val1 in self.cluster.points:
00138 _x = val1
00139 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00140 length = len(self.cluster.channels)
00141 buff.write(_struct_I.pack(length))
00142 for val1 in self.cluster.channels:
00143 _x = val1.name
00144 length = len(_x)
00145 buff.write(struct.pack('<I%ss'%length, length, _x))
00146 length = len(val1.values)
00147 buff.write(_struct_I.pack(length))
00148 pattern = '<%sf'%length
00149 buff.write(struct.pack(pattern, *val1.values))
00150 except struct.error, se: self._check_types(se)
00151 except TypeError, te: self._check_types(te)
00152
00153 def deserialize(self, str):
00154 """
00155 unpack serialized message in str into this message instance
00156 @param str: byte array of serialized message
00157 @type str: str
00158 """
00159 try:
00160 if self.cluster is None:
00161 self.cluster = sensor_msgs.msg.PointCloud()
00162 end = 0
00163 _x = self
00164 start = end
00165 end += 12
00166 (_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00167 start = end
00168 end += 4
00169 (length,) = _struct_I.unpack(str[start:end])
00170 start = end
00171 end += length
00172 self.cluster.header.frame_id = str[start:end]
00173 start = end
00174 end += 4
00175 (length,) = _struct_I.unpack(str[start:end])
00176 self.cluster.points = []
00177 for i in xrange(0, length):
00178 val1 = geometry_msgs.msg.Point32()
00179 _x = val1
00180 start = end
00181 end += 12
00182 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00183 self.cluster.points.append(val1)
00184 start = end
00185 end += 4
00186 (length,) = _struct_I.unpack(str[start:end])
00187 self.cluster.channels = []
00188 for i in xrange(0, length):
00189 val1 = sensor_msgs.msg.ChannelFloat32()
00190 start = end
00191 end += 4
00192 (length,) = _struct_I.unpack(str[start:end])
00193 start = end
00194 end += length
00195 val1.name = str[start:end]
00196 start = end
00197 end += 4
00198 (length,) = _struct_I.unpack(str[start:end])
00199 pattern = '<%sf'%length
00200 start = end
00201 end += struct.calcsize(pattern)
00202 val1.values = struct.unpack(pattern, str[start:end])
00203 self.cluster.channels.append(val1)
00204 return self
00205 except struct.error, e:
00206 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00207
00208
00209 def serialize_numpy(self, buff, numpy):
00210 """
00211 serialize message with numpy array types into buffer
00212 @param buff: buffer
00213 @type buff: StringIO
00214 @param numpy: numpy python module
00215 @type numpy module
00216 """
00217 try:
00218 _x = self
00219 buff.write(_struct_3I.pack(_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs))
00220 _x = self.cluster.header.frame_id
00221 length = len(_x)
00222 buff.write(struct.pack('<I%ss'%length, length, _x))
00223 length = len(self.cluster.points)
00224 buff.write(_struct_I.pack(length))
00225 for val1 in self.cluster.points:
00226 _x = val1
00227 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00228 length = len(self.cluster.channels)
00229 buff.write(_struct_I.pack(length))
00230 for val1 in self.cluster.channels:
00231 _x = val1.name
00232 length = len(_x)
00233 buff.write(struct.pack('<I%ss'%length, length, _x))
00234 length = len(val1.values)
00235 buff.write(_struct_I.pack(length))
00236 pattern = '<%sf'%length
00237 buff.write(val1.values.tostring())
00238 except struct.error, se: self._check_types(se)
00239 except TypeError, te: self._check_types(te)
00240
00241 def deserialize_numpy(self, str, numpy):
00242 """
00243 unpack serialized message in str into this message instance using numpy for array types
00244 @param str: byte array of serialized message
00245 @type str: str
00246 @param numpy: numpy python module
00247 @type numpy: module
00248 """
00249 try:
00250 if self.cluster is None:
00251 self.cluster = sensor_msgs.msg.PointCloud()
00252 end = 0
00253 _x = self
00254 start = end
00255 end += 12
00256 (_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00257 start = end
00258 end += 4
00259 (length,) = _struct_I.unpack(str[start:end])
00260 start = end
00261 end += length
00262 self.cluster.header.frame_id = str[start:end]
00263 start = end
00264 end += 4
00265 (length,) = _struct_I.unpack(str[start:end])
00266 self.cluster.points = []
00267 for i in xrange(0, length):
00268 val1 = geometry_msgs.msg.Point32()
00269 _x = val1
00270 start = end
00271 end += 12
00272 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00273 self.cluster.points.append(val1)
00274 start = end
00275 end += 4
00276 (length,) = _struct_I.unpack(str[start:end])
00277 self.cluster.channels = []
00278 for i in xrange(0, length):
00279 val1 = sensor_msgs.msg.ChannelFloat32()
00280 start = end
00281 end += 4
00282 (length,) = _struct_I.unpack(str[start:end])
00283 start = end
00284 end += length
00285 val1.name = str[start:end]
00286 start = end
00287 end += 4
00288 (length,) = _struct_I.unpack(str[start:end])
00289 pattern = '<%sf'%length
00290 start = end
00291 end += struct.calcsize(pattern)
00292 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00293 self.cluster.channels.append(val1)
00294 return self
00295 except struct.error, e:
00296 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00297
00298 _struct_I = roslib.message.struct_I
00299 _struct_3I = struct.Struct("<3I")
00300 _struct_3f = struct.Struct("<3f")
00301 """autogenerated by genmsg_py from FindClusterBoundingBoxResponse.msg. Do not edit."""
00302 import roslib.message
00303 import struct
00304
00305 import geometry_msgs.msg
00306 import std_msgs.msg
00307
00308 class FindClusterBoundingBoxResponse(roslib.message.Message):
00309 _md5sum = "981e2c8ffa160e77589dcf98a63a81cd"
00310 _type = "object_manipulation_msgs/FindClusterBoundingBoxResponse"
00311 _has_header = False #flag to mark the presence of a Header object
00312 _full_text = """
00313
00314 geometry_msgs/PoseStamped pose
00315
00316
00317 geometry_msgs/Vector3 box_dims
00318
00319
00320 int32 SUCCESS=0
00321 int32 TF_ERROR=1
00322 int32 error_code
00323
00324 ================================================================================
00325 MSG: geometry_msgs/PoseStamped
00326 # A Pose with reference coordinate frame and timestamp
00327 Header header
00328 Pose pose
00329
00330 ================================================================================
00331 MSG: std_msgs/Header
00332 # Standard metadata for higher-level stamped data types.
00333 # This is generally used to communicate timestamped data
00334 # in a particular coordinate frame.
00335 #
00336 # sequence ID: consecutively increasing ID
00337 uint32 seq
00338 #Two-integer timestamp that is expressed as:
00339 # * stamp.secs: seconds (stamp_secs) since epoch
00340 # * stamp.nsecs: nanoseconds since stamp_secs
00341 # time-handling sugar is provided by the client library
00342 time stamp
00343 #Frame this data is associated with
00344 # 0: no frame
00345 # 1: global frame
00346 string frame_id
00347
00348 ================================================================================
00349 MSG: geometry_msgs/Pose
00350 # A representation of pose in free space, composed of postion and orientation.
00351 Point position
00352 Quaternion orientation
00353
00354 ================================================================================
00355 MSG: geometry_msgs/Point
00356 # This contains the position of a point in free space
00357 float64 x
00358 float64 y
00359 float64 z
00360
00361 ================================================================================
00362 MSG: geometry_msgs/Quaternion
00363 # This represents an orientation in free space in quaternion form.
00364
00365 float64 x
00366 float64 y
00367 float64 z
00368 float64 w
00369
00370 ================================================================================
00371 MSG: geometry_msgs/Vector3
00372 # This represents a vector in free space.
00373
00374 float64 x
00375 float64 y
00376 float64 z
00377 """
00378 # Pseudo-constants
00379 SUCCESS = 0
00380 TF_ERROR = 1
00381
00382 __slots__ = ['pose','box_dims','error_code']
00383 _slot_types = ['geometry_msgs/PoseStamped','geometry_msgs/Vector3','int32']
00384
00385 def __init__(self, *args, **kwds):
00386 """
00387 Constructor. Any message fields that are implicitly/explicitly
00388 set to None will be assigned a default value. The recommend
00389 use is keyword arguments as this is more robust to future message
00390 changes. You cannot mix in-order arguments and keyword arguments.
00391
00392 The available fields are:
00393 pose,box_dims,error_code
00394
00395 @param args: complete set of field values, in .msg order
00396 @param kwds: use keyword arguments corresponding to message field names
00397 to set specific fields.
00398 """
00399 if args or kwds:
00400 super(FindClusterBoundingBoxResponse, self).__init__(*args, **kwds)
00401 #message fields cannot be None, assign default values for those that are
00402 if self.pose is None:
00403 self.pose = geometry_msgs.msg.PoseStamped()
00404 if self.box_dims is None:
00405 self.box_dims = geometry_msgs.msg.Vector3()
00406 if self.error_code is None:
00407 self.error_code = 0
00408 else:
00409 self.pose = geometry_msgs.msg.PoseStamped()
00410 self.box_dims = geometry_msgs.msg.Vector3()
00411 self.error_code = 0
00412
00413 def _get_types(self):
00414 """
00415 internal API method
00416 """
00417 return self._slot_types
00418
00419 def serialize(self, buff):
00420 """
00421 serialize message into buffer
00422 @param buff: buffer
00423 @type buff: StringIO
00424 """
00425 try:
00426 _x = self
00427 buff.write(_struct_3I.pack(_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs))
00428 _x = self.pose.header.frame_id
00429 length = len(_x)
00430 buff.write(struct.pack('<I%ss'%length, length, _x))
00431 _x = self
00432 buff.write(_struct_10di.pack(_x.pose.pose.position.x, _x.pose.pose.position.y, _x.pose.pose.position.z, _x.pose.pose.orientation.x, _x.pose.pose.orientation.y, _x.pose.pose.orientation.z, _x.pose.pose.orientation.w, _x.box_dims.x, _x.box_dims.y, _x.box_dims.z, _x.error_code))
00433 except struct.error, se: self._check_types(se)
00434 except TypeError, te: self._check_types(te)
00435
00436 def deserialize(self, str):
00437 """
00438 unpack serialized message in str into this message instance
00439 @param str: byte array of serialized message
00440 @type str: str
00441 """
00442 try:
00443 if self.pose is None:
00444 self.pose = geometry_msgs.msg.PoseStamped()
00445 if self.box_dims is None:
00446 self.box_dims = geometry_msgs.msg.Vector3()
00447 end = 0
00448 _x = self
00449 start = end
00450 end += 12
00451 (_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00452 start = end
00453 end += 4
00454 (length,) = _struct_I.unpack(str[start:end])
00455 start = end
00456 end += length
00457 self.pose.header.frame_id = str[start:end]
00458 _x = self
00459 start = end
00460 end += 84
00461 (_x.pose.pose.position.x, _x.pose.pose.position.y, _x.pose.pose.position.z, _x.pose.pose.orientation.x, _x.pose.pose.orientation.y, _x.pose.pose.orientation.z, _x.pose.pose.orientation.w, _x.box_dims.x, _x.box_dims.y, _x.box_dims.z, _x.error_code,) = _struct_10di.unpack(str[start:end])
00462 return self
00463 except struct.error, e:
00464 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00465
00466
00467 def serialize_numpy(self, buff, numpy):
00468 """
00469 serialize message with numpy array types into buffer
00470 @param buff: buffer
00471 @type buff: StringIO
00472 @param numpy: numpy python module
00473 @type numpy module
00474 """
00475 try:
00476 _x = self
00477 buff.write(_struct_3I.pack(_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs))
00478 _x = self.pose.header.frame_id
00479 length = len(_x)
00480 buff.write(struct.pack('<I%ss'%length, length, _x))
00481 _x = self
00482 buff.write(_struct_10di.pack(_x.pose.pose.position.x, _x.pose.pose.position.y, _x.pose.pose.position.z, _x.pose.pose.orientation.x, _x.pose.pose.orientation.y, _x.pose.pose.orientation.z, _x.pose.pose.orientation.w, _x.box_dims.x, _x.box_dims.y, _x.box_dims.z, _x.error_code))
00483 except struct.error, se: self._check_types(se)
00484 except TypeError, te: self._check_types(te)
00485
00486 def deserialize_numpy(self, str, numpy):
00487 """
00488 unpack serialized message in str into this message instance using numpy for array types
00489 @param str: byte array of serialized message
00490 @type str: str
00491 @param numpy: numpy python module
00492 @type numpy: module
00493 """
00494 try:
00495 if self.pose is None:
00496 self.pose = geometry_msgs.msg.PoseStamped()
00497 if self.box_dims is None:
00498 self.box_dims = geometry_msgs.msg.Vector3()
00499 end = 0
00500 _x = self
00501 start = end
00502 end += 12
00503 (_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00504 start = end
00505 end += 4
00506 (length,) = _struct_I.unpack(str[start:end])
00507 start = end
00508 end += length
00509 self.pose.header.frame_id = str[start:end]
00510 _x = self
00511 start = end
00512 end += 84
00513 (_x.pose.pose.position.x, _x.pose.pose.position.y, _x.pose.pose.position.z, _x.pose.pose.orientation.x, _x.pose.pose.orientation.y, _x.pose.pose.orientation.z, _x.pose.pose.orientation.w, _x.box_dims.x, _x.box_dims.y, _x.box_dims.z, _x.error_code,) = _struct_10di.unpack(str[start:end])
00514 return self
00515 except struct.error, e:
00516 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00517
00518 _struct_I = roslib.message.struct_I
00519 _struct_3I = struct.Struct("<3I")
00520 _struct_10di = struct.Struct("<10di")
00521 class FindClusterBoundingBox(roslib.message.ServiceDefinition):
00522 _type = 'object_manipulation_msgs/FindClusterBoundingBox'
00523 _md5sum = 'b3e1553121201f262f1cdaafb1409115'
00524 _request_class = FindClusterBoundingBoxRequest
00525 _response_class = FindClusterBoundingBoxResponse