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