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


humanoid_nav_msgs
Author(s): Armin Hornung
autogenerated on Tue Oct 15 2013 10:05:54