Go to the documentation of this file.00001 """autogenerated by genpy from humanoid_nav_msgs/ExecFootstepsResult.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 import humanoid_nav_msgs.msg
00009
00010 class ExecFootstepsResult(genpy.Message):
00011 _md5sum = "5dfde2cb244d6c76567d3c52c40a988c"
00012 _type = "humanoid_nav_msgs/ExecFootstepsResult"
00013 _has_header = False
00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00015 # Define the result
00016 humanoid_nav_msgs/StepTarget[] executed_footsteps
00017
00018 ================================================================================
00019 MSG: humanoid_nav_msgs/StepTarget
00020 # Target for a single stepping motion of a humanoid's leg
00021
00022 geometry_msgs/Pose2D pose # step pose as relative offset to last leg
00023 uint8 leg # which leg to use (left/right, see below)
00024
00025 uint8 right=0 # right leg constant
00026 uint8 left=1 # left leg constant
00027
00028 ================================================================================
00029 MSG: geometry_msgs/Pose2D
00030 # This expresses a position and orientation on a 2D manifold.
00031
00032 float64 x
00033 float64 y
00034 float64 theta
00035 """
00036 __slots__ = ['executed_footsteps']
00037 _slot_types = ['humanoid_nav_msgs/StepTarget[]']
00038
00039 def __init__(self, *args, **kwds):
00040 """
00041 Constructor. Any message fields that are implicitly/explicitly
00042 set to None will be assigned a default value. The recommend
00043 use is keyword arguments as this is more robust to future message
00044 changes. You cannot mix in-order arguments and keyword arguments.
00045
00046 The available fields are:
00047 executed_footsteps
00048
00049 :param args: complete set of field values, in .msg order
00050 :param kwds: use keyword arguments corresponding to message field names
00051 to set specific fields.
00052 """
00053 if args or kwds:
00054 super(ExecFootstepsResult, self).__init__(*args, **kwds)
00055
00056 if self.executed_footsteps is None:
00057 self.executed_footsteps = []
00058 else:
00059 self.executed_footsteps = []
00060
00061 def _get_types(self):
00062 """
00063 internal API method
00064 """
00065 return self._slot_types
00066
00067 def serialize(self, buff):
00068 """
00069 serialize message into buffer
00070 :param buff: buffer, ``StringIO``
00071 """
00072 try:
00073 length = len(self.executed_footsteps)
00074 buff.write(_struct_I.pack(length))
00075 for val1 in self.executed_footsteps:
00076 _v1 = val1.pose
00077 _x = _v1
00078 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00079 buff.write(_struct_B.pack(val1.leg))
00080 except struct.error as se: self._check_types(se)
00081 except TypeError as te: self._check_types(te)
00082
00083 def deserialize(self, str):
00084 """
00085 unpack serialized message in str into this message instance
00086 :param str: byte array of serialized message, ``str``
00087 """
00088 try:
00089 if self.executed_footsteps is None:
00090 self.executed_footsteps = None
00091 end = 0
00092 start = end
00093 end += 4
00094 (length,) = _struct_I.unpack(str[start:end])
00095 self.executed_footsteps = []
00096 for i in range(0, length):
00097 val1 = humanoid_nav_msgs.msg.StepTarget()
00098 _v2 = val1.pose
00099 _x = _v2
00100 start = end
00101 end += 24
00102 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00103 start = end
00104 end += 1
00105 (val1.leg,) = _struct_B.unpack(str[start:end])
00106 self.executed_footsteps.append(val1)
00107 return self
00108 except struct.error as e:
00109 raise genpy.DeserializationError(e)
00110
00111
00112 def serialize_numpy(self, buff, numpy):
00113 """
00114 serialize message with numpy array types into buffer
00115 :param buff: buffer, ``StringIO``
00116 :param numpy: numpy python module
00117 """
00118 try:
00119 length = len(self.executed_footsteps)
00120 buff.write(_struct_I.pack(length))
00121 for val1 in self.executed_footsteps:
00122 _v3 = val1.pose
00123 _x = _v3
00124 buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00125 buff.write(_struct_B.pack(val1.leg))
00126 except struct.error as se: self._check_types(se)
00127 except TypeError as te: self._check_types(te)
00128
00129 def deserialize_numpy(self, str, numpy):
00130 """
00131 unpack serialized message in str into this message instance using numpy for array types
00132 :param str: byte array of serialized message, ``str``
00133 :param numpy: numpy python module
00134 """
00135 try:
00136 if self.executed_footsteps is None:
00137 self.executed_footsteps = None
00138 end = 0
00139 start = end
00140 end += 4
00141 (length,) = _struct_I.unpack(str[start:end])
00142 self.executed_footsteps = []
00143 for i in range(0, length):
00144 val1 = humanoid_nav_msgs.msg.StepTarget()
00145 _v4 = val1.pose
00146 _x = _v4
00147 start = end
00148 end += 24
00149 (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00150 start = end
00151 end += 1
00152 (val1.leg,) = _struct_B.unpack(str[start:end])
00153 self.executed_footsteps.append(val1)
00154 return self
00155 except struct.error as e:
00156 raise genpy.DeserializationError(e)
00157
00158 _struct_I = genpy.struct_I
00159 _struct_B = struct.Struct("<B")
00160 _struct_3d = struct.Struct("<3d")