$search
00001 """autogenerated by genmsg_py from ExecFootstepsActionFeedback.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 ExecFootstepsActionFeedback(roslib.message.Message): 00012 _md5sum = "01da67223a0592f0de40186a03f441ff" 00013 _type = "humanoid_nav_msgs/ExecFootstepsActionFeedback" 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 ExecFootstepsFeedback feedback 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/ExecFootstepsFeedback 00080 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00081 # Define a feedback message 00082 humanoid_nav_msgs/StepTarget[] executed_footsteps 00083 00084 00085 ================================================================================ 00086 MSG: humanoid_nav_msgs/StepTarget 00087 # Target for a single stepping motion of a humanoid's leg 00088 00089 geometry_msgs/Pose2D pose # step pose as relative offset to last leg 00090 uint8 leg # which leg to use (left/right, see below) 00091 00092 uint8 right=0 # right leg constant 00093 uint8 left=1 # left leg constant 00094 00095 ================================================================================ 00096 MSG: geometry_msgs/Pose2D 00097 # This expresses a position and orientation on a 2D manifold. 00098 00099 float64 x 00100 float64 y 00101 float64 theta 00102 """ 00103 __slots__ = ['header','status','feedback'] 00104 _slot_types = ['Header','actionlib_msgs/GoalStatus','humanoid_nav_msgs/ExecFootstepsFeedback'] 00105 00106 def __init__(self, *args, **kwds): 00107 """ 00108 Constructor. Any message fields that are implicitly/explicitly 00109 set to None will be assigned a default value. The recommend 00110 use is keyword arguments as this is more robust to future message 00111 changes. You cannot mix in-order arguments and keyword arguments. 00112 00113 The available fields are: 00114 header,status,feedback 00115 00116 @param args: complete set of field values, in .msg order 00117 @param kwds: use keyword arguments corresponding to message field names 00118 to set specific fields. 00119 """ 00120 if args or kwds: 00121 super(ExecFootstepsActionFeedback, self).__init__(*args, **kwds) 00122 #message fields cannot be None, assign default values for those that are 00123 if self.header is None: 00124 self.header = std_msgs.msg._Header.Header() 00125 if self.status is None: 00126 self.status = actionlib_msgs.msg.GoalStatus() 00127 if self.feedback is None: 00128 self.feedback = humanoid_nav_msgs.msg.ExecFootstepsFeedback() 00129 else: 00130 self.header = std_msgs.msg._Header.Header() 00131 self.status = actionlib_msgs.msg.GoalStatus() 00132 self.feedback = humanoid_nav_msgs.msg.ExecFootstepsFeedback() 00133 00134 def _get_types(self): 00135 """ 00136 internal API method 00137 """ 00138 return self._slot_types 00139 00140 def serialize(self, buff): 00141 """ 00142 serialize message into buffer 00143 @param buff: buffer 00144 @type buff: StringIO 00145 """ 00146 try: 00147 _x = self 00148 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00149 _x = self.header.frame_id 00150 length = len(_x) 00151 buff.write(struct.pack('<I%ss'%length, length, _x)) 00152 _x = self 00153 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs)) 00154 _x = self.status.goal_id.id 00155 length = len(_x) 00156 buff.write(struct.pack('<I%ss'%length, length, _x)) 00157 buff.write(_struct_B.pack(self.status.status)) 00158 _x = self.status.text 00159 length = len(_x) 00160 buff.write(struct.pack('<I%ss'%length, length, _x)) 00161 length = len(self.feedback.executed_footsteps) 00162 buff.write(_struct_I.pack(length)) 00163 for val1 in self.feedback.executed_footsteps: 00164 _v1 = val1.pose 00165 _x = _v1 00166 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta)) 00167 buff.write(_struct_B.pack(val1.leg)) 00168 except struct.error as se: self._check_types(se) 00169 except TypeError as te: self._check_types(te) 00170 00171 def deserialize(self, str): 00172 """ 00173 unpack serialized message in str into this message instance 00174 @param str: byte array of serialized message 00175 @type str: str 00176 """ 00177 try: 00178 if self.header is None: 00179 self.header = std_msgs.msg._Header.Header() 00180 if self.status is None: 00181 self.status = actionlib_msgs.msg.GoalStatus() 00182 if self.feedback is None: 00183 self.feedback = humanoid_nav_msgs.msg.ExecFootstepsFeedback() 00184 end = 0 00185 _x = self 00186 start = end 00187 end += 12 00188 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00189 start = end 00190 end += 4 00191 (length,) = _struct_I.unpack(str[start:end]) 00192 start = end 00193 end += length 00194 self.header.frame_id = str[start:end] 00195 _x = self 00196 start = end 00197 end += 8 00198 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00199 start = end 00200 end += 4 00201 (length,) = _struct_I.unpack(str[start:end]) 00202 start = end 00203 end += length 00204 self.status.goal_id.id = str[start:end] 00205 start = end 00206 end += 1 00207 (self.status.status,) = _struct_B.unpack(str[start:end]) 00208 start = end 00209 end += 4 00210 (length,) = _struct_I.unpack(str[start:end]) 00211 start = end 00212 end += length 00213 self.status.text = str[start:end] 00214 start = end 00215 end += 4 00216 (length,) = _struct_I.unpack(str[start:end]) 00217 self.feedback.executed_footsteps = [] 00218 for i in range(0, length): 00219 val1 = humanoid_nav_msgs.msg.StepTarget() 00220 _v2 = val1.pose 00221 _x = _v2 00222 start = end 00223 end += 24 00224 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end]) 00225 start = end 00226 end += 1 00227 (val1.leg,) = _struct_B.unpack(str[start:end]) 00228 self.feedback.executed_footsteps.append(val1) 00229 return self 00230 except struct.error as e: 00231 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00232 00233 00234 def serialize_numpy(self, buff, numpy): 00235 """ 00236 serialize message with numpy array types into buffer 00237 @param buff: buffer 00238 @type buff: StringIO 00239 @param numpy: numpy python module 00240 @type numpy module 00241 """ 00242 try: 00243 _x = self 00244 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00245 _x = self.header.frame_id 00246 length = len(_x) 00247 buff.write(struct.pack('<I%ss'%length, length, _x)) 00248 _x = self 00249 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs)) 00250 _x = self.status.goal_id.id 00251 length = len(_x) 00252 buff.write(struct.pack('<I%ss'%length, length, _x)) 00253 buff.write(_struct_B.pack(self.status.status)) 00254 _x = self.status.text 00255 length = len(_x) 00256 buff.write(struct.pack('<I%ss'%length, length, _x)) 00257 length = len(self.feedback.executed_footsteps) 00258 buff.write(_struct_I.pack(length)) 00259 for val1 in self.feedback.executed_footsteps: 00260 _v3 = val1.pose 00261 _x = _v3 00262 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta)) 00263 buff.write(_struct_B.pack(val1.leg)) 00264 except struct.error as se: self._check_types(se) 00265 except TypeError as te: self._check_types(te) 00266 00267 def deserialize_numpy(self, str, numpy): 00268 """ 00269 unpack serialized message in str into this message instance using numpy for array types 00270 @param str: byte array of serialized message 00271 @type str: str 00272 @param numpy: numpy python module 00273 @type numpy: module 00274 """ 00275 try: 00276 if self.header is None: 00277 self.header = std_msgs.msg._Header.Header() 00278 if self.status is None: 00279 self.status = actionlib_msgs.msg.GoalStatus() 00280 if self.feedback is None: 00281 self.feedback = humanoid_nav_msgs.msg.ExecFootstepsFeedback() 00282 end = 0 00283 _x = self 00284 start = end 00285 end += 12 00286 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00287 start = end 00288 end += 4 00289 (length,) = _struct_I.unpack(str[start:end]) 00290 start = end 00291 end += length 00292 self.header.frame_id = str[start:end] 00293 _x = self 00294 start = end 00295 end += 8 00296 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00297 start = end 00298 end += 4 00299 (length,) = _struct_I.unpack(str[start:end]) 00300 start = end 00301 end += length 00302 self.status.goal_id.id = str[start:end] 00303 start = end 00304 end += 1 00305 (self.status.status,) = _struct_B.unpack(str[start:end]) 00306 start = end 00307 end += 4 00308 (length,) = _struct_I.unpack(str[start:end]) 00309 start = end 00310 end += length 00311 self.status.text = str[start:end] 00312 start = end 00313 end += 4 00314 (length,) = _struct_I.unpack(str[start:end]) 00315 self.feedback.executed_footsteps = [] 00316 for i in range(0, length): 00317 val1 = humanoid_nav_msgs.msg.StepTarget() 00318 _v4 = val1.pose 00319 _x = _v4 00320 start = end 00321 end += 24 00322 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end]) 00323 start = end 00324 end += 1 00325 (val1.leg,) = _struct_B.unpack(str[start:end]) 00326 self.feedback.executed_footsteps.append(val1) 00327 return self 00328 except struct.error as e: 00329 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00330 00331 _struct_I = roslib.message.struct_I 00332 _struct_3I = struct.Struct("<3I") 00333 _struct_B = struct.Struct("<B") 00334 _struct_2I = struct.Struct("<2I") 00335 _struct_3d = struct.Struct("<3d")