00001 """autogenerated by genpy from cob_object_detection_msgs/DetectObjectsAction.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 DetectObjectsAction(genpy.Message):
00015 _md5sum = "7cd45bb56e2daab5a041ec3ff94337d3"
00016 _type = "cob_object_detection_msgs/DetectObjectsAction"
00017 _has_header = False
00018 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019
00020 DetectObjectsActionGoal action_goal
00021 DetectObjectsActionResult action_result
00022 DetectObjectsActionFeedback action_feedback
00023
00024 ================================================================================
00025 MSG: cob_object_detection_msgs/DetectObjectsActionGoal
00026 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00027
00028 Header header
00029 actionlib_msgs/GoalID goal_id
00030 DetectObjectsGoal goal
00031
00032 ================================================================================
00033 MSG: std_msgs/Header
00034 # Standard metadata for higher-level stamped data types.
00035 # This is generally used to communicate timestamped data
00036 # in a particular coordinate frame.
00037 #
00038 # sequence ID: consecutively increasing ID
00039 uint32 seq
00040 #Two-integer timestamp that is expressed as:
00041 # * stamp.secs: seconds (stamp_secs) since epoch
00042 # * stamp.nsecs: nanoseconds since stamp_secs
00043 # time-handling sugar is provided by the client library
00044 time stamp
00045 #Frame this data is associated with
00046 # 0: no frame
00047 # 1: global frame
00048 string frame_id
00049
00050 ================================================================================
00051 MSG: actionlib_msgs/GoalID
00052 # The stamp should store the time at which this goal was requested.
00053 # It is used by an action server when it tries to preempt all
00054 # goals that were requested before a certain time
00055 time stamp
00056
00057 # The id provides a way to associate feedback and
00058 # result message with specific goal requests. The id
00059 # specified must be unique.
00060 string id
00061
00062
00063 ================================================================================
00064 MSG: cob_object_detection_msgs/DetectObjectsGoal
00065 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00066 # The goal
00067 std_msgs/String object_name
00068
00069 ================================================================================
00070 MSG: std_msgs/String
00071 string data
00072
00073 ================================================================================
00074 MSG: cob_object_detection_msgs/DetectObjectsActionResult
00075 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00076
00077 Header header
00078 actionlib_msgs/GoalStatus status
00079 DetectObjectsResult result
00080
00081 ================================================================================
00082 MSG: actionlib_msgs/GoalStatus
00083 GoalID goal_id
00084 uint8 status
00085 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00086 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00087 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00088 # and has since completed its execution (Terminal State)
00089 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00090 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00091 # to some failure (Terminal State)
00092 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00093 # because the goal was unattainable or invalid (Terminal State)
00094 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00095 # and has not yet completed execution
00096 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00097 # but the action server has not yet confirmed that the goal is canceled
00098 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00099 # and was successfully cancelled (Terminal State)
00100 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00101 # sent over the wire by an action server
00102
00103 #Allow for the user to associate a string with GoalStatus for debugging
00104 string text
00105
00106
00107 ================================================================================
00108 MSG: cob_object_detection_msgs/DetectObjectsResult
00109 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00110 # The result
00111 cob_object_detection_msgs/DetectionArray object_list
00112
00113 ================================================================================
00114 MSG: cob_object_detection_msgs/DetectionArray
00115 Header header
00116 Detection[] detections
00117
00118 ================================================================================
00119 MSG: cob_object_detection_msgs/Detection
00120 Header header
00121 string label
00122 string detector
00123 float32 score
00124 Mask mask
00125 geometry_msgs/PoseStamped pose
00126 geometry_msgs/Point bounding_box_lwh
00127
00128 ================================================================================
00129 MSG: cob_object_detection_msgs/Mask
00130 # this message is used to mark where an object is present in an image
00131 # this can be done either by a roi region on the image (less precise) or a mask (more precise)
00132
00133 Rect roi
00134
00135 # in the case when mask is used, 'roi' specifies the image region and 'mask'
00136 # (which should be of the same size) a binary mask in that region
00137 sensor_msgs/Image mask
00138
00139 # in the case there is 3D data available, 'indices' are used to index the
00140 # part of the point cloud representing the object
00141 #pcl/PointIndices indices
00142
00143 ================================================================================
00144 MSG: cob_object_detection_msgs/Rect
00145 int32 x
00146 int32 y
00147 int32 width
00148 int32 height
00149
00150 ================================================================================
00151 MSG: sensor_msgs/Image
00152 # This message contains an uncompressed image
00153 # (0, 0) is at top-left corner of image
00154 #
00155
00156 Header header # Header timestamp should be acquisition time of image
00157 # Header frame_id should be optical frame of camera
00158 # origin of frame should be optical center of cameara
00159 # +x should point to the right in the image
00160 # +y should point down in the image
00161 # +z should point into to plane of the image
00162 # If the frame_id here and the frame_id of the CameraInfo
00163 # message associated with the image conflict
00164 # the behavior is undefined
00165
00166 uint32 height # image height, that is, number of rows
00167 uint32 width # image width, that is, number of columns
00168
00169 # The legal values for encoding are in file src/image_encodings.cpp
00170 # If you want to standardize a new string format, join
00171 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00172
00173 string encoding # Encoding of pixels -- channel meaning, ordering, size
00174 # taken from the list of strings in include/sensor_msgs/image_encodings.h
00175
00176 uint8 is_bigendian # is this data bigendian?
00177 uint32 step # Full row length in bytes
00178 uint8[] data # actual matrix data, size is (step * rows)
00179
00180 ================================================================================
00181 MSG: geometry_msgs/PoseStamped
00182 # A Pose with reference coordinate frame and timestamp
00183 Header header
00184 Pose pose
00185
00186 ================================================================================
00187 MSG: geometry_msgs/Pose
00188 # A representation of pose in free space, composed of postion and orientation.
00189 Point position
00190 Quaternion orientation
00191
00192 ================================================================================
00193 MSG: geometry_msgs/Point
00194 # This contains the position of a point in free space
00195 float64 x
00196 float64 y
00197 float64 z
00198
00199 ================================================================================
00200 MSG: geometry_msgs/Quaternion
00201 # This represents an orientation in free space in quaternion form.
00202
00203 float64 x
00204 float64 y
00205 float64 z
00206 float64 w
00207
00208 ================================================================================
00209 MSG: cob_object_detection_msgs/DetectObjectsActionFeedback
00210 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00211
00212 Header header
00213 actionlib_msgs/GoalStatus status
00214 DetectObjectsFeedback feedback
00215
00216 ================================================================================
00217 MSG: cob_object_detection_msgs/DetectObjectsFeedback
00218 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00219 # The feedback
00220 float32 percent_complete
00221
00222
00223 """
00224 __slots__ = ['action_goal','action_result','action_feedback']
00225 _slot_types = ['cob_object_detection_msgs/DetectObjectsActionGoal','cob_object_detection_msgs/DetectObjectsActionResult','cob_object_detection_msgs/DetectObjectsActionFeedback']
00226
00227 def __init__(self, *args, **kwds):
00228 """
00229 Constructor. Any message fields that are implicitly/explicitly
00230 set to None will be assigned a default value. The recommend
00231 use is keyword arguments as this is more robust to future message
00232 changes. You cannot mix in-order arguments and keyword arguments.
00233
00234 The available fields are:
00235 action_goal,action_result,action_feedback
00236
00237 :param args: complete set of field values, in .msg order
00238 :param kwds: use keyword arguments corresponding to message field names
00239 to set specific fields.
00240 """
00241 if args or kwds:
00242 super(DetectObjectsAction, self).__init__(*args, **kwds)
00243
00244 if self.action_goal is None:
00245 self.action_goal = cob_object_detection_msgs.msg.DetectObjectsActionGoal()
00246 if self.action_result is None:
00247 self.action_result = cob_object_detection_msgs.msg.DetectObjectsActionResult()
00248 if self.action_feedback is None:
00249 self.action_feedback = cob_object_detection_msgs.msg.DetectObjectsActionFeedback()
00250 else:
00251 self.action_goal = cob_object_detection_msgs.msg.DetectObjectsActionGoal()
00252 self.action_result = cob_object_detection_msgs.msg.DetectObjectsActionResult()
00253 self.action_feedback = cob_object_detection_msgs.msg.DetectObjectsActionFeedback()
00254
00255 def _get_types(self):
00256 """
00257 internal API method
00258 """
00259 return self._slot_types
00260
00261 def serialize(self, buff):
00262 """
00263 serialize message into buffer
00264 :param buff: buffer, ``StringIO``
00265 """
00266 try:
00267 _x = self
00268 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00269 _x = self.action_goal.header.frame_id
00270 length = len(_x)
00271 if python3 or type(_x) == unicode:
00272 _x = _x.encode('utf-8')
00273 length = len(_x)
00274 buff.write(struct.pack('<I%ss'%length, length, _x))
00275 _x = self
00276 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00277 _x = self.action_goal.goal_id.id
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 _x = self.action_goal.goal.object_name.data
00284 length = len(_x)
00285 if python3 or type(_x) == unicode:
00286 _x = _x.encode('utf-8')
00287 length = len(_x)
00288 buff.write(struct.pack('<I%ss'%length, length, _x))
00289 _x = self
00290 buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00291 _x = self.action_result.header.frame_id
00292 length = len(_x)
00293 if python3 or type(_x) == unicode:
00294 _x = _x.encode('utf-8')
00295 length = len(_x)
00296 buff.write(struct.pack('<I%ss'%length, length, _x))
00297 _x = self
00298 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00299 _x = self.action_result.status.goal_id.id
00300 length = len(_x)
00301 if python3 or type(_x) == unicode:
00302 _x = _x.encode('utf-8')
00303 length = len(_x)
00304 buff.write(struct.pack('<I%ss'%length, length, _x))
00305 buff.write(_struct_B.pack(self.action_result.status.status))
00306 _x = self.action_result.status.text
00307 length = len(_x)
00308 if python3 or type(_x) == unicode:
00309 _x = _x.encode('utf-8')
00310 length = len(_x)
00311 buff.write(struct.pack('<I%ss'%length, length, _x))
00312 _x = self
00313 buff.write(_struct_3I.pack(_x.action_result.result.object_list.header.seq, _x.action_result.result.object_list.header.stamp.secs, _x.action_result.result.object_list.header.stamp.nsecs))
00314 _x = self.action_result.result.object_list.header.frame_id
00315 length = len(_x)
00316 if python3 or type(_x) == unicode:
00317 _x = _x.encode('utf-8')
00318 length = len(_x)
00319 buff.write(struct.pack('<I%ss'%length, length, _x))
00320 length = len(self.action_result.result.object_list.detections)
00321 buff.write(_struct_I.pack(length))
00322 for val1 in self.action_result.result.object_list.detections:
00323 _v1 = val1.header
00324 buff.write(_struct_I.pack(_v1.seq))
00325 _v2 = _v1.stamp
00326 _x = _v2
00327 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00328 _x = _v1.frame_id
00329 length = len(_x)
00330 if python3 or type(_x) == unicode:
00331 _x = _x.encode('utf-8')
00332 length = len(_x)
00333 buff.write(struct.pack('<I%ss'%length, length, _x))
00334 _x = val1.label
00335 length = len(_x)
00336 if python3 or type(_x) == unicode:
00337 _x = _x.encode('utf-8')
00338 length = len(_x)
00339 buff.write(struct.pack('<I%ss'%length, length, _x))
00340 _x = val1.detector
00341 length = len(_x)
00342 if python3 or type(_x) == unicode:
00343 _x = _x.encode('utf-8')
00344 length = len(_x)
00345 buff.write(struct.pack('<I%ss'%length, length, _x))
00346 buff.write(_struct_f.pack(val1.score))
00347 _v3 = val1.mask
00348 _v4 = _v3.roi
00349 _x = _v4
00350 buff.write(_struct_4i.pack(_x.x, _x.y, _x.width, _x.height))
00351 _v5 = _v3.mask
00352 _v6 = _v5.header
00353 buff.write(_struct_I.pack(_v6.seq))
00354 _v7 = _v6.stamp
00355 _x = _v7
00356 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00357 _x = _v6.frame_id
00358 length = len(_x)
00359 if python3 or type(_x) == unicode:
00360 _x = _x.encode('utf-8')
00361 length = len(_x)
00362 buff.write(struct.pack('<I%ss'%length, length, _x))
00363 _x = _v5
00364 buff.write(_struct_2I.pack(_x.height, _x.width))
00365 _x = _v5.encoding
00366 length = len(_x)
00367 if python3 or type(_x) == unicode:
00368 _x = _x.encode('utf-8')
00369 length = len(_x)
00370 buff.write(struct.pack('<I%ss'%length, length, _x))
00371 _x = _v5
00372 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00373 _x = _v5.data
00374 length = len(_x)
00375
00376 if type(_x) in [list, tuple]:
00377 buff.write(struct.pack('<I%sB'%length, length, *_x))
00378 else:
00379 buff.write(struct.pack('<I%ss'%length, length, _x))
00380 _v8 = val1.pose
00381 _v9 = _v8.header
00382 buff.write(_struct_I.pack(_v9.seq))
00383 _v10 = _v9.stamp
00384 _x = _v10
00385 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00386 _x = _v9.frame_id
00387 length = len(_x)
00388 if python3 or type(_x) == unicode:
00389 _x = _x.encode('utf-8')
00390 length = len(_x)
00391 buff.write(struct.pack('<I%ss'%length, length, _x))
00392 _v11 = _v8.pose
00393 _v12 = _v11.position
00394 _x = _v12
00395 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00396 _v13 = _v11.orientation
00397 _x = _v13
00398 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00399 _v14 = val1.bounding_box_lwh
00400 _x = _v14
00401 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00402 _x = self
00403 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00404 _x = self.action_feedback.header.frame_id
00405 length = len(_x)
00406 if python3 or type(_x) == unicode:
00407 _x = _x.encode('utf-8')
00408 length = len(_x)
00409 buff.write(struct.pack('<I%ss'%length, length, _x))
00410 _x = self
00411 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00412 _x = self.action_feedback.status.goal_id.id
00413 length = len(_x)
00414 if python3 or type(_x) == unicode:
00415 _x = _x.encode('utf-8')
00416 length = len(_x)
00417 buff.write(struct.pack('<I%ss'%length, length, _x))
00418 buff.write(_struct_B.pack(self.action_feedback.status.status))
00419 _x = self.action_feedback.status.text
00420 length = len(_x)
00421 if python3 or type(_x) == unicode:
00422 _x = _x.encode('utf-8')
00423 length = len(_x)
00424 buff.write(struct.pack('<I%ss'%length, length, _x))
00425 buff.write(_struct_f.pack(self.action_feedback.feedback.percent_complete))
00426 except struct.error as se: self._check_types(se)
00427 except TypeError as te: self._check_types(te)
00428
00429 def deserialize(self, str):
00430 """
00431 unpack serialized message in str into this message instance
00432 :param str: byte array of serialized message, ``str``
00433 """
00434 try:
00435 if self.action_goal is None:
00436 self.action_goal = cob_object_detection_msgs.msg.DetectObjectsActionGoal()
00437 if self.action_result is None:
00438 self.action_result = cob_object_detection_msgs.msg.DetectObjectsActionResult()
00439 if self.action_feedback is None:
00440 self.action_feedback = cob_object_detection_msgs.msg.DetectObjectsActionFeedback()
00441 end = 0
00442 _x = self
00443 start = end
00444 end += 12
00445 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00446 start = end
00447 end += 4
00448 (length,) = _struct_I.unpack(str[start:end])
00449 start = end
00450 end += length
00451 if python3:
00452 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00453 else:
00454 self.action_goal.header.frame_id = str[start:end]
00455 _x = self
00456 start = end
00457 end += 8
00458 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00459 start = end
00460 end += 4
00461 (length,) = _struct_I.unpack(str[start:end])
00462 start = end
00463 end += length
00464 if python3:
00465 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00466 else:
00467 self.action_goal.goal_id.id = str[start:end]
00468 start = end
00469 end += 4
00470 (length,) = _struct_I.unpack(str[start:end])
00471 start = end
00472 end += length
00473 if python3:
00474 self.action_goal.goal.object_name.data = str[start:end].decode('utf-8')
00475 else:
00476 self.action_goal.goal.object_name.data = str[start:end]
00477 _x = self
00478 start = end
00479 end += 12
00480 (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.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 if python3:
00487 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00488 else:
00489 self.action_result.header.frame_id = str[start:end]
00490 _x = self
00491 start = end
00492 end += 8
00493 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00494 start = end
00495 end += 4
00496 (length,) = _struct_I.unpack(str[start:end])
00497 start = end
00498 end += length
00499 if python3:
00500 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00501 else:
00502 self.action_result.status.goal_id.id = str[start:end]
00503 start = end
00504 end += 1
00505 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00506 start = end
00507 end += 4
00508 (length,) = _struct_I.unpack(str[start:end])
00509 start = end
00510 end += length
00511 if python3:
00512 self.action_result.status.text = str[start:end].decode('utf-8')
00513 else:
00514 self.action_result.status.text = str[start:end]
00515 _x = self
00516 start = end
00517 end += 12
00518 (_x.action_result.result.object_list.header.seq, _x.action_result.result.object_list.header.stamp.secs, _x.action_result.result.object_list.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00519 start = end
00520 end += 4
00521 (length,) = _struct_I.unpack(str[start:end])
00522 start = end
00523 end += length
00524 if python3:
00525 self.action_result.result.object_list.header.frame_id = str[start:end].decode('utf-8')
00526 else:
00527 self.action_result.result.object_list.header.frame_id = str[start:end]
00528 start = end
00529 end += 4
00530 (length,) = _struct_I.unpack(str[start:end])
00531 self.action_result.result.object_list.detections = []
00532 for i in range(0, length):
00533 val1 = cob_object_detection_msgs.msg.Detection()
00534 _v15 = val1.header
00535 start = end
00536 end += 4
00537 (_v15.seq,) = _struct_I.unpack(str[start:end])
00538 _v16 = _v15.stamp
00539 _x = _v16
00540 start = end
00541 end += 8
00542 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00543 start = end
00544 end += 4
00545 (length,) = _struct_I.unpack(str[start:end])
00546 start = end
00547 end += length
00548 if python3:
00549 _v15.frame_id = str[start:end].decode('utf-8')
00550 else:
00551 _v15.frame_id = str[start:end]
00552 start = end
00553 end += 4
00554 (length,) = _struct_I.unpack(str[start:end])
00555 start = end
00556 end += length
00557 if python3:
00558 val1.label = str[start:end].decode('utf-8')
00559 else:
00560 val1.label = str[start:end]
00561 start = end
00562 end += 4
00563 (length,) = _struct_I.unpack(str[start:end])
00564 start = end
00565 end += length
00566 if python3:
00567 val1.detector = str[start:end].decode('utf-8')
00568 else:
00569 val1.detector = str[start:end]
00570 start = end
00571 end += 4
00572 (val1.score,) = _struct_f.unpack(str[start:end])
00573 _v17 = val1.mask
00574 _v18 = _v17.roi
00575 _x = _v18
00576 start = end
00577 end += 16
00578 (_x.x, _x.y, _x.width, _x.height,) = _struct_4i.unpack(str[start:end])
00579 _v19 = _v17.mask
00580 _v20 = _v19.header
00581 start = end
00582 end += 4
00583 (_v20.seq,) = _struct_I.unpack(str[start:end])
00584 _v21 = _v20.stamp
00585 _x = _v21
00586 start = end
00587 end += 8
00588 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00589 start = end
00590 end += 4
00591 (length,) = _struct_I.unpack(str[start:end])
00592 start = end
00593 end += length
00594 if python3:
00595 _v20.frame_id = str[start:end].decode('utf-8')
00596 else:
00597 _v20.frame_id = str[start:end]
00598 _x = _v19
00599 start = end
00600 end += 8
00601 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00602 start = end
00603 end += 4
00604 (length,) = _struct_I.unpack(str[start:end])
00605 start = end
00606 end += length
00607 if python3:
00608 _v19.encoding = str[start:end].decode('utf-8')
00609 else:
00610 _v19.encoding = str[start:end]
00611 _x = _v19
00612 start = end
00613 end += 5
00614 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
00615 start = end
00616 end += 4
00617 (length,) = _struct_I.unpack(str[start:end])
00618 start = end
00619 end += length
00620 if python3:
00621 _v19.data = str[start:end].decode('utf-8')
00622 else:
00623 _v19.data = str[start:end]
00624 _v22 = val1.pose
00625 _v23 = _v22.header
00626 start = end
00627 end += 4
00628 (_v23.seq,) = _struct_I.unpack(str[start:end])
00629 _v24 = _v23.stamp
00630 _x = _v24
00631 start = end
00632 end += 8
00633 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00634 start = end
00635 end += 4
00636 (length,) = _struct_I.unpack(str[start:end])
00637 start = end
00638 end += length
00639 if python3:
00640 _v23.frame_id = str[start:end].decode('utf-8')
00641 else:
00642 _v23.frame_id = str[start:end]
00643 _v25 = _v22.pose
00644 _v26 = _v25.position
00645 _x = _v26
00646 start = end
00647 end += 24
00648 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00649 _v27 = _v25.orientation
00650 _x = _v27
00651 start = end
00652 end += 32
00653 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00654 _v28 = val1.bounding_box_lwh
00655 _x = _v28
00656 start = end
00657 end += 24
00658 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00659 self.action_result.result.object_list.detections.append(val1)
00660 _x = self
00661 start = end
00662 end += 12
00663 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00664 start = end
00665 end += 4
00666 (length,) = _struct_I.unpack(str[start:end])
00667 start = end
00668 end += length
00669 if python3:
00670 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00671 else:
00672 self.action_feedback.header.frame_id = str[start:end]
00673 _x = self
00674 start = end
00675 end += 8
00676 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00677 start = end
00678 end += 4
00679 (length,) = _struct_I.unpack(str[start:end])
00680 start = end
00681 end += length
00682 if python3:
00683 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00684 else:
00685 self.action_feedback.status.goal_id.id = str[start:end]
00686 start = end
00687 end += 1
00688 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00689 start = end
00690 end += 4
00691 (length,) = _struct_I.unpack(str[start:end])
00692 start = end
00693 end += length
00694 if python3:
00695 self.action_feedback.status.text = str[start:end].decode('utf-8')
00696 else:
00697 self.action_feedback.status.text = str[start:end]
00698 start = end
00699 end += 4
00700 (self.action_feedback.feedback.percent_complete,) = _struct_f.unpack(str[start:end])
00701 return self
00702 except struct.error as e:
00703 raise genpy.DeserializationError(e)
00704
00705
00706 def serialize_numpy(self, buff, numpy):
00707 """
00708 serialize message with numpy array types into buffer
00709 :param buff: buffer, ``StringIO``
00710 :param numpy: numpy python module
00711 """
00712 try:
00713 _x = self
00714 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00715 _x = self.action_goal.header.frame_id
00716 length = len(_x)
00717 if python3 or type(_x) == unicode:
00718 _x = _x.encode('utf-8')
00719 length = len(_x)
00720 buff.write(struct.pack('<I%ss'%length, length, _x))
00721 _x = self
00722 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00723 _x = self.action_goal.goal_id.id
00724 length = len(_x)
00725 if python3 or type(_x) == unicode:
00726 _x = _x.encode('utf-8')
00727 length = len(_x)
00728 buff.write(struct.pack('<I%ss'%length, length, _x))
00729 _x = self.action_goal.goal.object_name.data
00730 length = len(_x)
00731 if python3 or type(_x) == unicode:
00732 _x = _x.encode('utf-8')
00733 length = len(_x)
00734 buff.write(struct.pack('<I%ss'%length, length, _x))
00735 _x = self
00736 buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00737 _x = self.action_result.header.frame_id
00738 length = len(_x)
00739 if python3 or type(_x) == unicode:
00740 _x = _x.encode('utf-8')
00741 length = len(_x)
00742 buff.write(struct.pack('<I%ss'%length, length, _x))
00743 _x = self
00744 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00745 _x = self.action_result.status.goal_id.id
00746 length = len(_x)
00747 if python3 or type(_x) == unicode:
00748 _x = _x.encode('utf-8')
00749 length = len(_x)
00750 buff.write(struct.pack('<I%ss'%length, length, _x))
00751 buff.write(_struct_B.pack(self.action_result.status.status))
00752 _x = self.action_result.status.text
00753 length = len(_x)
00754 if python3 or type(_x) == unicode:
00755 _x = _x.encode('utf-8')
00756 length = len(_x)
00757 buff.write(struct.pack('<I%ss'%length, length, _x))
00758 _x = self
00759 buff.write(_struct_3I.pack(_x.action_result.result.object_list.header.seq, _x.action_result.result.object_list.header.stamp.secs, _x.action_result.result.object_list.header.stamp.nsecs))
00760 _x = self.action_result.result.object_list.header.frame_id
00761 length = len(_x)
00762 if python3 or type(_x) == unicode:
00763 _x = _x.encode('utf-8')
00764 length = len(_x)
00765 buff.write(struct.pack('<I%ss'%length, length, _x))
00766 length = len(self.action_result.result.object_list.detections)
00767 buff.write(_struct_I.pack(length))
00768 for val1 in self.action_result.result.object_list.detections:
00769 _v29 = val1.header
00770 buff.write(_struct_I.pack(_v29.seq))
00771 _v30 = _v29.stamp
00772 _x = _v30
00773 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00774 _x = _v29.frame_id
00775 length = len(_x)
00776 if python3 or type(_x) == unicode:
00777 _x = _x.encode('utf-8')
00778 length = len(_x)
00779 buff.write(struct.pack('<I%ss'%length, length, _x))
00780 _x = val1.label
00781 length = len(_x)
00782 if python3 or type(_x) == unicode:
00783 _x = _x.encode('utf-8')
00784 length = len(_x)
00785 buff.write(struct.pack('<I%ss'%length, length, _x))
00786 _x = val1.detector
00787 length = len(_x)
00788 if python3 or type(_x) == unicode:
00789 _x = _x.encode('utf-8')
00790 length = len(_x)
00791 buff.write(struct.pack('<I%ss'%length, length, _x))
00792 buff.write(_struct_f.pack(val1.score))
00793 _v31 = val1.mask
00794 _v32 = _v31.roi
00795 _x = _v32
00796 buff.write(_struct_4i.pack(_x.x, _x.y, _x.width, _x.height))
00797 _v33 = _v31.mask
00798 _v34 = _v33.header
00799 buff.write(_struct_I.pack(_v34.seq))
00800 _v35 = _v34.stamp
00801 _x = _v35
00802 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00803 _x = _v34.frame_id
00804 length = len(_x)
00805 if python3 or type(_x) == unicode:
00806 _x = _x.encode('utf-8')
00807 length = len(_x)
00808 buff.write(struct.pack('<I%ss'%length, length, _x))
00809 _x = _v33
00810 buff.write(_struct_2I.pack(_x.height, _x.width))
00811 _x = _v33.encoding
00812 length = len(_x)
00813 if python3 or type(_x) == unicode:
00814 _x = _x.encode('utf-8')
00815 length = len(_x)
00816 buff.write(struct.pack('<I%ss'%length, length, _x))
00817 _x = _v33
00818 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00819 _x = _v33.data
00820 length = len(_x)
00821
00822 if type(_x) in [list, tuple]:
00823 buff.write(struct.pack('<I%sB'%length, length, *_x))
00824 else:
00825 buff.write(struct.pack('<I%ss'%length, length, _x))
00826 _v36 = val1.pose
00827 _v37 = _v36.header
00828 buff.write(_struct_I.pack(_v37.seq))
00829 _v38 = _v37.stamp
00830 _x = _v38
00831 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00832 _x = _v37.frame_id
00833 length = len(_x)
00834 if python3 or type(_x) == unicode:
00835 _x = _x.encode('utf-8')
00836 length = len(_x)
00837 buff.write(struct.pack('<I%ss'%length, length, _x))
00838 _v39 = _v36.pose
00839 _v40 = _v39.position
00840 _x = _v40
00841 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00842 _v41 = _v39.orientation
00843 _x = _v41
00844 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00845 _v42 = val1.bounding_box_lwh
00846 _x = _v42
00847 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00848 _x = self
00849 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00850 _x = self.action_feedback.header.frame_id
00851 length = len(_x)
00852 if python3 or type(_x) == unicode:
00853 _x = _x.encode('utf-8')
00854 length = len(_x)
00855 buff.write(struct.pack('<I%ss'%length, length, _x))
00856 _x = self
00857 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00858 _x = self.action_feedback.status.goal_id.id
00859 length = len(_x)
00860 if python3 or type(_x) == unicode:
00861 _x = _x.encode('utf-8')
00862 length = len(_x)
00863 buff.write(struct.pack('<I%ss'%length, length, _x))
00864 buff.write(_struct_B.pack(self.action_feedback.status.status))
00865 _x = self.action_feedback.status.text
00866 length = len(_x)
00867 if python3 or type(_x) == unicode:
00868 _x = _x.encode('utf-8')
00869 length = len(_x)
00870 buff.write(struct.pack('<I%ss'%length, length, _x))
00871 buff.write(_struct_f.pack(self.action_feedback.feedback.percent_complete))
00872 except struct.error as se: self._check_types(se)
00873 except TypeError as te: self._check_types(te)
00874
00875 def deserialize_numpy(self, str, numpy):
00876 """
00877 unpack serialized message in str into this message instance using numpy for array types
00878 :param str: byte array of serialized message, ``str``
00879 :param numpy: numpy python module
00880 """
00881 try:
00882 if self.action_goal is None:
00883 self.action_goal = cob_object_detection_msgs.msg.DetectObjectsActionGoal()
00884 if self.action_result is None:
00885 self.action_result = cob_object_detection_msgs.msg.DetectObjectsActionResult()
00886 if self.action_feedback is None:
00887 self.action_feedback = cob_object_detection_msgs.msg.DetectObjectsActionFeedback()
00888 end = 0
00889 _x = self
00890 start = end
00891 end += 12
00892 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00893 start = end
00894 end += 4
00895 (length,) = _struct_I.unpack(str[start:end])
00896 start = end
00897 end += length
00898 if python3:
00899 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00900 else:
00901 self.action_goal.header.frame_id = str[start:end]
00902 _x = self
00903 start = end
00904 end += 8
00905 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00906 start = end
00907 end += 4
00908 (length,) = _struct_I.unpack(str[start:end])
00909 start = end
00910 end += length
00911 if python3:
00912 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00913 else:
00914 self.action_goal.goal_id.id = str[start:end]
00915 start = end
00916 end += 4
00917 (length,) = _struct_I.unpack(str[start:end])
00918 start = end
00919 end += length
00920 if python3:
00921 self.action_goal.goal.object_name.data = str[start:end].decode('utf-8')
00922 else:
00923 self.action_goal.goal.object_name.data = str[start:end]
00924 _x = self
00925 start = end
00926 end += 12
00927 (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00928 start = end
00929 end += 4
00930 (length,) = _struct_I.unpack(str[start:end])
00931 start = end
00932 end += length
00933 if python3:
00934 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00935 else:
00936 self.action_result.header.frame_id = str[start:end]
00937 _x = self
00938 start = end
00939 end += 8
00940 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00941 start = end
00942 end += 4
00943 (length,) = _struct_I.unpack(str[start:end])
00944 start = end
00945 end += length
00946 if python3:
00947 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00948 else:
00949 self.action_result.status.goal_id.id = str[start:end]
00950 start = end
00951 end += 1
00952 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00953 start = end
00954 end += 4
00955 (length,) = _struct_I.unpack(str[start:end])
00956 start = end
00957 end += length
00958 if python3:
00959 self.action_result.status.text = str[start:end].decode('utf-8')
00960 else:
00961 self.action_result.status.text = str[start:end]
00962 _x = self
00963 start = end
00964 end += 12
00965 (_x.action_result.result.object_list.header.seq, _x.action_result.result.object_list.header.stamp.secs, _x.action_result.result.object_list.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00966 start = end
00967 end += 4
00968 (length,) = _struct_I.unpack(str[start:end])
00969 start = end
00970 end += length
00971 if python3:
00972 self.action_result.result.object_list.header.frame_id = str[start:end].decode('utf-8')
00973 else:
00974 self.action_result.result.object_list.header.frame_id = str[start:end]
00975 start = end
00976 end += 4
00977 (length,) = _struct_I.unpack(str[start:end])
00978 self.action_result.result.object_list.detections = []
00979 for i in range(0, length):
00980 val1 = cob_object_detection_msgs.msg.Detection()
00981 _v43 = val1.header
00982 start = end
00983 end += 4
00984 (_v43.seq,) = _struct_I.unpack(str[start:end])
00985 _v44 = _v43.stamp
00986 _x = _v44
00987 start = end
00988 end += 8
00989 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00990 start = end
00991 end += 4
00992 (length,) = _struct_I.unpack(str[start:end])
00993 start = end
00994 end += length
00995 if python3:
00996 _v43.frame_id = str[start:end].decode('utf-8')
00997 else:
00998 _v43.frame_id = str[start:end]
00999 start = end
01000 end += 4
01001 (length,) = _struct_I.unpack(str[start:end])
01002 start = end
01003 end += length
01004 if python3:
01005 val1.label = str[start:end].decode('utf-8')
01006 else:
01007 val1.label = str[start:end]
01008 start = end
01009 end += 4
01010 (length,) = _struct_I.unpack(str[start:end])
01011 start = end
01012 end += length
01013 if python3:
01014 val1.detector = str[start:end].decode('utf-8')
01015 else:
01016 val1.detector = str[start:end]
01017 start = end
01018 end += 4
01019 (val1.score,) = _struct_f.unpack(str[start:end])
01020 _v45 = val1.mask
01021 _v46 = _v45.roi
01022 _x = _v46
01023 start = end
01024 end += 16
01025 (_x.x, _x.y, _x.width, _x.height,) = _struct_4i.unpack(str[start:end])
01026 _v47 = _v45.mask
01027 _v48 = _v47.header
01028 start = end
01029 end += 4
01030 (_v48.seq,) = _struct_I.unpack(str[start:end])
01031 _v49 = _v48.stamp
01032 _x = _v49
01033 start = end
01034 end += 8
01035 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01036 start = end
01037 end += 4
01038 (length,) = _struct_I.unpack(str[start:end])
01039 start = end
01040 end += length
01041 if python3:
01042 _v48.frame_id = str[start:end].decode('utf-8')
01043 else:
01044 _v48.frame_id = str[start:end]
01045 _x = _v47
01046 start = end
01047 end += 8
01048 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01049 start = end
01050 end += 4
01051 (length,) = _struct_I.unpack(str[start:end])
01052 start = end
01053 end += length
01054 if python3:
01055 _v47.encoding = str[start:end].decode('utf-8')
01056 else:
01057 _v47.encoding = str[start:end]
01058 _x = _v47
01059 start = end
01060 end += 5
01061 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
01062 start = end
01063 end += 4
01064 (length,) = _struct_I.unpack(str[start:end])
01065 start = end
01066 end += length
01067 if python3:
01068 _v47.data = str[start:end].decode('utf-8')
01069 else:
01070 _v47.data = str[start:end]
01071 _v50 = val1.pose
01072 _v51 = _v50.header
01073 start = end
01074 end += 4
01075 (_v51.seq,) = _struct_I.unpack(str[start:end])
01076 _v52 = _v51.stamp
01077 _x = _v52
01078 start = end
01079 end += 8
01080 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01081 start = end
01082 end += 4
01083 (length,) = _struct_I.unpack(str[start:end])
01084 start = end
01085 end += length
01086 if python3:
01087 _v51.frame_id = str[start:end].decode('utf-8')
01088 else:
01089 _v51.frame_id = str[start:end]
01090 _v53 = _v50.pose
01091 _v54 = _v53.position
01092 _x = _v54
01093 start = end
01094 end += 24
01095 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01096 _v55 = _v53.orientation
01097 _x = _v55
01098 start = end
01099 end += 32
01100 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01101 _v56 = val1.bounding_box_lwh
01102 _x = _v56
01103 start = end
01104 end += 24
01105 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01106 self.action_result.result.object_list.detections.append(val1)
01107 _x = self
01108 start = end
01109 end += 12
01110 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01111 start = end
01112 end += 4
01113 (length,) = _struct_I.unpack(str[start:end])
01114 start = end
01115 end += length
01116 if python3:
01117 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01118 else:
01119 self.action_feedback.header.frame_id = str[start:end]
01120 _x = self
01121 start = end
01122 end += 8
01123 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01124 start = end
01125 end += 4
01126 (length,) = _struct_I.unpack(str[start:end])
01127 start = end
01128 end += length
01129 if python3:
01130 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01131 else:
01132 self.action_feedback.status.goal_id.id = str[start:end]
01133 start = end
01134 end += 1
01135 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01136 start = end
01137 end += 4
01138 (length,) = _struct_I.unpack(str[start:end])
01139 start = end
01140 end += length
01141 if python3:
01142 self.action_feedback.status.text = str[start:end].decode('utf-8')
01143 else:
01144 self.action_feedback.status.text = str[start:end]
01145 start = end
01146 end += 4
01147 (self.action_feedback.feedback.percent_complete,) = _struct_f.unpack(str[start:end])
01148 return self
01149 except struct.error as e:
01150 raise genpy.DeserializationError(e)
01151
01152 _struct_I = genpy.struct_I
01153 _struct_B = struct.Struct("<B")
01154 _struct_f = struct.Struct("<f")
01155 _struct_BI = struct.Struct("<BI")
01156 _struct_3I = struct.Struct("<3I")
01157 _struct_4i = struct.Struct("<4i")
01158 _struct_4d = struct.Struct("<4d")
01159 _struct_2I = struct.Struct("<2I")
01160 _struct_3d = struct.Struct("<3d")