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