$search
00001 """autogenerated by genmsg_py from ExecFootstepsActionResult.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 ExecFootstepsActionResult(roslib.message.Message): 00012 _md5sum = "66fa71246c6848e28e972f9031bbbddc" 00013 _type = "humanoid_nav_msgs/ExecFootstepsActionResult" 00014 _has_header = True #flag to mark the presence of a Header object 00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00016 00017 Header header 00018 actionlib_msgs/GoalStatus status 00019 ExecFootstepsResult result 00020 00021 ================================================================================ 00022 MSG: std_msgs/Header 00023 # Standard metadata for higher-level stamped data types. 00024 # This is generally used to communicate timestamped data 00025 # in a particular coordinate frame. 00026 # 00027 # sequence ID: consecutively increasing ID 00028 uint32 seq 00029 #Two-integer timestamp that is expressed as: 00030 # * stamp.secs: seconds (stamp_secs) since epoch 00031 # * stamp.nsecs: nanoseconds since stamp_secs 00032 # time-handling sugar is provided by the client library 00033 time stamp 00034 #Frame this data is associated with 00035 # 0: no frame 00036 # 1: global frame 00037 string frame_id 00038 00039 ================================================================================ 00040 MSG: actionlib_msgs/GoalStatus 00041 GoalID goal_id 00042 uint8 status 00043 uint8 PENDING = 0 # The goal has yet to be processed by the action server 00044 uint8 ACTIVE = 1 # The goal is currently being processed by the action server 00045 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 00046 # and has since completed its execution (Terminal State) 00047 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 00048 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 00049 # to some failure (Terminal State) 00050 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 00051 # because the goal was unattainable or invalid (Terminal State) 00052 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 00053 # and has not yet completed execution 00054 uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 00055 # but the action server has not yet confirmed that the goal is canceled 00056 uint8 RECALLED = 8 # The goal received a cancel request before it started executing 00057 # and was successfully cancelled (Terminal State) 00058 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 00059 # sent over the wire by an action server 00060 00061 #Allow for the user to associate a string with GoalStatus for debugging 00062 string text 00063 00064 00065 ================================================================================ 00066 MSG: actionlib_msgs/GoalID 00067 # The stamp should store the time at which this goal was requested. 00068 # It is used by an action server when it tries to preempt all 00069 # goals that were requested before a certain time 00070 time stamp 00071 00072 # The id provides a way to associate feedback and 00073 # result message with specific goal requests. The id 00074 # specified must be unique. 00075 string id 00076 00077 00078 ================================================================================ 00079 MSG: humanoid_nav_msgs/ExecFootstepsResult 00080 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00081 # Define the result 00082 humanoid_nav_msgs/StepTarget[] executed_footsteps 00083 00084 ================================================================================ 00085 MSG: humanoid_nav_msgs/StepTarget 00086 # Target for a single stepping motion of a humanoid's leg 00087 00088 geometry_msgs/Pose2D pose # step pose as relative offset to last leg 00089 uint8 leg # which leg to use (left/right, see below) 00090 00091 uint8 right=0 # right leg constant 00092 uint8 left=1 # left leg constant 00093 00094 ================================================================================ 00095 MSG: geometry_msgs/Pose2D 00096 # This expresses a position and orientation on a 2D manifold. 00097 00098 float64 x 00099 float64 y 00100 float64 theta 00101 """ 00102 __slots__ = ['header','status','result'] 00103 _slot_types = ['Header','actionlib_msgs/GoalStatus','humanoid_nav_msgs/ExecFootstepsResult'] 00104 00105 def __init__(self, *args, **kwds): 00106 """ 00107 Constructor. Any message fields that are implicitly/explicitly 00108 set to None will be assigned a default value. The recommend 00109 use is keyword arguments as this is more robust to future message 00110 changes. You cannot mix in-order arguments and keyword arguments. 00111 00112 The available fields are: 00113 header,status,result 00114 00115 @param args: complete set of field values, in .msg order 00116 @param kwds: use keyword arguments corresponding to message field names 00117 to set specific fields. 00118 """ 00119 if args or kwds: 00120 super(ExecFootstepsActionResult, self).__init__(*args, **kwds) 00121 #message fields cannot be None, assign default values for those that are 00122 if self.header is None: 00123 self.header = std_msgs.msg._Header.Header() 00124 if self.status is None: 00125 self.status = actionlib_msgs.msg.GoalStatus() 00126 if self.result is None: 00127 self.result = humanoid_nav_msgs.msg.ExecFootstepsResult() 00128 else: 00129 self.header = std_msgs.msg._Header.Header() 00130 self.status = actionlib_msgs.msg.GoalStatus() 00131 self.result = humanoid_nav_msgs.msg.ExecFootstepsResult() 00132 00133 def _get_types(self): 00134 """ 00135 internal API method 00136 """ 00137 return self._slot_types 00138 00139 def serialize(self, buff): 00140 """ 00141 serialize message into buffer 00142 @param buff: buffer 00143 @type buff: StringIO 00144 """ 00145 try: 00146 _x = self 00147 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00148 _x = self.header.frame_id 00149 length = len(_x) 00150 buff.write(struct.pack('<I%ss'%length, length, _x)) 00151 _x = self 00152 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs)) 00153 _x = self.status.goal_id.id 00154 length = len(_x) 00155 buff.write(struct.pack('<I%ss'%length, length, _x)) 00156 buff.write(_struct_B.pack(self.status.status)) 00157 _x = self.status.text 00158 length = len(_x) 00159 buff.write(struct.pack('<I%ss'%length, length, _x)) 00160 length = len(self.result.executed_footsteps) 00161 buff.write(_struct_I.pack(length)) 00162 for val1 in self.result.executed_footsteps: 00163 _v1 = val1.pose 00164 _x = _v1 00165 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta)) 00166 buff.write(_struct_B.pack(val1.leg)) 00167 except struct.error as se: self._check_types(se) 00168 except TypeError as te: self._check_types(te) 00169 00170 def deserialize(self, str): 00171 """ 00172 unpack serialized message in str into this message instance 00173 @param str: byte array of serialized message 00174 @type str: str 00175 """ 00176 try: 00177 if self.header is None: 00178 self.header = std_msgs.msg._Header.Header() 00179 if self.status is None: 00180 self.status = actionlib_msgs.msg.GoalStatus() 00181 if self.result is None: 00182 self.result = humanoid_nav_msgs.msg.ExecFootstepsResult() 00183 end = 0 00184 _x = self 00185 start = end 00186 end += 12 00187 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00188 start = end 00189 end += 4 00190 (length,) = _struct_I.unpack(str[start:end]) 00191 start = end 00192 end += length 00193 self.header.frame_id = str[start:end] 00194 _x = self 00195 start = end 00196 end += 8 00197 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00198 start = end 00199 end += 4 00200 (length,) = _struct_I.unpack(str[start:end]) 00201 start = end 00202 end += length 00203 self.status.goal_id.id = str[start:end] 00204 start = end 00205 end += 1 00206 (self.status.status,) = _struct_B.unpack(str[start:end]) 00207 start = end 00208 end += 4 00209 (length,) = _struct_I.unpack(str[start:end]) 00210 start = end 00211 end += length 00212 self.status.text = str[start:end] 00213 start = end 00214 end += 4 00215 (length,) = _struct_I.unpack(str[start:end]) 00216 self.result.executed_footsteps = [] 00217 for i in range(0, length): 00218 val1 = humanoid_nav_msgs.msg.StepTarget() 00219 _v2 = val1.pose 00220 _x = _v2 00221 start = end 00222 end += 24 00223 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end]) 00224 start = end 00225 end += 1 00226 (val1.leg,) = _struct_B.unpack(str[start:end]) 00227 self.result.executed_footsteps.append(val1) 00228 return self 00229 except struct.error as e: 00230 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00231 00232 00233 def serialize_numpy(self, buff, numpy): 00234 """ 00235 serialize message with numpy array types into buffer 00236 @param buff: buffer 00237 @type buff: StringIO 00238 @param numpy: numpy python module 00239 @type numpy module 00240 """ 00241 try: 00242 _x = self 00243 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00244 _x = self.header.frame_id 00245 length = len(_x) 00246 buff.write(struct.pack('<I%ss'%length, length, _x)) 00247 _x = self 00248 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs)) 00249 _x = self.status.goal_id.id 00250 length = len(_x) 00251 buff.write(struct.pack('<I%ss'%length, length, _x)) 00252 buff.write(_struct_B.pack(self.status.status)) 00253 _x = self.status.text 00254 length = len(_x) 00255 buff.write(struct.pack('<I%ss'%length, length, _x)) 00256 length = len(self.result.executed_footsteps) 00257 buff.write(_struct_I.pack(length)) 00258 for val1 in self.result.executed_footsteps: 00259 _v3 = val1.pose 00260 _x = _v3 00261 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta)) 00262 buff.write(_struct_B.pack(val1.leg)) 00263 except struct.error as se: self._check_types(se) 00264 except TypeError as te: self._check_types(te) 00265 00266 def deserialize_numpy(self, str, numpy): 00267 """ 00268 unpack serialized message in str into this message instance using numpy for array types 00269 @param str: byte array of serialized message 00270 @type str: str 00271 @param numpy: numpy python module 00272 @type numpy: module 00273 """ 00274 try: 00275 if self.header is None: 00276 self.header = std_msgs.msg._Header.Header() 00277 if self.status is None: 00278 self.status = actionlib_msgs.msg.GoalStatus() 00279 if self.result is None: 00280 self.result = humanoid_nav_msgs.msg.ExecFootstepsResult() 00281 end = 0 00282 _x = self 00283 start = end 00284 end += 12 00285 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00286 start = end 00287 end += 4 00288 (length,) = _struct_I.unpack(str[start:end]) 00289 start = end 00290 end += length 00291 self.header.frame_id = str[start:end] 00292 _x = self 00293 start = end 00294 end += 8 00295 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00296 start = end 00297 end += 4 00298 (length,) = _struct_I.unpack(str[start:end]) 00299 start = end 00300 end += length 00301 self.status.goal_id.id = str[start:end] 00302 start = end 00303 end += 1 00304 (self.status.status,) = _struct_B.unpack(str[start:end]) 00305 start = end 00306 end += 4 00307 (length,) = _struct_I.unpack(str[start:end]) 00308 start = end 00309 end += length 00310 self.status.text = str[start:end] 00311 start = end 00312 end += 4 00313 (length,) = _struct_I.unpack(str[start:end]) 00314 self.result.executed_footsteps = [] 00315 for i in range(0, length): 00316 val1 = humanoid_nav_msgs.msg.StepTarget() 00317 _v4 = val1.pose 00318 _x = _v4 00319 start = end 00320 end += 24 00321 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end]) 00322 start = end 00323 end += 1 00324 (val1.leg,) = _struct_B.unpack(str[start:end]) 00325 self.result.executed_footsteps.append(val1) 00326 return self 00327 except struct.error as e: 00328 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00329 00330 _struct_I = roslib.message.struct_I 00331 _struct_3I = struct.Struct("<3I") 00332 _struct_B = struct.Struct("<B") 00333 _struct_2I = struct.Struct("<2I") 00334 _struct_3d = struct.Struct("<3d")