$search
00001 """autogenerated by genmsg_py from PlanFootstepsRequest.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 00007 class PlanFootstepsRequest(roslib.message.Message): 00008 _md5sum = "5e8ecd9fb61e382b8974a904baeee367" 00009 _type = "humanoid_nav_msgs/PlanFootstepsRequest" 00010 _has_header = False #flag to mark the presence of a Header object 00011 _full_text = """geometry_msgs/Pose2D start 00012 geometry_msgs/Pose2D goal 00013 00014 ================================================================================ 00015 MSG: geometry_msgs/Pose2D 00016 # This expresses a position and orientation on a 2D manifold. 00017 00018 float64 x 00019 float64 y 00020 float64 theta 00021 """ 00022 __slots__ = ['start','goal'] 00023 _slot_types = ['geometry_msgs/Pose2D','geometry_msgs/Pose2D'] 00024 00025 def __init__(self, *args, **kwds): 00026 """ 00027 Constructor. Any message fields that are implicitly/explicitly 00028 set to None will be assigned a default value. The recommend 00029 use is keyword arguments as this is more robust to future message 00030 changes. You cannot mix in-order arguments and keyword arguments. 00031 00032 The available fields are: 00033 start,goal 00034 00035 @param args: complete set of field values, in .msg order 00036 @param kwds: use keyword arguments corresponding to message field names 00037 to set specific fields. 00038 """ 00039 if args or kwds: 00040 super(PlanFootstepsRequest, self).__init__(*args, **kwds) 00041 #message fields cannot be None, assign default values for those that are 00042 if self.start is None: 00043 self.start = geometry_msgs.msg.Pose2D() 00044 if self.goal is None: 00045 self.goal = geometry_msgs.msg.Pose2D() 00046 else: 00047 self.start = geometry_msgs.msg.Pose2D() 00048 self.goal = geometry_msgs.msg.Pose2D() 00049 00050 def _get_types(self): 00051 """ 00052 internal API method 00053 """ 00054 return self._slot_types 00055 00056 def serialize(self, buff): 00057 """ 00058 serialize message into buffer 00059 @param buff: buffer 00060 @type buff: StringIO 00061 """ 00062 try: 00063 _x = self 00064 buff.write(_struct_6d.pack(_x.start.x, _x.start.y, _x.start.theta, _x.goal.x, _x.goal.y, _x.goal.theta)) 00065 except struct.error as se: self._check_types(se) 00066 except TypeError as te: self._check_types(te) 00067 00068 def deserialize(self, str): 00069 """ 00070 unpack serialized message in str into this message instance 00071 @param str: byte array of serialized message 00072 @type str: str 00073 """ 00074 try: 00075 if self.start is None: 00076 self.start = geometry_msgs.msg.Pose2D() 00077 if self.goal is None: 00078 self.goal = geometry_msgs.msg.Pose2D() 00079 end = 0 00080 _x = self 00081 start = end 00082 end += 48 00083 (_x.start.x, _x.start.y, _x.start.theta, _x.goal.x, _x.goal.y, _x.goal.theta,) = _struct_6d.unpack(str[start:end]) 00084 return self 00085 except struct.error as e: 00086 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00087 00088 00089 def serialize_numpy(self, buff, numpy): 00090 """ 00091 serialize message with numpy array types into buffer 00092 @param buff: buffer 00093 @type buff: StringIO 00094 @param numpy: numpy python module 00095 @type numpy module 00096 """ 00097 try: 00098 _x = self 00099 buff.write(_struct_6d.pack(_x.start.x, _x.start.y, _x.start.theta, _x.goal.x, _x.goal.y, _x.goal.theta)) 00100 except struct.error as se: self._check_types(se) 00101 except TypeError as te: self._check_types(te) 00102 00103 def deserialize_numpy(self, str, numpy): 00104 """ 00105 unpack serialized message in str into this message instance using numpy for array types 00106 @param str: byte array of serialized message 00107 @type str: str 00108 @param numpy: numpy python module 00109 @type numpy: module 00110 """ 00111 try: 00112 if self.start is None: 00113 self.start = geometry_msgs.msg.Pose2D() 00114 if self.goal is None: 00115 self.goal = geometry_msgs.msg.Pose2D() 00116 end = 0 00117 _x = self 00118 start = end 00119 end += 48 00120 (_x.start.x, _x.start.y, _x.start.theta, _x.goal.x, _x.goal.y, _x.goal.theta,) = _struct_6d.unpack(str[start:end]) 00121 return self 00122 except struct.error as e: 00123 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00124 00125 _struct_I = roslib.message.struct_I 00126 _struct_6d = struct.Struct("<6d") 00127 """autogenerated by genmsg_py from PlanFootstepsResponse.msg. Do not edit.""" 00128 import roslib.message 00129 import struct 00130 00131 import geometry_msgs.msg 00132 import humanoid_nav_msgs.msg 00133 00134 class PlanFootstepsResponse(roslib.message.Message): 00135 _md5sum = "1af07cd1d4ffe34a9a731e87aa13835c" 00136 _type = "humanoid_nav_msgs/PlanFootstepsResponse" 00137 _has_header = False #flag to mark the presence of a Header object 00138 _full_text = """bool result 00139 humanoid_nav_msgs/StepTarget[] footsteps 00140 float64 costs 00141 float64 final_eps 00142 float64 planning_time 00143 int64 expanded_states 00144 00145 00146 ================================================================================ 00147 MSG: humanoid_nav_msgs/StepTarget 00148 # Target for a single stepping motion of a humanoid's leg 00149 00150 geometry_msgs/Pose2D pose # step pose as relative offset to last leg 00151 uint8 leg # which leg to use (left/right, see below) 00152 00153 uint8 right=0 # right leg constant 00154 uint8 left=1 # left leg constant 00155 00156 ================================================================================ 00157 MSG: geometry_msgs/Pose2D 00158 # This expresses a position and orientation on a 2D manifold. 00159 00160 float64 x 00161 float64 y 00162 float64 theta 00163 """ 00164 __slots__ = ['result','footsteps','costs','final_eps','planning_time','expanded_states'] 00165 _slot_types = ['bool','humanoid_nav_msgs/StepTarget[]','float64','float64','float64','int64'] 00166 00167 def __init__(self, *args, **kwds): 00168 """ 00169 Constructor. Any message fields that are implicitly/explicitly 00170 set to None will be assigned a default value. The recommend 00171 use is keyword arguments as this is more robust to future message 00172 changes. You cannot mix in-order arguments and keyword arguments. 00173 00174 The available fields are: 00175 result,footsteps,costs,final_eps,planning_time,expanded_states 00176 00177 @param args: complete set of field values, in .msg order 00178 @param kwds: use keyword arguments corresponding to message field names 00179 to set specific fields. 00180 """ 00181 if args or kwds: 00182 super(PlanFootstepsResponse, self).__init__(*args, **kwds) 00183 #message fields cannot be None, assign default values for those that are 00184 if self.result is None: 00185 self.result = False 00186 if self.footsteps is None: 00187 self.footsteps = [] 00188 if self.costs is None: 00189 self.costs = 0. 00190 if self.final_eps is None: 00191 self.final_eps = 0. 00192 if self.planning_time is None: 00193 self.planning_time = 0. 00194 if self.expanded_states is None: 00195 self.expanded_states = 0 00196 else: 00197 self.result = False 00198 self.footsteps = [] 00199 self.costs = 0. 00200 self.final_eps = 0. 00201 self.planning_time = 0. 00202 self.expanded_states = 0 00203 00204 def _get_types(self): 00205 """ 00206 internal API method 00207 """ 00208 return self._slot_types 00209 00210 def serialize(self, buff): 00211 """ 00212 serialize message into buffer 00213 @param buff: buffer 00214 @type buff: StringIO 00215 """ 00216 try: 00217 buff.write(_struct_B.pack(self.result)) 00218 length = len(self.footsteps) 00219 buff.write(_struct_I.pack(length)) 00220 for val1 in self.footsteps: 00221 _v1 = val1.pose 00222 _x = _v1 00223 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta)) 00224 buff.write(_struct_B.pack(val1.leg)) 00225 _x = self 00226 buff.write(_struct_3dq.pack(_x.costs, _x.final_eps, _x.planning_time, _x.expanded_states)) 00227 except struct.error as se: self._check_types(se) 00228 except TypeError as te: self._check_types(te) 00229 00230 def deserialize(self, str): 00231 """ 00232 unpack serialized message in str into this message instance 00233 @param str: byte array of serialized message 00234 @type str: str 00235 """ 00236 try: 00237 end = 0 00238 start = end 00239 end += 1 00240 (self.result,) = _struct_B.unpack(str[start:end]) 00241 self.result = bool(self.result) 00242 start = end 00243 end += 4 00244 (length,) = _struct_I.unpack(str[start:end]) 00245 self.footsteps = [] 00246 for i in range(0, length): 00247 val1 = humanoid_nav_msgs.msg.StepTarget() 00248 _v2 = val1.pose 00249 _x = _v2 00250 start = end 00251 end += 24 00252 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end]) 00253 start = end 00254 end += 1 00255 (val1.leg,) = _struct_B.unpack(str[start:end]) 00256 self.footsteps.append(val1) 00257 _x = self 00258 start = end 00259 end += 32 00260 (_x.costs, _x.final_eps, _x.planning_time, _x.expanded_states,) = _struct_3dq.unpack(str[start:end]) 00261 return self 00262 except struct.error as e: 00263 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00264 00265 00266 def serialize_numpy(self, buff, numpy): 00267 """ 00268 serialize message with numpy array types into buffer 00269 @param buff: buffer 00270 @type buff: StringIO 00271 @param numpy: numpy python module 00272 @type numpy module 00273 """ 00274 try: 00275 buff.write(_struct_B.pack(self.result)) 00276 length = len(self.footsteps) 00277 buff.write(_struct_I.pack(length)) 00278 for val1 in self.footsteps: 00279 _v3 = val1.pose 00280 _x = _v3 00281 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta)) 00282 buff.write(_struct_B.pack(val1.leg)) 00283 _x = self 00284 buff.write(_struct_3dq.pack(_x.costs, _x.final_eps, _x.planning_time, _x.expanded_states)) 00285 except struct.error as se: self._check_types(se) 00286 except TypeError as te: self._check_types(te) 00287 00288 def deserialize_numpy(self, str, numpy): 00289 """ 00290 unpack serialized message in str into this message instance using numpy for array types 00291 @param str: byte array of serialized message 00292 @type str: str 00293 @param numpy: numpy python module 00294 @type numpy: module 00295 """ 00296 try: 00297 end = 0 00298 start = end 00299 end += 1 00300 (self.result,) = _struct_B.unpack(str[start:end]) 00301 self.result = bool(self.result) 00302 start = end 00303 end += 4 00304 (length,) = _struct_I.unpack(str[start:end]) 00305 self.footsteps = [] 00306 for i in range(0, length): 00307 val1 = humanoid_nav_msgs.msg.StepTarget() 00308 _v4 = val1.pose 00309 _x = _v4 00310 start = end 00311 end += 24 00312 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end]) 00313 start = end 00314 end += 1 00315 (val1.leg,) = _struct_B.unpack(str[start:end]) 00316 self.footsteps.append(val1) 00317 _x = self 00318 start = end 00319 end += 32 00320 (_x.costs, _x.final_eps, _x.planning_time, _x.expanded_states,) = _struct_3dq.unpack(str[start:end]) 00321 return self 00322 except struct.error as e: 00323 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00324 00325 _struct_I = roslib.message.struct_I 00326 _struct_B = struct.Struct("<B") 00327 _struct_3dq = struct.Struct("<3dq") 00328 _struct_3d = struct.Struct("<3d") 00329 class PlanFootsteps(roslib.message.ServiceDefinition): 00330 _type = 'humanoid_nav_msgs/PlanFootsteps' 00331 _md5sum = '6776471c1b6635688929b81b014b1c1c' 00332 _request_class = PlanFootstepsRequest 00333 _response_class = PlanFootstepsResponse