00001 """autogenerated by genpy from humanoid_nav_msgs/ExecFootstepsAction.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 geometry_msgs.msg
00008 import genpy
00009 import actionlib_msgs.msg
00010 import humanoid_nav_msgs.msg
00011 import std_msgs.msg
00012
00013 class ExecFootstepsAction(genpy.Message):
00014 _md5sum = "1a2c4888b786ce4d1be346c228ea5a28"
00015 _type = "humanoid_nav_msgs/ExecFootstepsAction"
00016 _has_header = False
00017 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018
00019 ExecFootstepsActionGoal action_goal
00020 ExecFootstepsActionResult action_result
00021 ExecFootstepsActionFeedback action_feedback
00022
00023 ================================================================================
00024 MSG: humanoid_nav_msgs/ExecFootstepsActionGoal
00025 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00026
00027 Header header
00028 actionlib_msgs/GoalID goal_id
00029 ExecFootstepsGoal 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: humanoid_nav_msgs/ExecFootstepsGoal
00064 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00065 # Define the goal
00066 humanoid_nav_msgs/StepTarget[] footsteps
00067 float64 feedback_frequency
00068
00069 ================================================================================
00070 MSG: humanoid_nav_msgs/StepTarget
00071 # Target for a single stepping motion of a humanoid's leg
00072
00073 geometry_msgs/Pose2D pose # step pose as relative offset to last leg
00074 uint8 leg # which leg to use (left/right, see below)
00075
00076 uint8 right=0 # right leg constant
00077 uint8 left=1 # left leg constant
00078
00079 ================================================================================
00080 MSG: geometry_msgs/Pose2D
00081 # This expresses a position and orientation on a 2D manifold.
00082
00083 float64 x
00084 float64 y
00085 float64 theta
00086 ================================================================================
00087 MSG: humanoid_nav_msgs/ExecFootstepsActionResult
00088 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00089
00090 Header header
00091 actionlib_msgs/GoalStatus status
00092 ExecFootstepsResult result
00093
00094 ================================================================================
00095 MSG: actionlib_msgs/GoalStatus
00096 GoalID goal_id
00097 uint8 status
00098 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00099 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00100 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00101 # and has since completed its execution (Terminal State)
00102 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00103 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00104 # to some failure (Terminal State)
00105 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00106 # because the goal was unattainable or invalid (Terminal State)
00107 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00108 # and has not yet completed execution
00109 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00110 # but the action server has not yet confirmed that the goal is canceled
00111 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00112 # and was successfully cancelled (Terminal State)
00113 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00114 # sent over the wire by an action server
00115
00116 #Allow for the user to associate a string with GoalStatus for debugging
00117 string text
00118
00119
00120 ================================================================================
00121 MSG: humanoid_nav_msgs/ExecFootstepsResult
00122 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00123 # Define the result
00124 humanoid_nav_msgs/StepTarget[] executed_footsteps
00125
00126 ================================================================================
00127 MSG: humanoid_nav_msgs/ExecFootstepsActionFeedback
00128 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00129
00130 Header header
00131 actionlib_msgs/GoalStatus status
00132 ExecFootstepsFeedback feedback
00133
00134 ================================================================================
00135 MSG: humanoid_nav_msgs/ExecFootstepsFeedback
00136 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00137 # Define a feedback message
00138 humanoid_nav_msgs/StepTarget[] executed_footsteps
00139
00140
00141 """
00142 __slots__ = ['action_goal','action_result','action_feedback']
00143 _slot_types = ['humanoid_nav_msgs/ExecFootstepsActionGoal','humanoid_nav_msgs/ExecFootstepsActionResult','humanoid_nav_msgs/ExecFootstepsActionFeedback']
00144
00145 def __init__(self, *args, **kwds):
00146 """
00147 Constructor. Any message fields that are implicitly/explicitly
00148 set to None will be assigned a default value. The recommend
00149 use is keyword arguments as this is more robust to future message
00150 changes. You cannot mix in-order arguments and keyword arguments.
00151
00152 The available fields are:
00153 action_goal,action_result,action_feedback
00154
00155 :param args: complete set of field values, in .msg order
00156 :param kwds: use keyword arguments corresponding to message field names
00157 to set specific fields.
00158 """
00159 if args or kwds:
00160 super(ExecFootstepsAction, self).__init__(*args, **kwds)
00161
00162 if self.action_goal is None:
00163 self.action_goal = humanoid_nav_msgs.msg.ExecFootstepsActionGoal()
00164 if self.action_result is None:
00165 self.action_result = humanoid_nav_msgs.msg.ExecFootstepsActionResult()
00166 if self.action_feedback is None:
00167 self.action_feedback = humanoid_nav_msgs.msg.ExecFootstepsActionFeedback()
00168 else:
00169 self.action_goal = humanoid_nav_msgs.msg.ExecFootstepsActionGoal()
00170 self.action_result = humanoid_nav_msgs.msg.ExecFootstepsActionResult()
00171 self.action_feedback = humanoid_nav_msgs.msg.ExecFootstepsActionFeedback()
00172
00173 def _get_types(self):
00174 """
00175 internal API method
00176 """
00177 return self._slot_types
00178
00179 def serialize(self, buff):
00180 """
00181 serialize message into buffer
00182 :param buff: buffer, ``StringIO``
00183 """
00184 try:
00185 _x = self
00186 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00187 _x = self.action_goal.header.frame_id
00188 length = len(_x)
00189 if python3 or type(_x) == unicode:
00190 _x = _x.encode('utf-8')
00191 length = len(_x)
00192 buff.write(struct.pack('<I%ss'%length, length, _x))
00193 _x = self
00194 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00195 _x = self.action_goal.goal_id.id
00196 length = len(_x)
00197 if python3 or type(_x) == unicode:
00198 _x = _x.encode('utf-8')
00199 length = len(_x)
00200 buff.write(struct.pack('<I%ss'%length, length, _x))
00201 length = len(self.action_goal.goal.footsteps)
00202 buff.write(_struct_I.pack(length))
00203 for val1 in self.action_goal.goal.footsteps:
00204 _v1 = val1.pose
00205 _x = _v1
00206 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00207 buff.write(_struct_B.pack(val1.leg))
00208 _x = self
00209 buff.write(_struct_d3I.pack(_x.action_goal.goal.feedback_frequency, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00210 _x = self.action_result.header.frame_id
00211 length = len(_x)
00212 if python3 or type(_x) == unicode:
00213 _x = _x.encode('utf-8')
00214 length = len(_x)
00215 buff.write(struct.pack('<I%ss'%length, length, _x))
00216 _x = self
00217 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00218 _x = self.action_result.status.goal_id.id
00219 length = len(_x)
00220 if python3 or type(_x) == unicode:
00221 _x = _x.encode('utf-8')
00222 length = len(_x)
00223 buff.write(struct.pack('<I%ss'%length, length, _x))
00224 buff.write(_struct_B.pack(self.action_result.status.status))
00225 _x = self.action_result.status.text
00226 length = len(_x)
00227 if python3 or type(_x) == unicode:
00228 _x = _x.encode('utf-8')
00229 length = len(_x)
00230 buff.write(struct.pack('<I%ss'%length, length, _x))
00231 length = len(self.action_result.result.executed_footsteps)
00232 buff.write(_struct_I.pack(length))
00233 for val1 in self.action_result.result.executed_footsteps:
00234 _v2 = val1.pose
00235 _x = _v2
00236 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00237 buff.write(_struct_B.pack(val1.leg))
00238 _x = self
00239 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00240 _x = self.action_feedback.header.frame_id
00241 length = len(_x)
00242 if python3 or type(_x) == unicode:
00243 _x = _x.encode('utf-8')
00244 length = len(_x)
00245 buff.write(struct.pack('<I%ss'%length, length, _x))
00246 _x = self
00247 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00248 _x = self.action_feedback.status.goal_id.id
00249 length = len(_x)
00250 if python3 or type(_x) == unicode:
00251 _x = _x.encode('utf-8')
00252 length = len(_x)
00253 buff.write(struct.pack('<I%ss'%length, length, _x))
00254 buff.write(_struct_B.pack(self.action_feedback.status.status))
00255 _x = self.action_feedback.status.text
00256 length = len(_x)
00257 if python3 or type(_x) == unicode:
00258 _x = _x.encode('utf-8')
00259 length = len(_x)
00260 buff.write(struct.pack('<I%ss'%length, length, _x))
00261 length = len(self.action_feedback.feedback.executed_footsteps)
00262 buff.write(_struct_I.pack(length))
00263 for val1 in self.action_feedback.feedback.executed_footsteps:
00264 _v3 = val1.pose
00265 _x = _v3
00266 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00267 buff.write(_struct_B.pack(val1.leg))
00268 except struct.error as se: self._check_types(se)
00269 except TypeError as te: self._check_types(te)
00270
00271 def deserialize(self, str):
00272 """
00273 unpack serialized message in str into this message instance
00274 :param str: byte array of serialized message, ``str``
00275 """
00276 try:
00277 if self.action_goal is None:
00278 self.action_goal = humanoid_nav_msgs.msg.ExecFootstepsActionGoal()
00279 if self.action_result is None:
00280 self.action_result = humanoid_nav_msgs.msg.ExecFootstepsActionResult()
00281 if self.action_feedback is None:
00282 self.action_feedback = humanoid_nav_msgs.msg.ExecFootstepsActionFeedback()
00283 end = 0
00284 _x = self
00285 start = end
00286 end += 12
00287 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00288 start = end
00289 end += 4
00290 (length,) = _struct_I.unpack(str[start:end])
00291 start = end
00292 end += length
00293 if python3:
00294 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00295 else:
00296 self.action_goal.header.frame_id = str[start:end]
00297 _x = self
00298 start = end
00299 end += 8
00300 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00301 start = end
00302 end += 4
00303 (length,) = _struct_I.unpack(str[start:end])
00304 start = end
00305 end += length
00306 if python3:
00307 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00308 else:
00309 self.action_goal.goal_id.id = str[start:end]
00310 start = end
00311 end += 4
00312 (length,) = _struct_I.unpack(str[start:end])
00313 self.action_goal.goal.footsteps = []
00314 for i in range(0, length):
00315 val1 = humanoid_nav_msgs.msg.StepTarget()
00316 _v4 = val1.pose
00317 _x = _v4
00318 start = end
00319 end += 24
00320 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00321 start = end
00322 end += 1
00323 (val1.leg,) = _struct_B.unpack(str[start:end])
00324 self.action_goal.goal.footsteps.append(val1)
00325 _x = self
00326 start = end
00327 end += 20
00328 (_x.action_goal.goal.feedback_frequency, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_d3I.unpack(str[start:end])
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 start = end
00333 end += length
00334 if python3:
00335 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00336 else:
00337 self.action_result.header.frame_id = str[start:end]
00338 _x = self
00339 start = end
00340 end += 8
00341 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00342 start = end
00343 end += 4
00344 (length,) = _struct_I.unpack(str[start:end])
00345 start = end
00346 end += length
00347 if python3:
00348 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00349 else:
00350 self.action_result.status.goal_id.id = str[start:end]
00351 start = end
00352 end += 1
00353 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00354 start = end
00355 end += 4
00356 (length,) = _struct_I.unpack(str[start:end])
00357 start = end
00358 end += length
00359 if python3:
00360 self.action_result.status.text = str[start:end].decode('utf-8')
00361 else:
00362 self.action_result.status.text = str[start:end]
00363 start = end
00364 end += 4
00365 (length,) = _struct_I.unpack(str[start:end])
00366 self.action_result.result.executed_footsteps = []
00367 for i in range(0, length):
00368 val1 = humanoid_nav_msgs.msg.StepTarget()
00369 _v5 = val1.pose
00370 _x = _v5
00371 start = end
00372 end += 24
00373 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00374 start = end
00375 end += 1
00376 (val1.leg,) = _struct_B.unpack(str[start:end])
00377 self.action_result.result.executed_footsteps.append(val1)
00378 _x = self
00379 start = end
00380 end += 12
00381 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00382 start = end
00383 end += 4
00384 (length,) = _struct_I.unpack(str[start:end])
00385 start = end
00386 end += length
00387 if python3:
00388 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00389 else:
00390 self.action_feedback.header.frame_id = str[start:end]
00391 _x = self
00392 start = end
00393 end += 8
00394 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.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 if python3:
00401 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00402 else:
00403 self.action_feedback.status.goal_id.id = str[start:end]
00404 start = end
00405 end += 1
00406 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00407 start = end
00408 end += 4
00409 (length,) = _struct_I.unpack(str[start:end])
00410 start = end
00411 end += length
00412 if python3:
00413 self.action_feedback.status.text = str[start:end].decode('utf-8')
00414 else:
00415 self.action_feedback.status.text = str[start:end]
00416 start = end
00417 end += 4
00418 (length,) = _struct_I.unpack(str[start:end])
00419 self.action_feedback.feedback.executed_footsteps = []
00420 for i in range(0, length):
00421 val1 = humanoid_nav_msgs.msg.StepTarget()
00422 _v6 = val1.pose
00423 _x = _v6
00424 start = end
00425 end += 24
00426 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00427 start = end
00428 end += 1
00429 (val1.leg,) = _struct_B.unpack(str[start:end])
00430 self.action_feedback.feedback.executed_footsteps.append(val1)
00431 return self
00432 except struct.error as e:
00433 raise genpy.DeserializationError(e)
00434
00435
00436 def serialize_numpy(self, buff, numpy):
00437 """
00438 serialize message with numpy array types into buffer
00439 :param buff: buffer, ``StringIO``
00440 :param numpy: numpy python module
00441 """
00442 try:
00443 _x = self
00444 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00445 _x = self.action_goal.header.frame_id
00446 length = len(_x)
00447 if python3 or type(_x) == unicode:
00448 _x = _x.encode('utf-8')
00449 length = len(_x)
00450 buff.write(struct.pack('<I%ss'%length, length, _x))
00451 _x = self
00452 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00453 _x = self.action_goal.goal_id.id
00454 length = len(_x)
00455 if python3 or type(_x) == unicode:
00456 _x = _x.encode('utf-8')
00457 length = len(_x)
00458 buff.write(struct.pack('<I%ss'%length, length, _x))
00459 length = len(self.action_goal.goal.footsteps)
00460 buff.write(_struct_I.pack(length))
00461 for val1 in self.action_goal.goal.footsteps:
00462 _v7 = val1.pose
00463 _x = _v7
00464 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00465 buff.write(_struct_B.pack(val1.leg))
00466 _x = self
00467 buff.write(_struct_d3I.pack(_x.action_goal.goal.feedback_frequency, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00468 _x = self.action_result.header.frame_id
00469 length = len(_x)
00470 if python3 or type(_x) == unicode:
00471 _x = _x.encode('utf-8')
00472 length = len(_x)
00473 buff.write(struct.pack('<I%ss'%length, length, _x))
00474 _x = self
00475 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00476 _x = self.action_result.status.goal_id.id
00477 length = len(_x)
00478 if python3 or type(_x) == unicode:
00479 _x = _x.encode('utf-8')
00480 length = len(_x)
00481 buff.write(struct.pack('<I%ss'%length, length, _x))
00482 buff.write(_struct_B.pack(self.action_result.status.status))
00483 _x = self.action_result.status.text
00484 length = len(_x)
00485 if python3 or type(_x) == unicode:
00486 _x = _x.encode('utf-8')
00487 length = len(_x)
00488 buff.write(struct.pack('<I%ss'%length, length, _x))
00489 length = len(self.action_result.result.executed_footsteps)
00490 buff.write(_struct_I.pack(length))
00491 for val1 in self.action_result.result.executed_footsteps:
00492 _v8 = val1.pose
00493 _x = _v8
00494 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00495 buff.write(_struct_B.pack(val1.leg))
00496 _x = self
00497 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00498 _x = self.action_feedback.header.frame_id
00499 length = len(_x)
00500 if python3 or type(_x) == unicode:
00501 _x = _x.encode('utf-8')
00502 length = len(_x)
00503 buff.write(struct.pack('<I%ss'%length, length, _x))
00504 _x = self
00505 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00506 _x = self.action_feedback.status.goal_id.id
00507 length = len(_x)
00508 if python3 or type(_x) == unicode:
00509 _x = _x.encode('utf-8')
00510 length = len(_x)
00511 buff.write(struct.pack('<I%ss'%length, length, _x))
00512 buff.write(_struct_B.pack(self.action_feedback.status.status))
00513 _x = self.action_feedback.status.text
00514 length = len(_x)
00515 if python3 or type(_x) == unicode:
00516 _x = _x.encode('utf-8')
00517 length = len(_x)
00518 buff.write(struct.pack('<I%ss'%length, length, _x))
00519 length = len(self.action_feedback.feedback.executed_footsteps)
00520 buff.write(_struct_I.pack(length))
00521 for val1 in self.action_feedback.feedback.executed_footsteps:
00522 _v9 = val1.pose
00523 _x = _v9
00524 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00525 buff.write(_struct_B.pack(val1.leg))
00526 except struct.error as se: self._check_types(se)
00527 except TypeError as te: self._check_types(te)
00528
00529 def deserialize_numpy(self, str, numpy):
00530 """
00531 unpack serialized message in str into this message instance using numpy for array types
00532 :param str: byte array of serialized message, ``str``
00533 :param numpy: numpy python module
00534 """
00535 try:
00536 if self.action_goal is None:
00537 self.action_goal = humanoid_nav_msgs.msg.ExecFootstepsActionGoal()
00538 if self.action_result is None:
00539 self.action_result = humanoid_nav_msgs.msg.ExecFootstepsActionResult()
00540 if self.action_feedback is None:
00541 self.action_feedback = humanoid_nav_msgs.msg.ExecFootstepsActionFeedback()
00542 end = 0
00543 _x = self
00544 start = end
00545 end += 12
00546 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00547 start = end
00548 end += 4
00549 (length,) = _struct_I.unpack(str[start:end])
00550 start = end
00551 end += length
00552 if python3:
00553 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00554 else:
00555 self.action_goal.header.frame_id = str[start:end]
00556 _x = self
00557 start = end
00558 end += 8
00559 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00560 start = end
00561 end += 4
00562 (length,) = _struct_I.unpack(str[start:end])
00563 start = end
00564 end += length
00565 if python3:
00566 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00567 else:
00568 self.action_goal.goal_id.id = str[start:end]
00569 start = end
00570 end += 4
00571 (length,) = _struct_I.unpack(str[start:end])
00572 self.action_goal.goal.footsteps = []
00573 for i in range(0, length):
00574 val1 = humanoid_nav_msgs.msg.StepTarget()
00575 _v10 = val1.pose
00576 _x = _v10
00577 start = end
00578 end += 24
00579 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00580 start = end
00581 end += 1
00582 (val1.leg,) = _struct_B.unpack(str[start:end])
00583 self.action_goal.goal.footsteps.append(val1)
00584 _x = self
00585 start = end
00586 end += 20
00587 (_x.action_goal.goal.feedback_frequency, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_d3I.unpack(str[start:end])
00588 start = end
00589 end += 4
00590 (length,) = _struct_I.unpack(str[start:end])
00591 start = end
00592 end += length
00593 if python3:
00594 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00595 else:
00596 self.action_result.header.frame_id = str[start:end]
00597 _x = self
00598 start = end
00599 end += 8
00600 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.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 if python3:
00607 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00608 else:
00609 self.action_result.status.goal_id.id = str[start:end]
00610 start = end
00611 end += 1
00612 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00613 start = end
00614 end += 4
00615 (length,) = _struct_I.unpack(str[start:end])
00616 start = end
00617 end += length
00618 if python3:
00619 self.action_result.status.text = str[start:end].decode('utf-8')
00620 else:
00621 self.action_result.status.text = str[start:end]
00622 start = end
00623 end += 4
00624 (length,) = _struct_I.unpack(str[start:end])
00625 self.action_result.result.executed_footsteps = []
00626 for i in range(0, length):
00627 val1 = humanoid_nav_msgs.msg.StepTarget()
00628 _v11 = val1.pose
00629 _x = _v11
00630 start = end
00631 end += 24
00632 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00633 start = end
00634 end += 1
00635 (val1.leg,) = _struct_B.unpack(str[start:end])
00636 self.action_result.result.executed_footsteps.append(val1)
00637 _x = self
00638 start = end
00639 end += 12
00640 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00641 start = end
00642 end += 4
00643 (length,) = _struct_I.unpack(str[start:end])
00644 start = end
00645 end += length
00646 if python3:
00647 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00648 else:
00649 self.action_feedback.header.frame_id = str[start:end]
00650 _x = self
00651 start = end
00652 end += 8
00653 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00654 start = end
00655 end += 4
00656 (length,) = _struct_I.unpack(str[start:end])
00657 start = end
00658 end += length
00659 if python3:
00660 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00661 else:
00662 self.action_feedback.status.goal_id.id = str[start:end]
00663 start = end
00664 end += 1
00665 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00666 start = end
00667 end += 4
00668 (length,) = _struct_I.unpack(str[start:end])
00669 start = end
00670 end += length
00671 if python3:
00672 self.action_feedback.status.text = str[start:end].decode('utf-8')
00673 else:
00674 self.action_feedback.status.text = str[start:end]
00675 start = end
00676 end += 4
00677 (length,) = _struct_I.unpack(str[start:end])
00678 self.action_feedback.feedback.executed_footsteps = []
00679 for i in range(0, length):
00680 val1 = humanoid_nav_msgs.msg.StepTarget()
00681 _v12 = val1.pose
00682 _x = _v12
00683 start = end
00684 end += 24
00685 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00686 start = end
00687 end += 1
00688 (val1.leg,) = _struct_B.unpack(str[start:end])
00689 self.action_feedback.feedback.executed_footsteps.append(val1)
00690 return self
00691 except struct.error as e:
00692 raise genpy.DeserializationError(e)
00693
00694 _struct_I = genpy.struct_I
00695 _struct_3I = struct.Struct("<3I")
00696 _struct_B = struct.Struct("<B")
00697 _struct_d3I = struct.Struct("<d3I")
00698 _struct_2I = struct.Struct("<2I")
00699 _struct_3d = struct.Struct("<3d")