00001 """autogenerated by genmsg_py from LookupTransformAction.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import roslib.rostime
00007 import actionlib_msgs.msg
00008 import tf2_msgs.msg
00009 import std_msgs.msg
00010
00011 class LookupTransformAction(roslib.message.Message):
00012 _md5sum = "7ee01ba91a56c2245c610992dbaa3c37"
00013 _type = "tf2_msgs/LookupTransformAction"
00014 _has_header = False
00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00016
00017 LookupTransformActionGoal action_goal
00018 LookupTransformActionResult action_result
00019 LookupTransformActionFeedback action_feedback
00020
00021 ================================================================================
00022 MSG: tf2_msgs/LookupTransformActionGoal
00023 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00024
00025 Header header
00026 actionlib_msgs/GoalID goal_id
00027 LookupTransformGoal goal
00028
00029 ================================================================================
00030 MSG: std_msgs/Header
00031 # Standard metadata for higher-level stamped data types.
00032 # This is generally used to communicate timestamped data
00033 # in a particular coordinate frame.
00034 #
00035 # sequence ID: consecutively increasing ID
00036 uint32 seq
00037 #Two-integer timestamp that is expressed as:
00038 # * stamp.secs: seconds (stamp_secs) since epoch
00039 # * stamp.nsecs: nanoseconds since stamp_secs
00040 # time-handling sugar is provided by the client library
00041 time stamp
00042 #Frame this data is associated with
00043 # 0: no frame
00044 # 1: global frame
00045 string frame_id
00046
00047 ================================================================================
00048 MSG: actionlib_msgs/GoalID
00049 # The stamp should store the time at which this goal was requested.
00050 # It is used by an action server when it tries to preempt all
00051 # goals that were requested before a certain time
00052 time stamp
00053
00054 # The id provides a way to associate feedback and
00055 # result message with specific goal requests. The id
00056 # specified must be unique.
00057 string id
00058
00059
00060 ================================================================================
00061 MSG: tf2_msgs/LookupTransformGoal
00062 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00063 #Simple API
00064 string target_frame
00065 string source_frame
00066 time source_time
00067 duration timeout
00068
00069 #Advanced API
00070 time target_time
00071 string fixed_frame
00072
00073 #Whether or not to use the advanced API
00074 bool advanced
00075
00076
00077 ================================================================================
00078 MSG: tf2_msgs/LookupTransformActionResult
00079 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00080
00081 Header header
00082 actionlib_msgs/GoalStatus status
00083 LookupTransformResult result
00084
00085 ================================================================================
00086 MSG: actionlib_msgs/GoalStatus
00087 GoalID goal_id
00088 uint8 status
00089 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00090 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00091 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00092 # and has since completed its execution (Terminal State)
00093 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00094 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00095 # to some failure (Terminal State)
00096 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00097 # because the goal was unattainable or invalid (Terminal State)
00098 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00099 # and has not yet completed execution
00100 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00101 # but the action server has not yet confirmed that the goal is canceled
00102 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00103 # and was successfully cancelled (Terminal State)
00104 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00105 # sent over the wire by an action server
00106
00107 #Allow for the user to associate a string with GoalStatus for debugging
00108 string text
00109
00110
00111 ================================================================================
00112 MSG: tf2_msgs/LookupTransformResult
00113 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00114 geometry_msgs/TransformStamped transform
00115 tf2_msgs/TF2Error error
00116
00117 ================================================================================
00118 MSG: geometry_msgs/TransformStamped
00119 # This expresses a transform from coordinate frame header.frame_id
00120 # to the coordinate frame child_frame_id
00121 #
00122 # This message is mostly used by the
00123 # <a href="http://www.ros.org/wiki/tf">tf</a> package.
00124 # See it's documentation for more information.
00125
00126 Header header
00127 string child_frame_id # the frame id of the child frame
00128 Transform transform
00129
00130 ================================================================================
00131 MSG: geometry_msgs/Transform
00132 # This represents the transform between two coordinate frames in free space.
00133
00134 Vector3 translation
00135 Quaternion rotation
00136
00137 ================================================================================
00138 MSG: geometry_msgs/Vector3
00139 # This represents a vector in free space.
00140
00141 float64 x
00142 float64 y
00143 float64 z
00144 ================================================================================
00145 MSG: geometry_msgs/Quaternion
00146 # This represents an orientation in free space in quaternion form.
00147
00148 float64 x
00149 float64 y
00150 float64 z
00151 float64 w
00152
00153 ================================================================================
00154 MSG: tf2_msgs/TF2Error
00155 uint8 NO_ERROR = 0
00156 uint8 LOOKUP_ERROR = 1
00157 uint8 CONNECTIVITY_ERROR = 2
00158 uint8 EXTRAPOLATION_ERROR = 3
00159 uint8 INVALID_ARGUMENT_ERROR = 4
00160 uint8 TIMEOUT_ERROR = 5
00161 uint8 TRANSFORM_ERROR = 6
00162
00163 uint8 error
00164 string error_string
00165
00166 ================================================================================
00167 MSG: tf2_msgs/LookupTransformActionFeedback
00168 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00169
00170 Header header
00171 actionlib_msgs/GoalStatus status
00172 LookupTransformFeedback feedback
00173
00174 ================================================================================
00175 MSG: tf2_msgs/LookupTransformFeedback
00176 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00177
00178
00179 """
00180 __slots__ = ['action_goal','action_result','action_feedback']
00181 _slot_types = ['tf2_msgs/LookupTransformActionGoal','tf2_msgs/LookupTransformActionResult','tf2_msgs/LookupTransformActionFeedback']
00182
00183 def __init__(self, *args, **kwds):
00184 """
00185 Constructor. Any message fields that are implicitly/explicitly
00186 set to None will be assigned a default value. The recommend
00187 use is keyword arguments as this is more robust to future message
00188 changes. You cannot mix in-order arguments and keyword arguments.
00189
00190 The available fields are:
00191 action_goal,action_result,action_feedback
00192
00193 @param args: complete set of field values, in .msg order
00194 @param kwds: use keyword arguments corresponding to message field names
00195 to set specific fields.
00196 """
00197 if args or kwds:
00198 super(LookupTransformAction, self).__init__(*args, **kwds)
00199
00200 if self.action_goal is None:
00201 self.action_goal = tf2_msgs.msg.LookupTransformActionGoal()
00202 if self.action_result is None:
00203 self.action_result = tf2_msgs.msg.LookupTransformActionResult()
00204 if self.action_feedback is None:
00205 self.action_feedback = tf2_msgs.msg.LookupTransformActionFeedback()
00206 else:
00207 self.action_goal = tf2_msgs.msg.LookupTransformActionGoal()
00208 self.action_result = tf2_msgs.msg.LookupTransformActionResult()
00209 self.action_feedback = tf2_msgs.msg.LookupTransformActionFeedback()
00210
00211 def _get_types(self):
00212 """
00213 internal API method
00214 """
00215 return self._slot_types
00216
00217 def serialize(self, buff):
00218 """
00219 serialize message into buffer
00220 @param buff: buffer
00221 @type buff: StringIO
00222 """
00223 try:
00224 _x = self
00225 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00226 _x = self.action_goal.header.frame_id
00227 length = len(_x)
00228 buff.write(struct.pack('<I%ss'%length, length, _x))
00229 _x = self
00230 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00231 _x = self.action_goal.goal_id.id
00232 length = len(_x)
00233 buff.write(struct.pack('<I%ss'%length, length, _x))
00234 _x = self.action_goal.goal.target_frame
00235 length = len(_x)
00236 buff.write(struct.pack('<I%ss'%length, length, _x))
00237 _x = self.action_goal.goal.source_frame
00238 length = len(_x)
00239 buff.write(struct.pack('<I%ss'%length, length, _x))
00240 _x = self
00241 buff.write(_struct_2I2i2I.pack(_x.action_goal.goal.source_time.secs, _x.action_goal.goal.source_time.nsecs, _x.action_goal.goal.timeout.secs, _x.action_goal.goal.timeout.nsecs, _x.action_goal.goal.target_time.secs, _x.action_goal.goal.target_time.nsecs))
00242 _x = self.action_goal.goal.fixed_frame
00243 length = len(_x)
00244 buff.write(struct.pack('<I%ss'%length, length, _x))
00245 _x = self
00246 buff.write(_struct_B3I.pack(_x.action_goal.goal.advanced, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00247 _x = self.action_result.header.frame_id
00248 length = len(_x)
00249 buff.write(struct.pack('<I%ss'%length, length, _x))
00250 _x = self
00251 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00252 _x = self.action_result.status.goal_id.id
00253 length = len(_x)
00254 buff.write(struct.pack('<I%ss'%length, length, _x))
00255 buff.write(_struct_B.pack(self.action_result.status.status))
00256 _x = self.action_result.status.text
00257 length = len(_x)
00258 buff.write(struct.pack('<I%ss'%length, length, _x))
00259 _x = self
00260 buff.write(_struct_3I.pack(_x.action_result.result.transform.header.seq, _x.action_result.result.transform.header.stamp.secs, _x.action_result.result.transform.header.stamp.nsecs))
00261 _x = self.action_result.result.transform.header.frame_id
00262 length = len(_x)
00263 buff.write(struct.pack('<I%ss'%length, length, _x))
00264 _x = self.action_result.result.transform.child_frame_id
00265 length = len(_x)
00266 buff.write(struct.pack('<I%ss'%length, length, _x))
00267 _x = self
00268 buff.write(_struct_7dB.pack(_x.action_result.result.transform.transform.translation.x, _x.action_result.result.transform.transform.translation.y, _x.action_result.result.transform.transform.translation.z, _x.action_result.result.transform.transform.rotation.x, _x.action_result.result.transform.transform.rotation.y, _x.action_result.result.transform.transform.rotation.z, _x.action_result.result.transform.transform.rotation.w, _x.action_result.result.error.error))
00269 _x = self.action_result.result.error.error_string
00270 length = len(_x)
00271 buff.write(struct.pack('<I%ss'%length, length, _x))
00272 _x = self
00273 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00274 _x = self.action_feedback.header.frame_id
00275 length = len(_x)
00276 buff.write(struct.pack('<I%ss'%length, length, _x))
00277 _x = self
00278 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00279 _x = self.action_feedback.status.goal_id.id
00280 length = len(_x)
00281 buff.write(struct.pack('<I%ss'%length, length, _x))
00282 buff.write(_struct_B.pack(self.action_feedback.status.status))
00283 _x = self.action_feedback.status.text
00284 length = len(_x)
00285 buff.write(struct.pack('<I%ss'%length, length, _x))
00286 except struct.error, se: self._check_types(se)
00287 except TypeError, te: self._check_types(te)
00288
00289 def deserialize(self, str):
00290 """
00291 unpack serialized message in str into this message instance
00292 @param str: byte array of serialized message
00293 @type str: str
00294 """
00295 try:
00296 if self.action_goal is None:
00297 self.action_goal = tf2_msgs.msg.LookupTransformActionGoal()
00298 if self.action_result is None:
00299 self.action_result = tf2_msgs.msg.LookupTransformActionResult()
00300 if self.action_feedback is None:
00301 self.action_feedback = tf2_msgs.msg.LookupTransformActionFeedback()
00302 end = 0
00303 _x = self
00304 start = end
00305 end += 12
00306 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00307 start = end
00308 end += 4
00309 (length,) = _struct_I.unpack(str[start:end])
00310 start = end
00311 end += length
00312 self.action_goal.header.frame_id = str[start:end]
00313 _x = self
00314 start = end
00315 end += 8
00316 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.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 self.action_goal.goal_id.id = str[start:end]
00323 start = end
00324 end += 4
00325 (length,) = _struct_I.unpack(str[start:end])
00326 start = end
00327 end += length
00328 self.action_goal.goal.target_frame = str[start:end]
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 start = end
00333 end += length
00334 self.action_goal.goal.source_frame = str[start:end]
00335 _x = self
00336 start = end
00337 end += 24
00338 (_x.action_goal.goal.source_time.secs, _x.action_goal.goal.source_time.nsecs, _x.action_goal.goal.timeout.secs, _x.action_goal.goal.timeout.nsecs, _x.action_goal.goal.target_time.secs, _x.action_goal.goal.target_time.nsecs,) = _struct_2I2i2I.unpack(str[start:end])
00339 start = end
00340 end += 4
00341 (length,) = _struct_I.unpack(str[start:end])
00342 start = end
00343 end += length
00344 self.action_goal.goal.fixed_frame = str[start:end]
00345 _x = self
00346 start = end
00347 end += 13
00348 (_x.action_goal.goal.advanced, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00349 self.action_goal.goal.advanced = bool(self.action_goal.goal.advanced)
00350 start = end
00351 end += 4
00352 (length,) = _struct_I.unpack(str[start:end])
00353 start = end
00354 end += length
00355 self.action_result.header.frame_id = str[start:end]
00356 _x = self
00357 start = end
00358 end += 8
00359 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00360 start = end
00361 end += 4
00362 (length,) = _struct_I.unpack(str[start:end])
00363 start = end
00364 end += length
00365 self.action_result.status.goal_id.id = str[start:end]
00366 start = end
00367 end += 1
00368 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00369 start = end
00370 end += 4
00371 (length,) = _struct_I.unpack(str[start:end])
00372 start = end
00373 end += length
00374 self.action_result.status.text = str[start:end]
00375 _x = self
00376 start = end
00377 end += 12
00378 (_x.action_result.result.transform.header.seq, _x.action_result.result.transform.header.stamp.secs, _x.action_result.result.transform.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00379 start = end
00380 end += 4
00381 (length,) = _struct_I.unpack(str[start:end])
00382 start = end
00383 end += length
00384 self.action_result.result.transform.header.frame_id = str[start:end]
00385 start = end
00386 end += 4
00387 (length,) = _struct_I.unpack(str[start:end])
00388 start = end
00389 end += length
00390 self.action_result.result.transform.child_frame_id = str[start:end]
00391 _x = self
00392 start = end
00393 end += 57
00394 (_x.action_result.result.transform.transform.translation.x, _x.action_result.result.transform.transform.translation.y, _x.action_result.result.transform.transform.translation.z, _x.action_result.result.transform.transform.rotation.x, _x.action_result.result.transform.transform.rotation.y, _x.action_result.result.transform.transform.rotation.z, _x.action_result.result.transform.transform.rotation.w, _x.action_result.result.error.error,) = _struct_7dB.unpack(str[start:end])
00395 start = end
00396 end += 4
00397 (length,) = _struct_I.unpack(str[start:end])
00398 start = end
00399 end += length
00400 self.action_result.result.error.error_string = str[start:end]
00401 _x = self
00402 start = end
00403 end += 12
00404 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00405 start = end
00406 end += 4
00407 (length,) = _struct_I.unpack(str[start:end])
00408 start = end
00409 end += length
00410 self.action_feedback.header.frame_id = str[start:end]
00411 _x = self
00412 start = end
00413 end += 8
00414 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00415 start = end
00416 end += 4
00417 (length,) = _struct_I.unpack(str[start:end])
00418 start = end
00419 end += length
00420 self.action_feedback.status.goal_id.id = str[start:end]
00421 start = end
00422 end += 1
00423 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00424 start = end
00425 end += 4
00426 (length,) = _struct_I.unpack(str[start:end])
00427 start = end
00428 end += length
00429 self.action_feedback.status.text = str[start:end]
00430 return self
00431 except struct.error, e:
00432 raise roslib.message.DeserializationError(e)
00433
00434
00435 def serialize_numpy(self, buff, numpy):
00436 """
00437 serialize message with numpy array types into buffer
00438 @param buff: buffer
00439 @type buff: StringIO
00440 @param numpy: numpy python module
00441 @type numpy module
00442 """
00443 try:
00444 _x = self
00445 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00446 _x = self.action_goal.header.frame_id
00447 length = len(_x)
00448 buff.write(struct.pack('<I%ss'%length, length, _x))
00449 _x = self
00450 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00451 _x = self.action_goal.goal_id.id
00452 length = len(_x)
00453 buff.write(struct.pack('<I%ss'%length, length, _x))
00454 _x = self.action_goal.goal.target_frame
00455 length = len(_x)
00456 buff.write(struct.pack('<I%ss'%length, length, _x))
00457 _x = self.action_goal.goal.source_frame
00458 length = len(_x)
00459 buff.write(struct.pack('<I%ss'%length, length, _x))
00460 _x = self
00461 buff.write(_struct_2I2i2I.pack(_x.action_goal.goal.source_time.secs, _x.action_goal.goal.source_time.nsecs, _x.action_goal.goal.timeout.secs, _x.action_goal.goal.timeout.nsecs, _x.action_goal.goal.target_time.secs, _x.action_goal.goal.target_time.nsecs))
00462 _x = self.action_goal.goal.fixed_frame
00463 length = len(_x)
00464 buff.write(struct.pack('<I%ss'%length, length, _x))
00465 _x = self
00466 buff.write(_struct_B3I.pack(_x.action_goal.goal.advanced, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00467 _x = self.action_result.header.frame_id
00468 length = len(_x)
00469 buff.write(struct.pack('<I%ss'%length, length, _x))
00470 _x = self
00471 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00472 _x = self.action_result.status.goal_id.id
00473 length = len(_x)
00474 buff.write(struct.pack('<I%ss'%length, length, _x))
00475 buff.write(_struct_B.pack(self.action_result.status.status))
00476 _x = self.action_result.status.text
00477 length = len(_x)
00478 buff.write(struct.pack('<I%ss'%length, length, _x))
00479 _x = self
00480 buff.write(_struct_3I.pack(_x.action_result.result.transform.header.seq, _x.action_result.result.transform.header.stamp.secs, _x.action_result.result.transform.header.stamp.nsecs))
00481 _x = self.action_result.result.transform.header.frame_id
00482 length = len(_x)
00483 buff.write(struct.pack('<I%ss'%length, length, _x))
00484 _x = self.action_result.result.transform.child_frame_id
00485 length = len(_x)
00486 buff.write(struct.pack('<I%ss'%length, length, _x))
00487 _x = self
00488 buff.write(_struct_7dB.pack(_x.action_result.result.transform.transform.translation.x, _x.action_result.result.transform.transform.translation.y, _x.action_result.result.transform.transform.translation.z, _x.action_result.result.transform.transform.rotation.x, _x.action_result.result.transform.transform.rotation.y, _x.action_result.result.transform.transform.rotation.z, _x.action_result.result.transform.transform.rotation.w, _x.action_result.result.error.error))
00489 _x = self.action_result.result.error.error_string
00490 length = len(_x)
00491 buff.write(struct.pack('<I%ss'%length, length, _x))
00492 _x = self
00493 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00494 _x = self.action_feedback.header.frame_id
00495 length = len(_x)
00496 buff.write(struct.pack('<I%ss'%length, length, _x))
00497 _x = self
00498 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00499 _x = self.action_feedback.status.goal_id.id
00500 length = len(_x)
00501 buff.write(struct.pack('<I%ss'%length, length, _x))
00502 buff.write(_struct_B.pack(self.action_feedback.status.status))
00503 _x = self.action_feedback.status.text
00504 length = len(_x)
00505 buff.write(struct.pack('<I%ss'%length, length, _x))
00506 except struct.error, se: self._check_types(se)
00507 except TypeError, te: self._check_types(te)
00508
00509 def deserialize_numpy(self, str, numpy):
00510 """
00511 unpack serialized message in str into this message instance using numpy for array types
00512 @param str: byte array of serialized message
00513 @type str: str
00514 @param numpy: numpy python module
00515 @type numpy: module
00516 """
00517 try:
00518 if self.action_goal is None:
00519 self.action_goal = tf2_msgs.msg.LookupTransformActionGoal()
00520 if self.action_result is None:
00521 self.action_result = tf2_msgs.msg.LookupTransformActionResult()
00522 if self.action_feedback is None:
00523 self.action_feedback = tf2_msgs.msg.LookupTransformActionFeedback()
00524 end = 0
00525 _x = self
00526 start = end
00527 end += 12
00528 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00529 start = end
00530 end += 4
00531 (length,) = _struct_I.unpack(str[start:end])
00532 start = end
00533 end += length
00534 self.action_goal.header.frame_id = str[start:end]
00535 _x = self
00536 start = end
00537 end += 8
00538 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00539 start = end
00540 end += 4
00541 (length,) = _struct_I.unpack(str[start:end])
00542 start = end
00543 end += length
00544 self.action_goal.goal_id.id = str[start:end]
00545 start = end
00546 end += 4
00547 (length,) = _struct_I.unpack(str[start:end])
00548 start = end
00549 end += length
00550 self.action_goal.goal.target_frame = str[start:end]
00551 start = end
00552 end += 4
00553 (length,) = _struct_I.unpack(str[start:end])
00554 start = end
00555 end += length
00556 self.action_goal.goal.source_frame = str[start:end]
00557 _x = self
00558 start = end
00559 end += 24
00560 (_x.action_goal.goal.source_time.secs, _x.action_goal.goal.source_time.nsecs, _x.action_goal.goal.timeout.secs, _x.action_goal.goal.timeout.nsecs, _x.action_goal.goal.target_time.secs, _x.action_goal.goal.target_time.nsecs,) = _struct_2I2i2I.unpack(str[start:end])
00561 start = end
00562 end += 4
00563 (length,) = _struct_I.unpack(str[start:end])
00564 start = end
00565 end += length
00566 self.action_goal.goal.fixed_frame = str[start:end]
00567 _x = self
00568 start = end
00569 end += 13
00570 (_x.action_goal.goal.advanced, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00571 self.action_goal.goal.advanced = bool(self.action_goal.goal.advanced)
00572 start = end
00573 end += 4
00574 (length,) = _struct_I.unpack(str[start:end])
00575 start = end
00576 end += length
00577 self.action_result.header.frame_id = str[start:end]
00578 _x = self
00579 start = end
00580 end += 8
00581 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00582 start = end
00583 end += 4
00584 (length,) = _struct_I.unpack(str[start:end])
00585 start = end
00586 end += length
00587 self.action_result.status.goal_id.id = str[start:end]
00588 start = end
00589 end += 1
00590 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00591 start = end
00592 end += 4
00593 (length,) = _struct_I.unpack(str[start:end])
00594 start = end
00595 end += length
00596 self.action_result.status.text = str[start:end]
00597 _x = self
00598 start = end
00599 end += 12
00600 (_x.action_result.result.transform.header.seq, _x.action_result.result.transform.header.stamp.secs, _x.action_result.result.transform.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00601 start = end
00602 end += 4
00603 (length,) = _struct_I.unpack(str[start:end])
00604 start = end
00605 end += length
00606 self.action_result.result.transform.header.frame_id = str[start:end]
00607 start = end
00608 end += 4
00609 (length,) = _struct_I.unpack(str[start:end])
00610 start = end
00611 end += length
00612 self.action_result.result.transform.child_frame_id = str[start:end]
00613 _x = self
00614 start = end
00615 end += 57
00616 (_x.action_result.result.transform.transform.translation.x, _x.action_result.result.transform.transform.translation.y, _x.action_result.result.transform.transform.translation.z, _x.action_result.result.transform.transform.rotation.x, _x.action_result.result.transform.transform.rotation.y, _x.action_result.result.transform.transform.rotation.z, _x.action_result.result.transform.transform.rotation.w, _x.action_result.result.error.error,) = _struct_7dB.unpack(str[start:end])
00617 start = end
00618 end += 4
00619 (length,) = _struct_I.unpack(str[start:end])
00620 start = end
00621 end += length
00622 self.action_result.result.error.error_string = str[start:end]
00623 _x = self
00624 start = end
00625 end += 12
00626 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.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 self.action_feedback.header.frame_id = str[start:end]
00633 _x = self
00634 start = end
00635 end += 8
00636 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00637 start = end
00638 end += 4
00639 (length,) = _struct_I.unpack(str[start:end])
00640 start = end
00641 end += length
00642 self.action_feedback.status.goal_id.id = str[start:end]
00643 start = end
00644 end += 1
00645 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00646 start = end
00647 end += 4
00648 (length,) = _struct_I.unpack(str[start:end])
00649 start = end
00650 end += length
00651 self.action_feedback.status.text = str[start:end]
00652 return self
00653 except struct.error, e:
00654 raise roslib.message.DeserializationError(e)
00655
00656 _struct_I = roslib.message.struct_I
00657 _struct_7dB = struct.Struct("<7dB")
00658 _struct_B = struct.Struct("<B")
00659 _struct_3I = struct.Struct("<3I")
00660 _struct_B3I = struct.Struct("<B3I")
00661 _struct_2I = struct.Struct("<2I")
00662 _struct_2I2i2I = struct.Struct("<2I2i2I")