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