$search
00001 """autogenerated by genmsg_py from DetectionArray.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 import cob_object_detection_msgs.msg 00007 import sensor_msgs.msg 00008 import std_msgs.msg 00009 00010 class DetectionArray(roslib.message.Message): 00011 _md5sum = "8b22bfbdd23654f0350f86baa47c12f9" 00012 _type = "cob_object_detection_msgs/DetectionArray" 00013 _has_header = True #flag to mark the presence of a Header object 00014 _full_text = """Header header 00015 Detection[] detections 00016 00017 ================================================================================ 00018 MSG: std_msgs/Header 00019 # Standard metadata for higher-level stamped data types. 00020 # This is generally used to communicate timestamped data 00021 # in a particular coordinate frame. 00022 # 00023 # sequence ID: consecutively increasing ID 00024 uint32 seq 00025 #Two-integer timestamp that is expressed as: 00026 # * stamp.secs: seconds (stamp_secs) since epoch 00027 # * stamp.nsecs: nanoseconds since stamp_secs 00028 # time-handling sugar is provided by the client library 00029 time stamp 00030 #Frame this data is associated with 00031 # 0: no frame 00032 # 1: global frame 00033 string frame_id 00034 00035 ================================================================================ 00036 MSG: cob_object_detection_msgs/Detection 00037 Header header 00038 string label 00039 string detector 00040 float32 score 00041 Mask mask 00042 geometry_msgs/PoseStamped pose 00043 geometry_msgs/Point bounding_box_lwh 00044 00045 ================================================================================ 00046 MSG: cob_object_detection_msgs/Mask 00047 # this message is used to mark where an object is present in an image 00048 # this can be done either by a roi region on the image (less precise) or a mask (more precise) 00049 00050 Rect roi 00051 00052 # in the case when mask is used, 'roi' specifies the image region and 'mask' 00053 # (which should be of the same size) a binary mask in that region 00054 sensor_msgs/Image mask 00055 00056 # in the case there is 3D data available, 'indices' are used to index the 00057 # part of the point cloud representing the object 00058 #pcl/PointIndices indices 00059 00060 ================================================================================ 00061 MSG: cob_object_detection_msgs/Rect 00062 int32 x 00063 int32 y 00064 int32 width 00065 int32 height 00066 00067 ================================================================================ 00068 MSG: sensor_msgs/Image 00069 # This message contains an uncompressed image 00070 # (0, 0) is at top-left corner of image 00071 # 00072 00073 Header header # Header timestamp should be acquisition time of image 00074 # Header frame_id should be optical frame of camera 00075 # origin of frame should be optical center of cameara 00076 # +x should point to the right in the image 00077 # +y should point down in the image 00078 # +z should point into to plane of the image 00079 # If the frame_id here and the frame_id of the CameraInfo 00080 # message associated with the image conflict 00081 # the behavior is undefined 00082 00083 uint32 height # image height, that is, number of rows 00084 uint32 width # image width, that is, number of columns 00085 00086 # The legal values for encoding are in file src/image_encodings.cpp 00087 # If you want to standardize a new string format, join 00088 # ros-users@lists.sourceforge.net and send an email proposing a new encoding. 00089 00090 string encoding # Encoding of pixels -- channel meaning, ordering, size 00091 # taken from the list of strings in src/image_encodings.cpp 00092 00093 uint8 is_bigendian # is this data bigendian? 00094 uint32 step # Full row length in bytes 00095 uint8[] data # actual matrix data, size is (step * rows) 00096 00097 ================================================================================ 00098 MSG: geometry_msgs/PoseStamped 00099 # A Pose with reference coordinate frame and timestamp 00100 Header header 00101 Pose pose 00102 00103 ================================================================================ 00104 MSG: geometry_msgs/Pose 00105 # A representation of pose in free space, composed of postion and orientation. 00106 Point position 00107 Quaternion orientation 00108 00109 ================================================================================ 00110 MSG: geometry_msgs/Point 00111 # This contains the position of a point in free space 00112 float64 x 00113 float64 y 00114 float64 z 00115 00116 ================================================================================ 00117 MSG: geometry_msgs/Quaternion 00118 # This represents an orientation in free space in quaternion form. 00119 00120 float64 x 00121 float64 y 00122 float64 z 00123 float64 w 00124 00125 """ 00126 __slots__ = ['header','detections'] 00127 _slot_types = ['Header','cob_object_detection_msgs/Detection[]'] 00128 00129 def __init__(self, *args, **kwds): 00130 """ 00131 Constructor. Any message fields that are implicitly/explicitly 00132 set to None will be assigned a default value. The recommend 00133 use is keyword arguments as this is more robust to future message 00134 changes. You cannot mix in-order arguments and keyword arguments. 00135 00136 The available fields are: 00137 header,detections 00138 00139 @param args: complete set of field values, in .msg order 00140 @param kwds: use keyword arguments corresponding to message field names 00141 to set specific fields. 00142 """ 00143 if args or kwds: 00144 super(DetectionArray, self).__init__(*args, **kwds) 00145 #message fields cannot be None, assign default values for those that are 00146 if self.header is None: 00147 self.header = std_msgs.msg._Header.Header() 00148 if self.detections is None: 00149 self.detections = [] 00150 else: 00151 self.header = std_msgs.msg._Header.Header() 00152 self.detections = [] 00153 00154 def _get_types(self): 00155 """ 00156 internal API method 00157 """ 00158 return self._slot_types 00159 00160 def serialize(self, buff): 00161 """ 00162 serialize message into buffer 00163 @param buff: buffer 00164 @type buff: StringIO 00165 """ 00166 try: 00167 _x = self 00168 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00169 _x = self.header.frame_id 00170 length = len(_x) 00171 buff.write(struct.pack('<I%ss'%length, length, _x)) 00172 length = len(self.detections) 00173 buff.write(_struct_I.pack(length)) 00174 for val1 in self.detections: 00175 _v1 = val1.header 00176 buff.write(_struct_I.pack(_v1.seq)) 00177 _v2 = _v1.stamp 00178 _x = _v2 00179 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00180 _x = _v1.frame_id 00181 length = len(_x) 00182 buff.write(struct.pack('<I%ss'%length, length, _x)) 00183 _x = val1.label 00184 length = len(_x) 00185 buff.write(struct.pack('<I%ss'%length, length, _x)) 00186 _x = val1.detector 00187 length = len(_x) 00188 buff.write(struct.pack('<I%ss'%length, length, _x)) 00189 buff.write(_struct_f.pack(val1.score)) 00190 _v3 = val1.mask 00191 _v4 = _v3.roi 00192 _x = _v4 00193 buff.write(_struct_4i.pack(_x.x, _x.y, _x.width, _x.height)) 00194 _v5 = _v3.mask 00195 _v6 = _v5.header 00196 buff.write(_struct_I.pack(_v6.seq)) 00197 _v7 = _v6.stamp 00198 _x = _v7 00199 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00200 _x = _v6.frame_id 00201 length = len(_x) 00202 buff.write(struct.pack('<I%ss'%length, length, _x)) 00203 _x = _v5 00204 buff.write(_struct_2I.pack(_x.height, _x.width)) 00205 _x = _v5.encoding 00206 length = len(_x) 00207 buff.write(struct.pack('<I%ss'%length, length, _x)) 00208 _x = _v5 00209 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 00210 _x = _v5.data 00211 length = len(_x) 00212 # - if encoded as a list instead, serialize as bytes instead of string 00213 if type(_x) in [list, tuple]: 00214 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00215 else: 00216 buff.write(struct.pack('<I%ss'%length, length, _x)) 00217 _v8 = val1.pose 00218 _v9 = _v8.header 00219 buff.write(_struct_I.pack(_v9.seq)) 00220 _v10 = _v9.stamp 00221 _x = _v10 00222 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00223 _x = _v9.frame_id 00224 length = len(_x) 00225 buff.write(struct.pack('<I%ss'%length, length, _x)) 00226 _v11 = _v8.pose 00227 _v12 = _v11.position 00228 _x = _v12 00229 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00230 _v13 = _v11.orientation 00231 _x = _v13 00232 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00233 _v14 = val1.bounding_box_lwh 00234 _x = _v14 00235 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00236 except struct.error as se: self._check_types(se) 00237 except TypeError as te: self._check_types(te) 00238 00239 def deserialize(self, str): 00240 """ 00241 unpack serialized message in str into this message instance 00242 @param str: byte array of serialized message 00243 @type str: str 00244 """ 00245 try: 00246 if self.header is None: 00247 self.header = std_msgs.msg._Header.Header() 00248 end = 0 00249 _x = self 00250 start = end 00251 end += 12 00252 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00253 start = end 00254 end += 4 00255 (length,) = _struct_I.unpack(str[start:end]) 00256 start = end 00257 end += length 00258 self.header.frame_id = str[start:end] 00259 start = end 00260 end += 4 00261 (length,) = _struct_I.unpack(str[start:end]) 00262 self.detections = [] 00263 for i in range(0, length): 00264 val1 = cob_object_detection_msgs.msg.Detection() 00265 _v15 = val1.header 00266 start = end 00267 end += 4 00268 (_v15.seq,) = _struct_I.unpack(str[start:end]) 00269 _v16 = _v15.stamp 00270 _x = _v16 00271 start = end 00272 end += 8 00273 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00274 start = end 00275 end += 4 00276 (length,) = _struct_I.unpack(str[start:end]) 00277 start = end 00278 end += length 00279 _v15.frame_id = str[start:end] 00280 start = end 00281 end += 4 00282 (length,) = _struct_I.unpack(str[start:end]) 00283 start = end 00284 end += length 00285 val1.label = str[start:end] 00286 start = end 00287 end += 4 00288 (length,) = _struct_I.unpack(str[start:end]) 00289 start = end 00290 end += length 00291 val1.detector = str[start:end] 00292 start = end 00293 end += 4 00294 (val1.score,) = _struct_f.unpack(str[start:end]) 00295 _v17 = val1.mask 00296 _v18 = _v17.roi 00297 _x = _v18 00298 start = end 00299 end += 16 00300 (_x.x, _x.y, _x.width, _x.height,) = _struct_4i.unpack(str[start:end]) 00301 _v19 = _v17.mask 00302 _v20 = _v19.header 00303 start = end 00304 end += 4 00305 (_v20.seq,) = _struct_I.unpack(str[start:end]) 00306 _v21 = _v20.stamp 00307 _x = _v21 00308 start = end 00309 end += 8 00310 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00311 start = end 00312 end += 4 00313 (length,) = _struct_I.unpack(str[start:end]) 00314 start = end 00315 end += length 00316 _v20.frame_id = str[start:end] 00317 _x = _v19 00318 start = end 00319 end += 8 00320 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 00321 start = end 00322 end += 4 00323 (length,) = _struct_I.unpack(str[start:end]) 00324 start = end 00325 end += length 00326 _v19.encoding = str[start:end] 00327 _x = _v19 00328 start = end 00329 end += 5 00330 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 00331 start = end 00332 end += 4 00333 (length,) = _struct_I.unpack(str[start:end]) 00334 start = end 00335 end += length 00336 _v19.data = str[start:end] 00337 _v22 = val1.pose 00338 _v23 = _v22.header 00339 start = end 00340 end += 4 00341 (_v23.seq,) = _struct_I.unpack(str[start:end]) 00342 _v24 = _v23.stamp 00343 _x = _v24 00344 start = end 00345 end += 8 00346 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00347 start = end 00348 end += 4 00349 (length,) = _struct_I.unpack(str[start:end]) 00350 start = end 00351 end += length 00352 _v23.frame_id = str[start:end] 00353 _v25 = _v22.pose 00354 _v26 = _v25.position 00355 _x = _v26 00356 start = end 00357 end += 24 00358 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00359 _v27 = _v25.orientation 00360 _x = _v27 00361 start = end 00362 end += 32 00363 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00364 _v28 = val1.bounding_box_lwh 00365 _x = _v28 00366 start = end 00367 end += 24 00368 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00369 self.detections.append(val1) 00370 return self 00371 except struct.error as e: 00372 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00373 00374 00375 def serialize_numpy(self, buff, numpy): 00376 """ 00377 serialize message with numpy array types into buffer 00378 @param buff: buffer 00379 @type buff: StringIO 00380 @param numpy: numpy python module 00381 @type numpy module 00382 """ 00383 try: 00384 _x = self 00385 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00386 _x = self.header.frame_id 00387 length = len(_x) 00388 buff.write(struct.pack('<I%ss'%length, length, _x)) 00389 length = len(self.detections) 00390 buff.write(_struct_I.pack(length)) 00391 for val1 in self.detections: 00392 _v29 = val1.header 00393 buff.write(_struct_I.pack(_v29.seq)) 00394 _v30 = _v29.stamp 00395 _x = _v30 00396 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00397 _x = _v29.frame_id 00398 length = len(_x) 00399 buff.write(struct.pack('<I%ss'%length, length, _x)) 00400 _x = val1.label 00401 length = len(_x) 00402 buff.write(struct.pack('<I%ss'%length, length, _x)) 00403 _x = val1.detector 00404 length = len(_x) 00405 buff.write(struct.pack('<I%ss'%length, length, _x)) 00406 buff.write(_struct_f.pack(val1.score)) 00407 _v31 = val1.mask 00408 _v32 = _v31.roi 00409 _x = _v32 00410 buff.write(_struct_4i.pack(_x.x, _x.y, _x.width, _x.height)) 00411 _v33 = _v31.mask 00412 _v34 = _v33.header 00413 buff.write(_struct_I.pack(_v34.seq)) 00414 _v35 = _v34.stamp 00415 _x = _v35 00416 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00417 _x = _v34.frame_id 00418 length = len(_x) 00419 buff.write(struct.pack('<I%ss'%length, length, _x)) 00420 _x = _v33 00421 buff.write(_struct_2I.pack(_x.height, _x.width)) 00422 _x = _v33.encoding 00423 length = len(_x) 00424 buff.write(struct.pack('<I%ss'%length, length, _x)) 00425 _x = _v33 00426 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 00427 _x = _v33.data 00428 length = len(_x) 00429 # - if encoded as a list instead, serialize as bytes instead of string 00430 if type(_x) in [list, tuple]: 00431 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00432 else: 00433 buff.write(struct.pack('<I%ss'%length, length, _x)) 00434 _v36 = val1.pose 00435 _v37 = _v36.header 00436 buff.write(_struct_I.pack(_v37.seq)) 00437 _v38 = _v37.stamp 00438 _x = _v38 00439 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00440 _x = _v37.frame_id 00441 length = len(_x) 00442 buff.write(struct.pack('<I%ss'%length, length, _x)) 00443 _v39 = _v36.pose 00444 _v40 = _v39.position 00445 _x = _v40 00446 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00447 _v41 = _v39.orientation 00448 _x = _v41 00449 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00450 _v42 = val1.bounding_box_lwh 00451 _x = _v42 00452 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00453 except struct.error as se: self._check_types(se) 00454 except TypeError as te: self._check_types(te) 00455 00456 def deserialize_numpy(self, str, numpy): 00457 """ 00458 unpack serialized message in str into this message instance using numpy for array types 00459 @param str: byte array of serialized message 00460 @type str: str 00461 @param numpy: numpy python module 00462 @type numpy: module 00463 """ 00464 try: 00465 if self.header is None: 00466 self.header = std_msgs.msg._Header.Header() 00467 end = 0 00468 _x = self 00469 start = end 00470 end += 12 00471 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00472 start = end 00473 end += 4 00474 (length,) = _struct_I.unpack(str[start:end]) 00475 start = end 00476 end += length 00477 self.header.frame_id = str[start:end] 00478 start = end 00479 end += 4 00480 (length,) = _struct_I.unpack(str[start:end]) 00481 self.detections = [] 00482 for i in range(0, length): 00483 val1 = cob_object_detection_msgs.msg.Detection() 00484 _v43 = val1.header 00485 start = end 00486 end += 4 00487 (_v43.seq,) = _struct_I.unpack(str[start:end]) 00488 _v44 = _v43.stamp 00489 _x = _v44 00490 start = end 00491 end += 8 00492 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00493 start = end 00494 end += 4 00495 (length,) = _struct_I.unpack(str[start:end]) 00496 start = end 00497 end += length 00498 _v43.frame_id = str[start:end] 00499 start = end 00500 end += 4 00501 (length,) = _struct_I.unpack(str[start:end]) 00502 start = end 00503 end += length 00504 val1.label = str[start:end] 00505 start = end 00506 end += 4 00507 (length,) = _struct_I.unpack(str[start:end]) 00508 start = end 00509 end += length 00510 val1.detector = str[start:end] 00511 start = end 00512 end += 4 00513 (val1.score,) = _struct_f.unpack(str[start:end]) 00514 _v45 = val1.mask 00515 _v46 = _v45.roi 00516 _x = _v46 00517 start = end 00518 end += 16 00519 (_x.x, _x.y, _x.width, _x.height,) = _struct_4i.unpack(str[start:end]) 00520 _v47 = _v45.mask 00521 _v48 = _v47.header 00522 start = end 00523 end += 4 00524 (_v48.seq,) = _struct_I.unpack(str[start:end]) 00525 _v49 = _v48.stamp 00526 _x = _v49 00527 start = end 00528 end += 8 00529 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00530 start = end 00531 end += 4 00532 (length,) = _struct_I.unpack(str[start:end]) 00533 start = end 00534 end += length 00535 _v48.frame_id = str[start:end] 00536 _x = _v47 00537 start = end 00538 end += 8 00539 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 00540 start = end 00541 end += 4 00542 (length,) = _struct_I.unpack(str[start:end]) 00543 start = end 00544 end += length 00545 _v47.encoding = str[start:end] 00546 _x = _v47 00547 start = end 00548 end += 5 00549 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 00550 start = end 00551 end += 4 00552 (length,) = _struct_I.unpack(str[start:end]) 00553 start = end 00554 end += length 00555 _v47.data = str[start:end] 00556 _v50 = val1.pose 00557 _v51 = _v50.header 00558 start = end 00559 end += 4 00560 (_v51.seq,) = _struct_I.unpack(str[start:end]) 00561 _v52 = _v51.stamp 00562 _x = _v52 00563 start = end 00564 end += 8 00565 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00566 start = end 00567 end += 4 00568 (length,) = _struct_I.unpack(str[start:end]) 00569 start = end 00570 end += length 00571 _v51.frame_id = str[start:end] 00572 _v53 = _v50.pose 00573 _v54 = _v53.position 00574 _x = _v54 00575 start = end 00576 end += 24 00577 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00578 _v55 = _v53.orientation 00579 _x = _v55 00580 start = end 00581 end += 32 00582 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00583 _v56 = val1.bounding_box_lwh 00584 _x = _v56 00585 start = end 00586 end += 24 00587 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00588 self.detections.append(val1) 00589 return self 00590 except struct.error as e: 00591 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00592 00593 _struct_I = roslib.message.struct_I 00594 _struct_f = struct.Struct("<f") 00595 _struct_BI = struct.Struct("<BI") 00596 _struct_3I = struct.Struct("<3I") 00597 _struct_4i = struct.Struct("<4i") 00598 _struct_4d = struct.Struct("<4d") 00599 _struct_2I = struct.Struct("<2I") 00600 _struct_3d = struct.Struct("<3d")