Go to the documentation of this file.00001 """autogenerated by genpy from nao_msgs/CmdPoseServiceRequest.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 CmdPoseServiceRequest(genpy.Message):
00010 _md5sum = "271cb12677c4cd9bccbc642cd9258d1f"
00011 _type = "nao_msgs/CmdPoseServiceRequest"
00012 _has_header = False
00013 _full_text = """
00014 geometry_msgs/Pose2D pose
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__ = ['pose']
00025 _slot_types = ['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 pose
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(CmdPoseServiceRequest, self).__init__(*args, **kwds)
00043
00044 if self.pose is None:
00045 self.pose = geometry_msgs.msg.Pose2D()
00046 else:
00047 self.pose = geometry_msgs.msg.Pose2D()
00048
00049 def _get_types(self):
00050 """
00051 internal API method
00052 """
00053 return self._slot_types
00054
00055 def serialize(self, buff):
00056 """
00057 serialize message into buffer
00058 :param buff: buffer, ``StringIO``
00059 """
00060 try:
00061 _x = self
00062 buff.write(_struct_3d.pack(_x.pose.x, _x.pose.y, _x.pose.theta))
00063 except struct.error as se: self._check_types(se)
00064 except TypeError as te: self._check_types(te)
00065
00066 def deserialize(self, str):
00067 """
00068 unpack serialized message in str into this message instance
00069 :param str: byte array of serialized message, ``str``
00070 """
00071 try:
00072 if self.pose is None:
00073 self.pose = geometry_msgs.msg.Pose2D()
00074 end = 0
00075 _x = self
00076 start = end
00077 end += 24
00078 (_x.pose.x, _x.pose.y, _x.pose.theta,) = _struct_3d.unpack(str[start:end])
00079 return self
00080 except struct.error as e:
00081 raise genpy.DeserializationError(e)
00082
00083
00084 def serialize_numpy(self, buff, numpy):
00085 """
00086 serialize message with numpy array types into buffer
00087 :param buff: buffer, ``StringIO``
00088 :param numpy: numpy python module
00089 """
00090 try:
00091 _x = self
00092 buff.write(_struct_3d.pack(_x.pose.x, _x.pose.y, _x.pose.theta))
00093 except struct.error as se: self._check_types(se)
00094 except TypeError as te: self._check_types(te)
00095
00096 def deserialize_numpy(self, str, numpy):
00097 """
00098 unpack serialized message in str into this message instance using numpy for array types
00099 :param str: byte array of serialized message, ``str``
00100 :param numpy: numpy python module
00101 """
00102 try:
00103 if self.pose is None:
00104 self.pose = geometry_msgs.msg.Pose2D()
00105 end = 0
00106 _x = self
00107 start = end
00108 end += 24
00109 (_x.pose.x, _x.pose.y, _x.pose.theta,) = _struct_3d.unpack(str[start:end])
00110 return self
00111 except struct.error as e:
00112 raise genpy.DeserializationError(e)
00113
00114 _struct_I = genpy.struct_I
00115 _struct_3d = struct.Struct("<3d")
00116 """autogenerated by genpy from nao_msgs/CmdPoseServiceResponse.msg. Do not edit."""
00117 import sys
00118 python3 = True if sys.hexversion > 0x03000000 else False
00119 import genpy
00120 import struct
00121
00122
00123 class CmdPoseServiceResponse(genpy.Message):
00124 _md5sum = "d41d8cd98f00b204e9800998ecf8427e"
00125 _type = "nao_msgs/CmdPoseServiceResponse"
00126 _has_header = False
00127 _full_text = """
00128
00129 """
00130 __slots__ = []
00131 _slot_types = []
00132
00133 def __init__(self, *args, **kwds):
00134 """
00135 Constructor. Any message fields that are implicitly/explicitly
00136 set to None will be assigned a default value. The recommend
00137 use is keyword arguments as this is more robust to future message
00138 changes. You cannot mix in-order arguments and keyword arguments.
00139
00140 The available fields are:
00141
00142
00143 :param args: complete set of field values, in .msg order
00144 :param kwds: use keyword arguments corresponding to message field names
00145 to set specific fields.
00146 """
00147 if args or kwds:
00148 super(CmdPoseServiceResponse, self).__init__(*args, **kwds)
00149
00150 def _get_types(self):
00151 """
00152 internal API method
00153 """
00154 return self._slot_types
00155
00156 def serialize(self, buff):
00157 """
00158 serialize message into buffer
00159 :param buff: buffer, ``StringIO``
00160 """
00161 try:
00162 pass
00163 except struct.error as se: self._check_types(se)
00164 except TypeError as te: self._check_types(te)
00165
00166 def deserialize(self, str):
00167 """
00168 unpack serialized message in str into this message instance
00169 :param str: byte array of serialized message, ``str``
00170 """
00171 try:
00172 end = 0
00173 return self
00174 except struct.error as e:
00175 raise genpy.DeserializationError(e)
00176
00177
00178 def serialize_numpy(self, buff, numpy):
00179 """
00180 serialize message with numpy array types into buffer
00181 :param buff: buffer, ``StringIO``
00182 :param numpy: numpy python module
00183 """
00184 try:
00185 pass
00186 except struct.error as se: self._check_types(se)
00187 except TypeError as te: self._check_types(te)
00188
00189 def deserialize_numpy(self, str, numpy):
00190 """
00191 unpack serialized message in str into this message instance using numpy for array types
00192 :param str: byte array of serialized message, ``str``
00193 :param numpy: numpy python module
00194 """
00195 try:
00196 end = 0
00197 return self
00198 except struct.error as e:
00199 raise genpy.DeserializationError(e)
00200
00201 _struct_I = genpy.struct_I
00202 class CmdPoseService(object):
00203 _type = 'nao_msgs/CmdPoseService'
00204 _md5sum = '271cb12677c4cd9bccbc642cd9258d1f'
00205 _request_class = CmdPoseServiceRequest
00206 _response_class = CmdPoseServiceResponse