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