$search
00001 """autogenerated by genmsg_py from GetPathRequest.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import walk_msgs.msg 00006 import geometry_msgs.msg 00007 import roslib.rostime 00008 00009 class GetPathRequest(roslib.message.Message): 00010 _md5sum = "9325cbcfc330e3e7667ffad5cb6d4c50" 00011 _type = "walk_msgs/GetPathRequest" 00012 _has_header = False #flag to mark the presence of a Header object 00013 _full_text = """geometry_msgs/Pose initial_left_foot_position 00014 geometry_msgs/Pose initial_right_foot_position 00015 geometry_msgs/Point initial_center_of_mass_position 00016 00017 geometry_msgs/Pose final_left_foot_position 00018 geometry_msgs/Pose final_right_foot_position 00019 geometry_msgs/Point final_center_of_mass_position 00020 00021 bool start_with_left_foot 00022 00023 walk_msgs/Footprint2d[] footprints 00024 00025 ================================================================================ 00026 MSG: geometry_msgs/Pose 00027 # A representation of pose in free space, composed of postion and orientation. 00028 Point position 00029 Quaternion orientation 00030 00031 ================================================================================ 00032 MSG: geometry_msgs/Point 00033 # This contains the position of a point in free space 00034 float64 x 00035 float64 y 00036 float64 z 00037 00038 ================================================================================ 00039 MSG: geometry_msgs/Quaternion 00040 # This represents an orientation in free space in quaternion form. 00041 00042 float64 x 00043 float64 y 00044 float64 z 00045 float64 w 00046 00047 ================================================================================ 00048 MSG: walk_msgs/Footprint2d 00049 time beginTime 00050 duration duration 00051 float64 x 00052 float64 y 00053 float64 theta 00054 00055 """ 00056 __slots__ = ['initial_left_foot_position','initial_right_foot_position','initial_center_of_mass_position','final_left_foot_position','final_right_foot_position','final_center_of_mass_position','start_with_left_foot','footprints'] 00057 _slot_types = ['geometry_msgs/Pose','geometry_msgs/Pose','geometry_msgs/Point','geometry_msgs/Pose','geometry_msgs/Pose','geometry_msgs/Point','bool','walk_msgs/Footprint2d[]'] 00058 00059 def __init__(self, *args, **kwds): 00060 """ 00061 Constructor. Any message fields that are implicitly/explicitly 00062 set to None will be assigned a default value. The recommend 00063 use is keyword arguments as this is more robust to future message 00064 changes. You cannot mix in-order arguments and keyword arguments. 00065 00066 The available fields are: 00067 initial_left_foot_position,initial_right_foot_position,initial_center_of_mass_position,final_left_foot_position,final_right_foot_position,final_center_of_mass_position,start_with_left_foot,footprints 00068 00069 @param args: complete set of field values, in .msg order 00070 @param kwds: use keyword arguments corresponding to message field names 00071 to set specific fields. 00072 """ 00073 if args or kwds: 00074 super(GetPathRequest, self).__init__(*args, **kwds) 00075 #message fields cannot be None, assign default values for those that are 00076 if self.initial_left_foot_position is None: 00077 self.initial_left_foot_position = geometry_msgs.msg.Pose() 00078 if self.initial_right_foot_position is None: 00079 self.initial_right_foot_position = geometry_msgs.msg.Pose() 00080 if self.initial_center_of_mass_position is None: 00081 self.initial_center_of_mass_position = geometry_msgs.msg.Point() 00082 if self.final_left_foot_position is None: 00083 self.final_left_foot_position = geometry_msgs.msg.Pose() 00084 if self.final_right_foot_position is None: 00085 self.final_right_foot_position = geometry_msgs.msg.Pose() 00086 if self.final_center_of_mass_position is None: 00087 self.final_center_of_mass_position = geometry_msgs.msg.Point() 00088 if self.start_with_left_foot is None: 00089 self.start_with_left_foot = False 00090 if self.footprints is None: 00091 self.footprints = [] 00092 else: 00093 self.initial_left_foot_position = geometry_msgs.msg.Pose() 00094 self.initial_right_foot_position = geometry_msgs.msg.Pose() 00095 self.initial_center_of_mass_position = geometry_msgs.msg.Point() 00096 self.final_left_foot_position = geometry_msgs.msg.Pose() 00097 self.final_right_foot_position = geometry_msgs.msg.Pose() 00098 self.final_center_of_mass_position = geometry_msgs.msg.Point() 00099 self.start_with_left_foot = False 00100 self.footprints = [] 00101 00102 def _get_types(self): 00103 """ 00104 internal API method 00105 """ 00106 return self._slot_types 00107 00108 def serialize(self, buff): 00109 """ 00110 serialize message into buffer 00111 @param buff: buffer 00112 @type buff: StringIO 00113 """ 00114 try: 00115 _x = self 00116 buff.write(_struct_34dB.pack(_x.initial_left_foot_position.position.x, _x.initial_left_foot_position.position.y, _x.initial_left_foot_position.position.z, _x.initial_left_foot_position.orientation.x, _x.initial_left_foot_position.orientation.y, _x.initial_left_foot_position.orientation.z, _x.initial_left_foot_position.orientation.w, _x.initial_right_foot_position.position.x, _x.initial_right_foot_position.position.y, _x.initial_right_foot_position.position.z, _x.initial_right_foot_position.orientation.x, _x.initial_right_foot_position.orientation.y, _x.initial_right_foot_position.orientation.z, _x.initial_right_foot_position.orientation.w, _x.initial_center_of_mass_position.x, _x.initial_center_of_mass_position.y, _x.initial_center_of_mass_position.z, _x.final_left_foot_position.position.x, _x.final_left_foot_position.position.y, _x.final_left_foot_position.position.z, _x.final_left_foot_position.orientation.x, _x.final_left_foot_position.orientation.y, _x.final_left_foot_position.orientation.z, _x.final_left_foot_position.orientation.w, _x.final_right_foot_position.position.x, _x.final_right_foot_position.position.y, _x.final_right_foot_position.position.z, _x.final_right_foot_position.orientation.x, _x.final_right_foot_position.orientation.y, _x.final_right_foot_position.orientation.z, _x.final_right_foot_position.orientation.w, _x.final_center_of_mass_position.x, _x.final_center_of_mass_position.y, _x.final_center_of_mass_position.z, _x.start_with_left_foot)) 00117 length = len(self.footprints) 00118 buff.write(_struct_I.pack(length)) 00119 for val1 in self.footprints: 00120 _v1 = val1.beginTime 00121 _x = _v1 00122 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00123 _v2 = val1.duration 00124 _x = _v2 00125 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00126 _x = val1 00127 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta)) 00128 except struct.error as se: self._check_types(se) 00129 except TypeError as te: self._check_types(te) 00130 00131 def deserialize(self, str): 00132 """ 00133 unpack serialized message in str into this message instance 00134 @param str: byte array of serialized message 00135 @type str: str 00136 """ 00137 try: 00138 if self.initial_left_foot_position is None: 00139 self.initial_left_foot_position = geometry_msgs.msg.Pose() 00140 if self.initial_right_foot_position is None: 00141 self.initial_right_foot_position = geometry_msgs.msg.Pose() 00142 if self.initial_center_of_mass_position is None: 00143 self.initial_center_of_mass_position = geometry_msgs.msg.Point() 00144 if self.final_left_foot_position is None: 00145 self.final_left_foot_position = geometry_msgs.msg.Pose() 00146 if self.final_right_foot_position is None: 00147 self.final_right_foot_position = geometry_msgs.msg.Pose() 00148 if self.final_center_of_mass_position is None: 00149 self.final_center_of_mass_position = geometry_msgs.msg.Point() 00150 end = 0 00151 _x = self 00152 start = end 00153 end += 273 00154 (_x.initial_left_foot_position.position.x, _x.initial_left_foot_position.position.y, _x.initial_left_foot_position.position.z, _x.initial_left_foot_position.orientation.x, _x.initial_left_foot_position.orientation.y, _x.initial_left_foot_position.orientation.z, _x.initial_left_foot_position.orientation.w, _x.initial_right_foot_position.position.x, _x.initial_right_foot_position.position.y, _x.initial_right_foot_position.position.z, _x.initial_right_foot_position.orientation.x, _x.initial_right_foot_position.orientation.y, _x.initial_right_foot_position.orientation.z, _x.initial_right_foot_position.orientation.w, _x.initial_center_of_mass_position.x, _x.initial_center_of_mass_position.y, _x.initial_center_of_mass_position.z, _x.final_left_foot_position.position.x, _x.final_left_foot_position.position.y, _x.final_left_foot_position.position.z, _x.final_left_foot_position.orientation.x, _x.final_left_foot_position.orientation.y, _x.final_left_foot_position.orientation.z, _x.final_left_foot_position.orientation.w, _x.final_right_foot_position.position.x, _x.final_right_foot_position.position.y, _x.final_right_foot_position.position.z, _x.final_right_foot_position.orientation.x, _x.final_right_foot_position.orientation.y, _x.final_right_foot_position.orientation.z, _x.final_right_foot_position.orientation.w, _x.final_center_of_mass_position.x, _x.final_center_of_mass_position.y, _x.final_center_of_mass_position.z, _x.start_with_left_foot,) = _struct_34dB.unpack(str[start:end]) 00155 self.start_with_left_foot = bool(self.start_with_left_foot) 00156 start = end 00157 end += 4 00158 (length,) = _struct_I.unpack(str[start:end]) 00159 self.footprints = [] 00160 for i in range(0, length): 00161 val1 = walk_msgs.msg.Footprint2d() 00162 _v3 = val1.beginTime 00163 _x = _v3 00164 start = end 00165 end += 8 00166 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00167 _v4 = val1.duration 00168 _x = _v4 00169 start = end 00170 end += 8 00171 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00172 _x = val1 00173 start = end 00174 end += 24 00175 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end]) 00176 self.footprints.append(val1) 00177 return self 00178 except struct.error as e: 00179 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00180 00181 00182 def serialize_numpy(self, buff, numpy): 00183 """ 00184 serialize message with numpy array types into buffer 00185 @param buff: buffer 00186 @type buff: StringIO 00187 @param numpy: numpy python module 00188 @type numpy module 00189 """ 00190 try: 00191 _x = self 00192 buff.write(_struct_34dB.pack(_x.initial_left_foot_position.position.x, _x.initial_left_foot_position.position.y, _x.initial_left_foot_position.position.z, _x.initial_left_foot_position.orientation.x, _x.initial_left_foot_position.orientation.y, _x.initial_left_foot_position.orientation.z, _x.initial_left_foot_position.orientation.w, _x.initial_right_foot_position.position.x, _x.initial_right_foot_position.position.y, _x.initial_right_foot_position.position.z, _x.initial_right_foot_position.orientation.x, _x.initial_right_foot_position.orientation.y, _x.initial_right_foot_position.orientation.z, _x.initial_right_foot_position.orientation.w, _x.initial_center_of_mass_position.x, _x.initial_center_of_mass_position.y, _x.initial_center_of_mass_position.z, _x.final_left_foot_position.position.x, _x.final_left_foot_position.position.y, _x.final_left_foot_position.position.z, _x.final_left_foot_position.orientation.x, _x.final_left_foot_position.orientation.y, _x.final_left_foot_position.orientation.z, _x.final_left_foot_position.orientation.w, _x.final_right_foot_position.position.x, _x.final_right_foot_position.position.y, _x.final_right_foot_position.position.z, _x.final_right_foot_position.orientation.x, _x.final_right_foot_position.orientation.y, _x.final_right_foot_position.orientation.z, _x.final_right_foot_position.orientation.w, _x.final_center_of_mass_position.x, _x.final_center_of_mass_position.y, _x.final_center_of_mass_position.z, _x.start_with_left_foot)) 00193 length = len(self.footprints) 00194 buff.write(_struct_I.pack(length)) 00195 for val1 in self.footprints: 00196 _v5 = val1.beginTime 00197 _x = _v5 00198 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00199 _v6 = val1.duration 00200 _x = _v6 00201 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00202 _x = val1 00203 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta)) 00204 except struct.error as se: self._check_types(se) 00205 except TypeError as te: self._check_types(te) 00206 00207 def deserialize_numpy(self, str, numpy): 00208 """ 00209 unpack serialized message in str into this message instance using numpy for array types 00210 @param str: byte array of serialized message 00211 @type str: str 00212 @param numpy: numpy python module 00213 @type numpy: module 00214 """ 00215 try: 00216 if self.initial_left_foot_position is None: 00217 self.initial_left_foot_position = geometry_msgs.msg.Pose() 00218 if self.initial_right_foot_position is None: 00219 self.initial_right_foot_position = geometry_msgs.msg.Pose() 00220 if self.initial_center_of_mass_position is None: 00221 self.initial_center_of_mass_position = geometry_msgs.msg.Point() 00222 if self.final_left_foot_position is None: 00223 self.final_left_foot_position = geometry_msgs.msg.Pose() 00224 if self.final_right_foot_position is None: 00225 self.final_right_foot_position = geometry_msgs.msg.Pose() 00226 if self.final_center_of_mass_position is None: 00227 self.final_center_of_mass_position = geometry_msgs.msg.Point() 00228 end = 0 00229 _x = self 00230 start = end 00231 end += 273 00232 (_x.initial_left_foot_position.position.x, _x.initial_left_foot_position.position.y, _x.initial_left_foot_position.position.z, _x.initial_left_foot_position.orientation.x, _x.initial_left_foot_position.orientation.y, _x.initial_left_foot_position.orientation.z, _x.initial_left_foot_position.orientation.w, _x.initial_right_foot_position.position.x, _x.initial_right_foot_position.position.y, _x.initial_right_foot_position.position.z, _x.initial_right_foot_position.orientation.x, _x.initial_right_foot_position.orientation.y, _x.initial_right_foot_position.orientation.z, _x.initial_right_foot_position.orientation.w, _x.initial_center_of_mass_position.x, _x.initial_center_of_mass_position.y, _x.initial_center_of_mass_position.z, _x.final_left_foot_position.position.x, _x.final_left_foot_position.position.y, _x.final_left_foot_position.position.z, _x.final_left_foot_position.orientation.x, _x.final_left_foot_position.orientation.y, _x.final_left_foot_position.orientation.z, _x.final_left_foot_position.orientation.w, _x.final_right_foot_position.position.x, _x.final_right_foot_position.position.y, _x.final_right_foot_position.position.z, _x.final_right_foot_position.orientation.x, _x.final_right_foot_position.orientation.y, _x.final_right_foot_position.orientation.z, _x.final_right_foot_position.orientation.w, _x.final_center_of_mass_position.x, _x.final_center_of_mass_position.y, _x.final_center_of_mass_position.z, _x.start_with_left_foot,) = _struct_34dB.unpack(str[start:end]) 00233 self.start_with_left_foot = bool(self.start_with_left_foot) 00234 start = end 00235 end += 4 00236 (length,) = _struct_I.unpack(str[start:end]) 00237 self.footprints = [] 00238 for i in range(0, length): 00239 val1 = walk_msgs.msg.Footprint2d() 00240 _v7 = val1.beginTime 00241 _x = _v7 00242 start = end 00243 end += 8 00244 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00245 _v8 = val1.duration 00246 _x = _v8 00247 start = end 00248 end += 8 00249 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00250 _x = val1 00251 start = end 00252 end += 24 00253 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end]) 00254 self.footprints.append(val1) 00255 return self 00256 except struct.error as e: 00257 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00258 00259 _struct_I = roslib.message.struct_I 00260 _struct_2i = struct.Struct("<2i") 00261 _struct_3d = struct.Struct("<3d") 00262 _struct_2I = struct.Struct("<2I") 00263 _struct_34dB = struct.Struct("<34dB") 00264 """autogenerated by genmsg_py from GetPathResponse.msg. Do not edit.""" 00265 import roslib.message 00266 import struct 00267 00268 import geometry_msgs.msg 00269 import walk_msgs.msg 00270 import nav_msgs.msg 00271 import std_msgs.msg 00272 00273 class GetPathResponse(roslib.message.Message): 00274 _md5sum = "76d3891998acfa84511d5b8b9e0f9b97" 00275 _type = "walk_msgs/GetPathResponse" 00276 _has_header = False #flag to mark the presence of a Header object 00277 _full_text = """walk_msgs/WalkPath path 00278 00279 00280 ================================================================================ 00281 MSG: walk_msgs/WalkPath 00282 nav_msgs/Path left_foot 00283 nav_msgs/Path right_foot 00284 walk_msgs/PathPoint3d center_of_mass 00285 walk_msgs/PathPoint2d zmp 00286 00287 ================================================================================ 00288 MSG: nav_msgs/Path 00289 #An array of poses that represents a Path for a robot to follow 00290 Header header 00291 geometry_msgs/PoseStamped[] poses 00292 00293 ================================================================================ 00294 MSG: std_msgs/Header 00295 # Standard metadata for higher-level stamped data types. 00296 # This is generally used to communicate timestamped data 00297 # in a particular coordinate frame. 00298 # 00299 # sequence ID: consecutively increasing ID 00300 uint32 seq 00301 #Two-integer timestamp that is expressed as: 00302 # * stamp.secs: seconds (stamp_secs) since epoch 00303 # * stamp.nsecs: nanoseconds since stamp_secs 00304 # time-handling sugar is provided by the client library 00305 time stamp 00306 #Frame this data is associated with 00307 # 0: no frame 00308 # 1: global frame 00309 string frame_id 00310 00311 ================================================================================ 00312 MSG: geometry_msgs/PoseStamped 00313 # A Pose with reference coordinate frame and timestamp 00314 Header header 00315 Pose pose 00316 00317 ================================================================================ 00318 MSG: geometry_msgs/Pose 00319 # A representation of pose in free space, composed of postion and orientation. 00320 Point position 00321 Quaternion orientation 00322 00323 ================================================================================ 00324 MSG: geometry_msgs/Point 00325 # This contains the position of a point in free space 00326 float64 x 00327 float64 y 00328 float64 z 00329 00330 ================================================================================ 00331 MSG: geometry_msgs/Quaternion 00332 # This represents an orientation in free space in quaternion form. 00333 00334 float64 x 00335 float64 y 00336 float64 z 00337 float64 w 00338 00339 ================================================================================ 00340 MSG: walk_msgs/PathPoint3d 00341 Header header 00342 geometry_msgs/PointStamped[] points 00343 00344 ================================================================================ 00345 MSG: geometry_msgs/PointStamped 00346 # This represents a Point with reference coordinate frame and timestamp 00347 Header header 00348 Point point 00349 00350 ================================================================================ 00351 MSG: walk_msgs/PathPoint2d 00352 Header header 00353 walk_msgs/Point2dStamped[] points 00354 00355 ================================================================================ 00356 MSG: walk_msgs/Point2dStamped 00357 Header header 00358 Point2d point 00359 00360 ================================================================================ 00361 MSG: walk_msgs/Point2d 00362 float64 x 00363 float64 y 00364 00365 """ 00366 __slots__ = ['path'] 00367 _slot_types = ['walk_msgs/WalkPath'] 00368 00369 def __init__(self, *args, **kwds): 00370 """ 00371 Constructor. Any message fields that are implicitly/explicitly 00372 set to None will be assigned a default value. The recommend 00373 use is keyword arguments as this is more robust to future message 00374 changes. You cannot mix in-order arguments and keyword arguments. 00375 00376 The available fields are: 00377 path 00378 00379 @param args: complete set of field values, in .msg order 00380 @param kwds: use keyword arguments corresponding to message field names 00381 to set specific fields. 00382 """ 00383 if args or kwds: 00384 super(GetPathResponse, self).__init__(*args, **kwds) 00385 #message fields cannot be None, assign default values for those that are 00386 if self.path is None: 00387 self.path = walk_msgs.msg.WalkPath() 00388 else: 00389 self.path = walk_msgs.msg.WalkPath() 00390 00391 def _get_types(self): 00392 """ 00393 internal API method 00394 """ 00395 return self._slot_types 00396 00397 def serialize(self, buff): 00398 """ 00399 serialize message into buffer 00400 @param buff: buffer 00401 @type buff: StringIO 00402 """ 00403 try: 00404 _x = self 00405 buff.write(_struct_3I.pack(_x.path.left_foot.header.seq, _x.path.left_foot.header.stamp.secs, _x.path.left_foot.header.stamp.nsecs)) 00406 _x = self.path.left_foot.header.frame_id 00407 length = len(_x) 00408 buff.write(struct.pack('<I%ss'%length, length, _x)) 00409 length = len(self.path.left_foot.poses) 00410 buff.write(_struct_I.pack(length)) 00411 for val1 in self.path.left_foot.poses: 00412 _v9 = val1.header 00413 buff.write(_struct_I.pack(_v9.seq)) 00414 _v10 = _v9.stamp 00415 _x = _v10 00416 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00417 _x = _v9.frame_id 00418 length = len(_x) 00419 buff.write(struct.pack('<I%ss'%length, length, _x)) 00420 _v11 = val1.pose 00421 _v12 = _v11.position 00422 _x = _v12 00423 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00424 _v13 = _v11.orientation 00425 _x = _v13 00426 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00427 _x = self 00428 buff.write(_struct_3I.pack(_x.path.right_foot.header.seq, _x.path.right_foot.header.stamp.secs, _x.path.right_foot.header.stamp.nsecs)) 00429 _x = self.path.right_foot.header.frame_id 00430 length = len(_x) 00431 buff.write(struct.pack('<I%ss'%length, length, _x)) 00432 length = len(self.path.right_foot.poses) 00433 buff.write(_struct_I.pack(length)) 00434 for val1 in self.path.right_foot.poses: 00435 _v14 = val1.header 00436 buff.write(_struct_I.pack(_v14.seq)) 00437 _v15 = _v14.stamp 00438 _x = _v15 00439 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00440 _x = _v14.frame_id 00441 length = len(_x) 00442 buff.write(struct.pack('<I%ss'%length, length, _x)) 00443 _v16 = val1.pose 00444 _v17 = _v16.position 00445 _x = _v17 00446 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00447 _v18 = _v16.orientation 00448 _x = _v18 00449 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00450 _x = self 00451 buff.write(_struct_3I.pack(_x.path.center_of_mass.header.seq, _x.path.center_of_mass.header.stamp.secs, _x.path.center_of_mass.header.stamp.nsecs)) 00452 _x = self.path.center_of_mass.header.frame_id 00453 length = len(_x) 00454 buff.write(struct.pack('<I%ss'%length, length, _x)) 00455 length = len(self.path.center_of_mass.points) 00456 buff.write(_struct_I.pack(length)) 00457 for val1 in self.path.center_of_mass.points: 00458 _v19 = val1.header 00459 buff.write(_struct_I.pack(_v19.seq)) 00460 _v20 = _v19.stamp 00461 _x = _v20 00462 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00463 _x = _v19.frame_id 00464 length = len(_x) 00465 buff.write(struct.pack('<I%ss'%length, length, _x)) 00466 _v21 = val1.point 00467 _x = _v21 00468 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00469 _x = self 00470 buff.write(_struct_3I.pack(_x.path.zmp.header.seq, _x.path.zmp.header.stamp.secs, _x.path.zmp.header.stamp.nsecs)) 00471 _x = self.path.zmp.header.frame_id 00472 length = len(_x) 00473 buff.write(struct.pack('<I%ss'%length, length, _x)) 00474 length = len(self.path.zmp.points) 00475 buff.write(_struct_I.pack(length)) 00476 for val1 in self.path.zmp.points: 00477 _v22 = val1.header 00478 buff.write(_struct_I.pack(_v22.seq)) 00479 _v23 = _v22.stamp 00480 _x = _v23 00481 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00482 _x = _v22.frame_id 00483 length = len(_x) 00484 buff.write(struct.pack('<I%ss'%length, length, _x)) 00485 _v24 = val1.point 00486 _x = _v24 00487 buff.write(_struct_2d.pack(_x.x, _x.y)) 00488 except struct.error as se: self._check_types(se) 00489 except TypeError as te: self._check_types(te) 00490 00491 def deserialize(self, str): 00492 """ 00493 unpack serialized message in str into this message instance 00494 @param str: byte array of serialized message 00495 @type str: str 00496 """ 00497 try: 00498 if self.path is None: 00499 self.path = walk_msgs.msg.WalkPath() 00500 end = 0 00501 _x = self 00502 start = end 00503 end += 12 00504 (_x.path.left_foot.header.seq, _x.path.left_foot.header.stamp.secs, _x.path.left_foot.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00505 start = end 00506 end += 4 00507 (length,) = _struct_I.unpack(str[start:end]) 00508 start = end 00509 end += length 00510 self.path.left_foot.header.frame_id = str[start:end] 00511 start = end 00512 end += 4 00513 (length,) = _struct_I.unpack(str[start:end]) 00514 self.path.left_foot.poses = [] 00515 for i in range(0, length): 00516 val1 = geometry_msgs.msg.PoseStamped() 00517 _v25 = val1.header 00518 start = end 00519 end += 4 00520 (_v25.seq,) = _struct_I.unpack(str[start:end]) 00521 _v26 = _v25.stamp 00522 _x = _v26 00523 start = end 00524 end += 8 00525 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00526 start = end 00527 end += 4 00528 (length,) = _struct_I.unpack(str[start:end]) 00529 start = end 00530 end += length 00531 _v25.frame_id = str[start:end] 00532 _v27 = val1.pose 00533 _v28 = _v27.position 00534 _x = _v28 00535 start = end 00536 end += 24 00537 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00538 _v29 = _v27.orientation 00539 _x = _v29 00540 start = end 00541 end += 32 00542 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00543 self.path.left_foot.poses.append(val1) 00544 _x = self 00545 start = end 00546 end += 12 00547 (_x.path.right_foot.header.seq, _x.path.right_foot.header.stamp.secs, _x.path.right_foot.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00548 start = end 00549 end += 4 00550 (length,) = _struct_I.unpack(str[start:end]) 00551 start = end 00552 end += length 00553 self.path.right_foot.header.frame_id = str[start:end] 00554 start = end 00555 end += 4 00556 (length,) = _struct_I.unpack(str[start:end]) 00557 self.path.right_foot.poses = [] 00558 for i in range(0, length): 00559 val1 = geometry_msgs.msg.PoseStamped() 00560 _v30 = val1.header 00561 start = end 00562 end += 4 00563 (_v30.seq,) = _struct_I.unpack(str[start:end]) 00564 _v31 = _v30.stamp 00565 _x = _v31 00566 start = end 00567 end += 8 00568 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00569 start = end 00570 end += 4 00571 (length,) = _struct_I.unpack(str[start:end]) 00572 start = end 00573 end += length 00574 _v30.frame_id = str[start:end] 00575 _v32 = val1.pose 00576 _v33 = _v32.position 00577 _x = _v33 00578 start = end 00579 end += 24 00580 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00581 _v34 = _v32.orientation 00582 _x = _v34 00583 start = end 00584 end += 32 00585 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00586 self.path.right_foot.poses.append(val1) 00587 _x = self 00588 start = end 00589 end += 12 00590 (_x.path.center_of_mass.header.seq, _x.path.center_of_mass.header.stamp.secs, _x.path.center_of_mass.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00591 start = end 00592 end += 4 00593 (length,) = _struct_I.unpack(str[start:end]) 00594 start = end 00595 end += length 00596 self.path.center_of_mass.header.frame_id = str[start:end] 00597 start = end 00598 end += 4 00599 (length,) = _struct_I.unpack(str[start:end]) 00600 self.path.center_of_mass.points = [] 00601 for i in range(0, length): 00602 val1 = geometry_msgs.msg.PointStamped() 00603 _v35 = val1.header 00604 start = end 00605 end += 4 00606 (_v35.seq,) = _struct_I.unpack(str[start:end]) 00607 _v36 = _v35.stamp 00608 _x = _v36 00609 start = end 00610 end += 8 00611 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00612 start = end 00613 end += 4 00614 (length,) = _struct_I.unpack(str[start:end]) 00615 start = end 00616 end += length 00617 _v35.frame_id = str[start:end] 00618 _v37 = val1.point 00619 _x = _v37 00620 start = end 00621 end += 24 00622 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00623 self.path.center_of_mass.points.append(val1) 00624 _x = self 00625 start = end 00626 end += 12 00627 (_x.path.zmp.header.seq, _x.path.zmp.header.stamp.secs, _x.path.zmp.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00628 start = end 00629 end += 4 00630 (length,) = _struct_I.unpack(str[start:end]) 00631 start = end 00632 end += length 00633 self.path.zmp.header.frame_id = str[start:end] 00634 start = end 00635 end += 4 00636 (length,) = _struct_I.unpack(str[start:end]) 00637 self.path.zmp.points = [] 00638 for i in range(0, length): 00639 val1 = walk_msgs.msg.Point2dStamped() 00640 _v38 = val1.header 00641 start = end 00642 end += 4 00643 (_v38.seq,) = _struct_I.unpack(str[start:end]) 00644 _v39 = _v38.stamp 00645 _x = _v39 00646 start = end 00647 end += 8 00648 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00649 start = end 00650 end += 4 00651 (length,) = _struct_I.unpack(str[start:end]) 00652 start = end 00653 end += length 00654 _v38.frame_id = str[start:end] 00655 _v40 = val1.point 00656 _x = _v40 00657 start = end 00658 end += 16 00659 (_x.x, _x.y,) = _struct_2d.unpack(str[start:end]) 00660 self.path.zmp.points.append(val1) 00661 return self 00662 except struct.error as e: 00663 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00664 00665 00666 def serialize_numpy(self, buff, numpy): 00667 """ 00668 serialize message with numpy array types into buffer 00669 @param buff: buffer 00670 @type buff: StringIO 00671 @param numpy: numpy python module 00672 @type numpy module 00673 """ 00674 try: 00675 _x = self 00676 buff.write(_struct_3I.pack(_x.path.left_foot.header.seq, _x.path.left_foot.header.stamp.secs, _x.path.left_foot.header.stamp.nsecs)) 00677 _x = self.path.left_foot.header.frame_id 00678 length = len(_x) 00679 buff.write(struct.pack('<I%ss'%length, length, _x)) 00680 length = len(self.path.left_foot.poses) 00681 buff.write(_struct_I.pack(length)) 00682 for val1 in self.path.left_foot.poses: 00683 _v41 = val1.header 00684 buff.write(_struct_I.pack(_v41.seq)) 00685 _v42 = _v41.stamp 00686 _x = _v42 00687 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00688 _x = _v41.frame_id 00689 length = len(_x) 00690 buff.write(struct.pack('<I%ss'%length, length, _x)) 00691 _v43 = val1.pose 00692 _v44 = _v43.position 00693 _x = _v44 00694 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00695 _v45 = _v43.orientation 00696 _x = _v45 00697 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00698 _x = self 00699 buff.write(_struct_3I.pack(_x.path.right_foot.header.seq, _x.path.right_foot.header.stamp.secs, _x.path.right_foot.header.stamp.nsecs)) 00700 _x = self.path.right_foot.header.frame_id 00701 length = len(_x) 00702 buff.write(struct.pack('<I%ss'%length, length, _x)) 00703 length = len(self.path.right_foot.poses) 00704 buff.write(_struct_I.pack(length)) 00705 for val1 in self.path.right_foot.poses: 00706 _v46 = val1.header 00707 buff.write(_struct_I.pack(_v46.seq)) 00708 _v47 = _v46.stamp 00709 _x = _v47 00710 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00711 _x = _v46.frame_id 00712 length = len(_x) 00713 buff.write(struct.pack('<I%ss'%length, length, _x)) 00714 _v48 = val1.pose 00715 _v49 = _v48.position 00716 _x = _v49 00717 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00718 _v50 = _v48.orientation 00719 _x = _v50 00720 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00721 _x = self 00722 buff.write(_struct_3I.pack(_x.path.center_of_mass.header.seq, _x.path.center_of_mass.header.stamp.secs, _x.path.center_of_mass.header.stamp.nsecs)) 00723 _x = self.path.center_of_mass.header.frame_id 00724 length = len(_x) 00725 buff.write(struct.pack('<I%ss'%length, length, _x)) 00726 length = len(self.path.center_of_mass.points) 00727 buff.write(_struct_I.pack(length)) 00728 for val1 in self.path.center_of_mass.points: 00729 _v51 = val1.header 00730 buff.write(_struct_I.pack(_v51.seq)) 00731 _v52 = _v51.stamp 00732 _x = _v52 00733 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00734 _x = _v51.frame_id 00735 length = len(_x) 00736 buff.write(struct.pack('<I%ss'%length, length, _x)) 00737 _v53 = val1.point 00738 _x = _v53 00739 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00740 _x = self 00741 buff.write(_struct_3I.pack(_x.path.zmp.header.seq, _x.path.zmp.header.stamp.secs, _x.path.zmp.header.stamp.nsecs)) 00742 _x = self.path.zmp.header.frame_id 00743 length = len(_x) 00744 buff.write(struct.pack('<I%ss'%length, length, _x)) 00745 length = len(self.path.zmp.points) 00746 buff.write(_struct_I.pack(length)) 00747 for val1 in self.path.zmp.points: 00748 _v54 = val1.header 00749 buff.write(_struct_I.pack(_v54.seq)) 00750 _v55 = _v54.stamp 00751 _x = _v55 00752 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00753 _x = _v54.frame_id 00754 length = len(_x) 00755 buff.write(struct.pack('<I%ss'%length, length, _x)) 00756 _v56 = val1.point 00757 _x = _v56 00758 buff.write(_struct_2d.pack(_x.x, _x.y)) 00759 except struct.error as se: self._check_types(se) 00760 except TypeError as te: self._check_types(te) 00761 00762 def deserialize_numpy(self, str, numpy): 00763 """ 00764 unpack serialized message in str into this message instance using numpy for array types 00765 @param str: byte array of serialized message 00766 @type str: str 00767 @param numpy: numpy python module 00768 @type numpy: module 00769 """ 00770 try: 00771 if self.path is None: 00772 self.path = walk_msgs.msg.WalkPath() 00773 end = 0 00774 _x = self 00775 start = end 00776 end += 12 00777 (_x.path.left_foot.header.seq, _x.path.left_foot.header.stamp.secs, _x.path.left_foot.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00778 start = end 00779 end += 4 00780 (length,) = _struct_I.unpack(str[start:end]) 00781 start = end 00782 end += length 00783 self.path.left_foot.header.frame_id = str[start:end] 00784 start = end 00785 end += 4 00786 (length,) = _struct_I.unpack(str[start:end]) 00787 self.path.left_foot.poses = [] 00788 for i in range(0, length): 00789 val1 = geometry_msgs.msg.PoseStamped() 00790 _v57 = val1.header 00791 start = end 00792 end += 4 00793 (_v57.seq,) = _struct_I.unpack(str[start:end]) 00794 _v58 = _v57.stamp 00795 _x = _v58 00796 start = end 00797 end += 8 00798 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00799 start = end 00800 end += 4 00801 (length,) = _struct_I.unpack(str[start:end]) 00802 start = end 00803 end += length 00804 _v57.frame_id = str[start:end] 00805 _v59 = val1.pose 00806 _v60 = _v59.position 00807 _x = _v60 00808 start = end 00809 end += 24 00810 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00811 _v61 = _v59.orientation 00812 _x = _v61 00813 start = end 00814 end += 32 00815 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00816 self.path.left_foot.poses.append(val1) 00817 _x = self 00818 start = end 00819 end += 12 00820 (_x.path.right_foot.header.seq, _x.path.right_foot.header.stamp.secs, _x.path.right_foot.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00821 start = end 00822 end += 4 00823 (length,) = _struct_I.unpack(str[start:end]) 00824 start = end 00825 end += length 00826 self.path.right_foot.header.frame_id = str[start:end] 00827 start = end 00828 end += 4 00829 (length,) = _struct_I.unpack(str[start:end]) 00830 self.path.right_foot.poses = [] 00831 for i in range(0, length): 00832 val1 = geometry_msgs.msg.PoseStamped() 00833 _v62 = val1.header 00834 start = end 00835 end += 4 00836 (_v62.seq,) = _struct_I.unpack(str[start:end]) 00837 _v63 = _v62.stamp 00838 _x = _v63 00839 start = end 00840 end += 8 00841 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00842 start = end 00843 end += 4 00844 (length,) = _struct_I.unpack(str[start:end]) 00845 start = end 00846 end += length 00847 _v62.frame_id = str[start:end] 00848 _v64 = val1.pose 00849 _v65 = _v64.position 00850 _x = _v65 00851 start = end 00852 end += 24 00853 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00854 _v66 = _v64.orientation 00855 _x = _v66 00856 start = end 00857 end += 32 00858 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00859 self.path.right_foot.poses.append(val1) 00860 _x = self 00861 start = end 00862 end += 12 00863 (_x.path.center_of_mass.header.seq, _x.path.center_of_mass.header.stamp.secs, _x.path.center_of_mass.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00864 start = end 00865 end += 4 00866 (length,) = _struct_I.unpack(str[start:end]) 00867 start = end 00868 end += length 00869 self.path.center_of_mass.header.frame_id = str[start:end] 00870 start = end 00871 end += 4 00872 (length,) = _struct_I.unpack(str[start:end]) 00873 self.path.center_of_mass.points = [] 00874 for i in range(0, length): 00875 val1 = geometry_msgs.msg.PointStamped() 00876 _v67 = val1.header 00877 start = end 00878 end += 4 00879 (_v67.seq,) = _struct_I.unpack(str[start:end]) 00880 _v68 = _v67.stamp 00881 _x = _v68 00882 start = end 00883 end += 8 00884 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00885 start = end 00886 end += 4 00887 (length,) = _struct_I.unpack(str[start:end]) 00888 start = end 00889 end += length 00890 _v67.frame_id = str[start:end] 00891 _v69 = val1.point 00892 _x = _v69 00893 start = end 00894 end += 24 00895 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00896 self.path.center_of_mass.points.append(val1) 00897 _x = self 00898 start = end 00899 end += 12 00900 (_x.path.zmp.header.seq, _x.path.zmp.header.stamp.secs, _x.path.zmp.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00901 start = end 00902 end += 4 00903 (length,) = _struct_I.unpack(str[start:end]) 00904 start = end 00905 end += length 00906 self.path.zmp.header.frame_id = str[start:end] 00907 start = end 00908 end += 4 00909 (length,) = _struct_I.unpack(str[start:end]) 00910 self.path.zmp.points = [] 00911 for i in range(0, length): 00912 val1 = walk_msgs.msg.Point2dStamped() 00913 _v70 = val1.header 00914 start = end 00915 end += 4 00916 (_v70.seq,) = _struct_I.unpack(str[start:end]) 00917 _v71 = _v70.stamp 00918 _x = _v71 00919 start = end 00920 end += 8 00921 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00922 start = end 00923 end += 4 00924 (length,) = _struct_I.unpack(str[start:end]) 00925 start = end 00926 end += length 00927 _v70.frame_id = str[start:end] 00928 _v72 = val1.point 00929 _x = _v72 00930 start = end 00931 end += 16 00932 (_x.x, _x.y,) = _struct_2d.unpack(str[start:end]) 00933 self.path.zmp.points.append(val1) 00934 return self 00935 except struct.error as e: 00936 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00937 00938 _struct_I = roslib.message.struct_I 00939 _struct_2d = struct.Struct("<2d") 00940 _struct_3I = struct.Struct("<3I") 00941 _struct_4d = struct.Struct("<4d") 00942 _struct_2I = struct.Struct("<2I") 00943 _struct_3d = struct.Struct("<3d") 00944 class GetPath(roslib.message.ServiceDefinition): 00945 _type = 'walk_msgs/GetPath' 00946 _md5sum = '2b6fd7b841642a7520d3b2fd459370d2' 00947 _request_class = GetPathRequest 00948 _response_class = GetPathResponse