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