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


walk_msgs
Author(s): Thomas Moulard
autogenerated on Sat Dec 28 2013 17:05:24