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