00001 """autogenerated by genpy from hector_uav_msgs/RC.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 std_msgs.msg
00008
00009 class RC(genpy.Message):
00010 _md5sum = "2691c2fe8c5ab2323146bdd8dd2e449e"
00011 _type = "hector_uav_msgs/RC"
00012 _has_header = True
00013 _full_text = """Header header
00014
00015 uint8 ROLL = 1
00016 uint8 PITCH = 2
00017 uint8 YAW = 3
00018 uint8 STEER = 4
00019 uint8 HEIGHT = 5
00020 uint8 THRUST = 6
00021 uint8 BRAKE = 7
00022
00023 uint8 status
00024 bool valid
00025
00026 float32[] axis
00027 uint8[] axis_function
00028
00029 int8[] swit
00030 uint8[] swit_function
00031
00032 ================================================================================
00033 MSG: std_msgs/Header
00034 # Standard metadata for higher-level stamped data types.
00035 # This is generally used to communicate timestamped data
00036 # in a particular coordinate frame.
00037 #
00038 # sequence ID: consecutively increasing ID
00039 uint32 seq
00040 #Two-integer timestamp that is expressed as:
00041 # * stamp.secs: seconds (stamp_secs) since epoch
00042 # * stamp.nsecs: nanoseconds since stamp_secs
00043 # time-handling sugar is provided by the client library
00044 time stamp
00045 #Frame this data is associated with
00046 # 0: no frame
00047 # 1: global frame
00048 string frame_id
00049
00050 """
00051
00052 ROLL = 1
00053 PITCH = 2
00054 YAW = 3
00055 STEER = 4
00056 HEIGHT = 5
00057 THRUST = 6
00058 BRAKE = 7
00059
00060 __slots__ = ['header','status','valid','axis','axis_function','swit','swit_function']
00061 _slot_types = ['std_msgs/Header','uint8','bool','float32[]','uint8[]','int8[]','uint8[]']
00062
00063 def __init__(self, *args, **kwds):
00064 """
00065 Constructor. Any message fields that are implicitly/explicitly
00066 set to None will be assigned a default value. The recommend
00067 use is keyword arguments as this is more robust to future message
00068 changes. You cannot mix in-order arguments and keyword arguments.
00069
00070 The available fields are:
00071 header,status,valid,axis,axis_function,swit,swit_function
00072
00073 :param args: complete set of field values, in .msg order
00074 :param kwds: use keyword arguments corresponding to message field names
00075 to set specific fields.
00076 """
00077 if args or kwds:
00078 super(RC, self).__init__(*args, **kwds)
00079
00080 if self.header is None:
00081 self.header = std_msgs.msg.Header()
00082 if self.status is None:
00083 self.status = 0
00084 if self.valid is None:
00085 self.valid = False
00086 if self.axis is None:
00087 self.axis = []
00088 if self.axis_function is None:
00089 self.axis_function = ''
00090 if self.swit is None:
00091 self.swit = []
00092 if self.swit_function is None:
00093 self.swit_function = ''
00094 else:
00095 self.header = std_msgs.msg.Header()
00096 self.status = 0
00097 self.valid = False
00098 self.axis = []
00099 self.axis_function = ''
00100 self.swit = []
00101 self.swit_function = ''
00102
00103 def _get_types(self):
00104 """
00105 internal API method
00106 """
00107 return self._slot_types
00108
00109 def serialize(self, buff):
00110 """
00111 serialize message into buffer
00112 :param buff: buffer, ``StringIO``
00113 """
00114 try:
00115 _x = self
00116 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00117 _x = self.header.frame_id
00118 length = len(_x)
00119 if python3 or type(_x) == unicode:
00120 _x = _x.encode('utf-8')
00121 length = len(_x)
00122 buff.write(struct.pack('<I%ss'%length, length, _x))
00123 _x = self
00124 buff.write(_struct_2B.pack(_x.status, _x.valid))
00125 length = len(self.axis)
00126 buff.write(_struct_I.pack(length))
00127 pattern = '<%sf'%length
00128 buff.write(struct.pack(pattern, *self.axis))
00129 _x = self.axis_function
00130 length = len(_x)
00131
00132 if type(_x) in [list, tuple]:
00133 buff.write(struct.pack('<I%sB'%length, length, *_x))
00134 else:
00135 buff.write(struct.pack('<I%ss'%length, length, _x))
00136 length = len(self.swit)
00137 buff.write(_struct_I.pack(length))
00138 pattern = '<%sb'%length
00139 buff.write(struct.pack(pattern, *self.swit))
00140 _x = self.swit_function
00141 length = len(_x)
00142
00143 if type(_x) in [list, tuple]:
00144 buff.write(struct.pack('<I%sB'%length, length, *_x))
00145 else:
00146 buff.write(struct.pack('<I%ss'%length, length, _x))
00147 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00148 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00149
00150 def deserialize(self, str):
00151 """
00152 unpack serialized message in str into this message instance
00153 :param str: byte array of serialized message, ``str``
00154 """
00155 try:
00156 if self.header is None:
00157 self.header = std_msgs.msg.Header()
00158 end = 0
00159 _x = self
00160 start = end
00161 end += 12
00162 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00163 start = end
00164 end += 4
00165 (length,) = _struct_I.unpack(str[start:end])
00166 start = end
00167 end += length
00168 if python3:
00169 self.header.frame_id = str[start:end].decode('utf-8')
00170 else:
00171 self.header.frame_id = str[start:end]
00172 _x = self
00173 start = end
00174 end += 2
00175 (_x.status, _x.valid,) = _struct_2B.unpack(str[start:end])
00176 self.valid = bool(self.valid)
00177 start = end
00178 end += 4
00179 (length,) = _struct_I.unpack(str[start:end])
00180 pattern = '<%sf'%length
00181 start = end
00182 end += struct.calcsize(pattern)
00183 self.axis = struct.unpack(pattern, str[start:end])
00184 start = end
00185 end += 4
00186 (length,) = _struct_I.unpack(str[start:end])
00187 start = end
00188 end += length
00189 self.axis_function = str[start:end]
00190 start = end
00191 end += 4
00192 (length,) = _struct_I.unpack(str[start:end])
00193 pattern = '<%sb'%length
00194 start = end
00195 end += struct.calcsize(pattern)
00196 self.swit = struct.unpack(pattern, str[start:end])
00197 start = end
00198 end += 4
00199 (length,) = _struct_I.unpack(str[start:end])
00200 start = end
00201 end += length
00202 self.swit_function = str[start:end]
00203 return self
00204 except struct.error as e:
00205 raise genpy.DeserializationError(e)
00206
00207
00208 def serialize_numpy(self, buff, numpy):
00209 """
00210 serialize message with numpy array types into buffer
00211 :param buff: buffer, ``StringIO``
00212 :param numpy: numpy python module
00213 """
00214 try:
00215 _x = self
00216 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00217 _x = self.header.frame_id
00218 length = len(_x)
00219 if python3 or type(_x) == unicode:
00220 _x = _x.encode('utf-8')
00221 length = len(_x)
00222 buff.write(struct.pack('<I%ss'%length, length, _x))
00223 _x = self
00224 buff.write(_struct_2B.pack(_x.status, _x.valid))
00225 length = len(self.axis)
00226 buff.write(_struct_I.pack(length))
00227 pattern = '<%sf'%length
00228 buff.write(self.axis.tostring())
00229 _x = self.axis_function
00230 length = len(_x)
00231
00232 if type(_x) in [list, tuple]:
00233 buff.write(struct.pack('<I%sB'%length, length, *_x))
00234 else:
00235 buff.write(struct.pack('<I%ss'%length, length, _x))
00236 length = len(self.swit)
00237 buff.write(_struct_I.pack(length))
00238 pattern = '<%sb'%length
00239 buff.write(self.swit.tostring())
00240 _x = self.swit_function
00241 length = len(_x)
00242
00243 if type(_x) in [list, tuple]:
00244 buff.write(struct.pack('<I%sB'%length, length, *_x))
00245 else:
00246 buff.write(struct.pack('<I%ss'%length, length, _x))
00247 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00248 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00249
00250 def deserialize_numpy(self, str, numpy):
00251 """
00252 unpack serialized message in str into this message instance using numpy for array types
00253 :param str: byte array of serialized message, ``str``
00254 :param numpy: numpy python module
00255 """
00256 try:
00257 if self.header is None:
00258 self.header = std_msgs.msg.Header()
00259 end = 0
00260 _x = self
00261 start = end
00262 end += 12
00263 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00264 start = end
00265 end += 4
00266 (length,) = _struct_I.unpack(str[start:end])
00267 start = end
00268 end += length
00269 if python3:
00270 self.header.frame_id = str[start:end].decode('utf-8')
00271 else:
00272 self.header.frame_id = str[start:end]
00273 _x = self
00274 start = end
00275 end += 2
00276 (_x.status, _x.valid,) = _struct_2B.unpack(str[start:end])
00277 self.valid = bool(self.valid)
00278 start = end
00279 end += 4
00280 (length,) = _struct_I.unpack(str[start:end])
00281 pattern = '<%sf'%length
00282 start = end
00283 end += struct.calcsize(pattern)
00284 self.axis = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00285 start = end
00286 end += 4
00287 (length,) = _struct_I.unpack(str[start:end])
00288 start = end
00289 end += length
00290 self.axis_function = str[start:end]
00291 start = end
00292 end += 4
00293 (length,) = _struct_I.unpack(str[start:end])
00294 pattern = '<%sb'%length
00295 start = end
00296 end += struct.calcsize(pattern)
00297 self.swit = numpy.frombuffer(str[start:end], dtype=numpy.int8, count=length)
00298 start = end
00299 end += 4
00300 (length,) = _struct_I.unpack(str[start:end])
00301 start = end
00302 end += length
00303 self.swit_function = str[start:end]
00304 return self
00305 except struct.error as e:
00306 raise genpy.DeserializationError(e)
00307
00308 _struct_I = genpy.struct_I
00309 _struct_3I = struct.Struct("<3I")
00310 _struct_2B = struct.Struct("<2B")