From 996e363122e7d05aa464560773b5dece3ff40582 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Dec 2012 02:13:49 +0100 Subject: Hotfix: general MAVLink update, including file transfer --- Tools/mavlink_px4.py | 5268 ++++++++++++++++++++ .../mavlink/v1.0/ardupilotmega/ardupilotmega.h | 6 +- .../include/mavlink/v1.0/ardupilotmega/version.h | 4 +- mavlink/include/mavlink/v1.0/common/common.h | 11 +- .../common/mavlink_msg_file_transfer_dir_list.h | 182 + .../v1.0/common/mavlink_msg_file_transfer_res.h | 166 + .../v1.0/common/mavlink_msg_file_transfer_start.h | 226 + .../v1.0/common/mavlink_msg_manual_setpoint.h | 276 + ...link_msg_roll_pitch_yaw_rates_thrust_setpoint.h | 232 + mavlink/include/mavlink/v1.0/common/testsuite.h | 254 + mavlink/include/mavlink/v1.0/common/version.h | 4 +- .../include/mavlink/v1.0/matrixpilot/matrixpilot.h | 6 +- mavlink/include/mavlink/v1.0/matrixpilot/version.h | 4 +- mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h | 6 +- mavlink/include/mavlink/v1.0/pixhawk/version.h | 2 +- mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h | 6 +- mavlink/include/mavlink/v1.0/sensesoar/version.h | 4 +- 17 files changed, 6633 insertions(+), 24 deletions(-) create mode 100644 Tools/mavlink_px4.py create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h diff --git a/Tools/mavlink_px4.py b/Tools/mavlink_px4.py new file mode 100644 index 000000000..bbad57b7d --- /dev/null +++ b/Tools/mavlink_px4.py @@ -0,0 +1,5268 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, mavutil, time, json + +WIRE_PROTOCOL_VERSION = "1.0" + + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, str): + return self._msgbuf + return self._msgbuf.tostring() + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = mavutil.x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate(chr(crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + def __init__(self, target_system, target_component, param_id, param_index): + MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_READ, 'PARAM_REQUEST_READ') + self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 214, struct.pack('= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + if self.callback: + self.callback(m, *self.callback_args, **self.callback_kwargs) + self.expected_length = 6 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = self.buf[0:self.expected_length] + self.buf = self.buf[self.expected_length:] + self.expected_length = 6 + if self.robust_parsing: + try: + m = self.decode(mbuf) + self.total_packets_received += 1 + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + self.total_packets_received += 1 + if self.callback: + self.callback(m, *self.callback_args, **self.callback_kwargs) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + (fmt, type, order_map, crc_extra) = mavlink_map[msgId] + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + msg = MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + msg.pack(self) + return msg + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + msg = MAVLink_param_request_list_message(target_system, target_component) + msg.pack(self) + return msg + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + msg = MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + msg.pack(self) + return msg + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + msg = MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + msg.pack(self) + return msg + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the sytem, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) above MSL (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + msg = MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + msg.pack(self) + return msg + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the sytem, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) above MSL (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + msg = MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + msg.pack(self) + return msg + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + msg = MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + msg.pack(self) + return msg + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + msg = MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + msg.pack(self) + return msg + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + msg = MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + msg.pack(self) + return msg + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + msg = MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + msg.pack(self) + return msg + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + msg = MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + msg.pack(self) + return msg + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1 (float) + q2 : Quaternion component 2 (float) + q3 : Quaternion component 3 (float) + q4 : Quaternion component 4 (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + msg = MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + msg.pack(self) + return msg + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1 (float) + q2 : Quaternion component 2 (float) + q3 : Quaternion component 3 (float) + q4 : Quaternion component 4 (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + msg = MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + msg.pack(self) + return msg + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + + ''' + msg = MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + msg.pack(self) + return msg + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to 65535. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + msg = MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + msg.pack(self) + return msg + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to 65535. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + msg = MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + msg.pack(self) + return msg + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_boot_ms : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + msg = MAVLink_servo_output_raw_message(time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + msg.pack(self) + return msg + + def servo_output_raw_send(self, time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_boot_ms : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + msg = MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + msg.pack(self) + return msg + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + msg = MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + msg.pack(self) + return msg + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + msg = MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + msg.pack(self) + return msg + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + msg = MAVLink_mission_request_message(target_system, target_component, seq) + msg.pack(self) + return msg + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + msg = MAVLink_mission_set_current_message(target_system, target_component, seq) + msg.pack(self) + return msg + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + msg = MAVLink_mission_current_message(seq) + msg.pack(self) + return msg + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + msg = MAVLink_mission_request_list_message(target_system, target_component) + msg.pack(self) + return msg + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + msg = MAVLink_mission_count_message(target_system, target_component, count) + msg.pack(self) + return msg + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + msg = MAVLink_mission_clear_all_message(target_system, target_component) + msg.pack(self) + return msg + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + msg = MAVLink_mission_item_reached_message(seq) + msg.pack(self) + return msg + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + msg = MAVLink_mission_ack_message(target_system, target_component, type) + msg.pack(self) + return msg + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + msg = MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + msg.pack(self) + return msg + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + msg = MAVLink_gps_global_origin_message(latitude, longitude, altitude) + msg.pack(self) + return msg + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def set_local_position_setpoint_encode(self, target_system, target_component, coordinate_frame, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/MISSION planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + msg = MAVLink_set_local_position_setpoint_message(target_system, target_component, coordinate_frame, x, y, z, yaw) + msg.pack(self) + return msg + + def set_local_position_setpoint_send(self, target_system, target_component, coordinate_frame, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/MISSION planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.set_local_position_setpoint_encode(target_system, target_component, coordinate_frame, x, y, z, yaw)) + + def local_position_setpoint_encode(self, coordinate_frame, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + msg = MAVLink_local_position_setpoint_message(coordinate_frame, x, y, z, yaw) + msg.pack(self) + return msg + + def local_position_setpoint_send(self, coordinate_frame, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_encode(coordinate_frame, x, y, z, yaw)) + + def global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) + latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) + longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) + altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) + yaw : Desired yaw angle in degrees * 100 (int16_t) + + ''' + msg = MAVLink_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw) + msg.pack(self) + return msg + + def global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) + latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) + longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) + altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) + yaw : Desired yaw angle in degrees * 100 (int16_t) + + ''' + return self.send(self.global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw)) + + def set_global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw): + ''' + Set the current global position setpoint. + + coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) + latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) + longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) + altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) + yaw : Desired yaw angle in degrees * 100 (int16_t) + + ''' + msg = MAVLink_set_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw) + msg.pack(self) + return msg + + def set_global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw): + ''' + Set the current global position setpoint. + + coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) + latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) + longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) + altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) + yaw : Desired yaw angle in degrees * 100 (int16_t) + + ''' + return self.send(self.set_global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + msg = MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + msg.pack(self) + return msg + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + msg = MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + msg.pack(self) + return msg + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + msg = MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) + msg.pack(self) + return msg + + def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) + + def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + msg = MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) + msg.pack(self) + return msg + + def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) + + def roll_pitch_yaw_thrust_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + msg = MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust) + msg.pack(self) + return msg + + def roll_pitch_yaw_thrust_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust)) + + def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + msg = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust) + msg.pack(self) + return msg + + def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust)) + + def set_quad_motors_setpoint_encode(self, target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw): + ''' + Setpoint in the four motor speeds + + target_system : System ID of the system that should set these motor commands (uint8_t) + motor_front_nw : Front motor in + configuration, front left motor in x configuration (uint16_t) + motor_right_ne : Right motor in + configuration, front right motor in x configuration (uint16_t) + motor_back_se : Back motor in + configuration, back right motor in x configuration (uint16_t) + motor_left_sw : Left motor in + configuration, back left motor in x configuration (uint16_t) + + ''' + msg = MAVLink_set_quad_motors_setpoint_message(target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw) + msg.pack(self) + return msg + + def set_quad_motors_setpoint_send(self, target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw): + ''' + Setpoint in the four motor speeds + + target_system : System ID of the system that should set these motor commands (uint8_t) + motor_front_nw : Front motor in + configuration, front left motor in x configuration (uint16_t) + motor_right_ne : Right motor in + configuration, front right motor in x configuration (uint16_t) + motor_back_se : Back motor in + configuration, back right motor in x configuration (uint16_t) + motor_left_sw : Left motor in + configuration, back left motor in x configuration (uint16_t) + + ''' + return self.send(self.set_quad_motors_setpoint_encode(target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw)) + + def set_quad_swarm_roll_pitch_yaw_thrust_encode(self, group, mode, roll, pitch, yaw, thrust): + ''' + Setpoint for up to four quadrotors in a group / wing + + group : ID of the quadrotor group (0 - 255, up to 256 groups supported) (uint8_t) + mode : ID of the flight mode (0 - 255, up to 256 modes supported) (uint8_t) + roll : Desired roll angle in radians +-PI (+-32767) (int16_t) + pitch : Desired pitch angle in radians +-PI (+-32767) (int16_t) + yaw : Desired yaw angle in radians, scaled to int16 +-PI (+-32767) (int16_t) + thrust : Collective thrust, scaled to uint16 (0..65535) (uint16_t) + + ''' + msg = MAVLink_set_quad_swarm_roll_pitch_yaw_thrust_message(group, mode, roll, pitch, yaw, thrust) + msg.pack(self) + return msg + + def set_quad_swarm_roll_pitch_yaw_thrust_send(self, group, mode, roll, pitch, yaw, thrust): + ''' + Setpoint for up to four quadrotors in a group / wing + + group : ID of the quadrotor group (0 - 255, up to 256 groups supported) (uint8_t) + mode : ID of the flight mode (0 - 255, up to 256 modes supported) (uint8_t) + roll : Desired roll angle in radians +-PI (+-32767) (int16_t) + pitch : Desired pitch angle in radians +-PI (+-32767) (int16_t) + yaw : Desired yaw angle in radians, scaled to int16 +-PI (+-32767) (int16_t) + thrust : Collective thrust, scaled to uint16 (0..65535) (uint16_t) + + ''' + return self.send(self.set_quad_swarm_roll_pitch_yaw_thrust_encode(group, mode, roll, pitch, yaw, thrust)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + msg = MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + msg.pack(self) + return msg + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def set_quad_swarm_led_roll_pitch_yaw_thrust_encode(self, group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust): + ''' + Setpoint for up to four quadrotors in a group / wing + + group : ID of the quadrotor group (0 - 255, up to 256 groups supported) (uint8_t) + mode : ID of the flight mode (0 - 255, up to 256 modes supported) (uint8_t) + led_red : RGB red channel (0-255) (uint8_t) + led_blue : RGB green channel (0-255) (uint8_t) + led_green : RGB blue channel (0-255) (uint8_t) + roll : Desired roll angle in radians +-PI (+-32767) (int16_t) + pitch : Desired pitch angle in radians +-PI (+-32767) (int16_t) + yaw : Desired yaw angle in radians, scaled to int16 +-PI (+-32767) (int16_t) + thrust : Collective thrust, scaled to uint16 (0..65535) (uint16_t) + + ''' + msg = MAVLink_set_quad_swarm_led_roll_pitch_yaw_thrust_message(group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust) + msg.pack(self) + return msg + + def set_quad_swarm_led_roll_pitch_yaw_thrust_send(self, group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust): + ''' + Setpoint for up to four quadrotors in a group / wing + + group : ID of the quadrotor group (0 - 255, up to 256 groups supported) (uint8_t) + mode : ID of the flight mode (0 - 255, up to 256 modes supported) (uint8_t) + led_red : RGB red channel (0-255) (uint8_t) + led_blue : RGB green channel (0-255) (uint8_t) + led_green : RGB blue channel (0-255) (uint8_t) + roll : Desired roll angle in radians +-PI (+-32767) (int16_t) + pitch : Desired pitch angle in radians +-PI (+-32767) (int16_t) + yaw : Desired yaw angle in radians, scaled to int16 +-PI (+-32767) (int16_t) + thrust : Collective thrust, scaled to uint16 (0..65535) (uint16_t) + + ''' + return self.send(self.set_quad_swarm_led_roll_pitch_yaw_thrust_encode(group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust)) + + def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + msg = MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) + msg.pack(self) + return msg + + def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested interval between two messages of this type (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + msg = MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + msg.pack(self) + return msg + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested interval between two messages of this type (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The requested interval between two messages of this type (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + msg = MAVLink_data_stream_message(stream_id, message_rate, on_off) + msg.pack(self) + return msg + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The requested interval between two messages of this type (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + msg = MAVLink_manual_control_message(target, x, y, z, r, buttons) + msg.pack(self) + return msg + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + msg = MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + msg.pack(self) + return msg + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + msg = MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + msg.pack(self) + return msg + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + msg = MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + msg.pack(self) + return msg + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + msg = MAVLink_command_ack_message(command, result) + msg.pack(self) + return msg + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def roll_pitch_yaw_rates_thrust_setpoint_encode(self, time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust): + ''' + Setpoint in roll, pitch, yaw rates and thrust currently active on the + system. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll_rate : Desired roll rate in radians per second (float) + pitch_rate : Desired pitch rate in radians per second (float) + yaw_rate : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + msg = MAVLink_roll_pitch_yaw_rates_thrust_setpoint_message(time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust) + msg.pack(self) + return msg + + def roll_pitch_yaw_rates_thrust_setpoint_send(self, time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust): + ''' + Setpoint in roll, pitch, yaw rates and thrust currently active on the + system. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll_rate : Desired roll rate in radians per second (float) + pitch_rate : Desired pitch rate in radians per second (float) + yaw_rate : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_rates_thrust_setpoint_encode(time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + msg = MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + msg.pack(self) + return msg + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + msg = MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + msg.pack(self) + return msg + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + msg = MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + msg.pack(self) + return msg + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + msg = MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + msg.pack(self) + return msg + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + msg = MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + msg.pack(self) + return msg + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + msg = MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + msg.pack(self) + return msg + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + msg = MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + msg.pack(self) + return msg + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + msg = MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + msg.pack(self) + return msg + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + msg = MAVLink_vision_speed_estimate_message(usec, x, y, z) + msg.pack(self) + return msg + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + msg = MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + msg.pack(self) + return msg + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + msg = MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + msg.pack(self) + return msg + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def file_transfer_start_encode(self, transfer_uid, dest_path, direction, file_size, flags): + ''' + Begin file transfer + + transfer_uid : Unique transfer ID (uint64_t) + dest_path : Destination path (char) + direction : Transfer direction: 0: from requester, 1: to requester (uint8_t) + file_size : File size in bytes (uint32_t) + flags : RESERVED (uint8_t) + + ''' + msg = MAVLink_file_transfer_start_message(transfer_uid, dest_path, direction, file_size, flags) + msg.pack(self) + return msg + + def file_transfer_start_send(self, transfer_uid, dest_path, direction, file_size, flags): + ''' + Begin file transfer + + transfer_uid : Unique transfer ID (uint64_t) + dest_path : Destination path (char) + direction : Transfer direction: 0: from requester, 1: to requester (uint8_t) + file_size : File size in bytes (uint32_t) + flags : RESERVED (uint8_t) + + ''' + return self.send(self.file_transfer_start_encode(transfer_uid, dest_path, direction, file_size, flags)) + + def file_transfer_dir_list_encode(self, transfer_uid, dir_path, flags): + ''' + Get directory listing + + transfer_uid : Unique transfer ID (uint64_t) + dir_path : Directory path to list (char) + flags : RESERVED (uint8_t) + + ''' + msg = MAVLink_file_transfer_dir_list_message(transfer_uid, dir_path, flags) + msg.pack(self) + return msg + + def file_transfer_dir_list_send(self, transfer_uid, dir_path, flags): + ''' + Get directory listing + + transfer_uid : Unique transfer ID (uint64_t) + dir_path : Directory path to list (char) + flags : RESERVED (uint8_t) + + ''' + return self.send(self.file_transfer_dir_list_encode(transfer_uid, dir_path, flags)) + + def file_transfer_res_encode(self, transfer_uid, result): + ''' + File transfer result + + transfer_uid : Unique transfer ID (uint64_t) + result : 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device (uint8_t) + + ''' + msg = MAVLink_file_transfer_res_message(transfer_uid, result) + msg.pack(self) + return msg + + def file_transfer_res_send(self, transfer_uid, result): + ''' + File transfer result + + transfer_uid : Unique transfer ID (uint64_t) + result : 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device (uint8_t) + + ''' + return self.send(self.file_transfer_res_encode(transfer_uid, result)) + + def battery_status_encode(self, accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining): + ''' + Transmitte battery informations for a accu pack. + + accu_id : Accupack ID (uint8_t) + voltage_cell_1 : Battery voltage of cell 1, in millivolts (1 = 1 millivolt) (uint16_t) + voltage_cell_2 : Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + voltage_cell_3 : Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + voltage_cell_4 : Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + voltage_cell_5 : Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + voltage_cell_6 : Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + msg = MAVLink_battery_status_message(accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining) + msg.pack(self) + return msg + + def battery_status_send(self, accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining): + ''' + Transmitte battery informations for a accu pack. + + accu_id : Accupack ID (uint8_t) + voltage_cell_1 : Battery voltage of cell 1, in millivolts (1 = 1 millivolt) (uint16_t) + voltage_cell_2 : Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + voltage_cell_3 : Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + voltage_cell_4 : Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + voltage_cell_5 : Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + voltage_cell_6 : Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining)) + + def setpoint_8dof_encode(self, target_system, val1, val2, val3, val4, val5, val6, val7, val8): + ''' + Set the 8 DOF setpoint for a controller. + + target_system : System ID (uint8_t) + val1 : Value 1 (float) + val2 : Value 2 (float) + val3 : Value 3 (float) + val4 : Value 4 (float) + val5 : Value 5 (float) + val6 : Value 6 (float) + val7 : Value 7 (float) + val8 : Value 8 (float) + + ''' + msg = MAVLink_setpoint_8dof_message(target_system, val1, val2, val3, val4, val5, val6, val7, val8) + msg.pack(self) + return msg + + def setpoint_8dof_send(self, target_system, val1, val2, val3, val4, val5, val6, val7, val8): + ''' + Set the 8 DOF setpoint for a controller. + + target_system : System ID (uint8_t) + val1 : Value 1 (float) + val2 : Value 2 (float) + val3 : Value 3 (float) + val4 : Value 4 (float) + val5 : Value 5 (float) + val6 : Value 6 (float) + val7 : Value 7 (float) + val8 : Value 8 (float) + + ''' + return self.send(self.setpoint_8dof_encode(target_system, val1, val2, val3, val4, val5, val6, val7, val8)) + + def setpoint_6dof_encode(self, target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z): + ''' + Set the 6 DOF setpoint for a attitude and position controller. + + target_system : System ID (uint8_t) + trans_x : Translational Component in x (float) + trans_y : Translational Component in y (float) + trans_z : Translational Component in z (float) + rot_x : Rotational Component in x (float) + rot_y : Rotational Component in y (float) + rot_z : Rotational Component in z (float) + + ''' + msg = MAVLink_setpoint_6dof_message(target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z) + msg.pack(self) + return msg + + def setpoint_6dof_send(self, target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z): + ''' + Set the 6 DOF setpoint for a attitude and position controller. + + target_system : System ID (uint8_t) + trans_x : Translational Component in x (float) + trans_y : Translational Component in y (float) + trans_z : Translational Component in z (float) + rot_x : Rotational Component in x (float) + rot_y : Rotational Component in y (float) + rot_z : Rotational Component in z (float) + + ''' + return self.send(self.setpoint_6dof_encode(target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + msg = MAVLink_memory_vect_message(address, ver, type, value) + msg.pack(self) + return msg + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + msg = MAVLink_debug_vect_message(name, time_usec, x, y, z) + msg.pack(self) + return msg + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + msg = MAVLink_named_value_float_message(time_boot_ms, name, value) + msg.pack(self) + return msg + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + msg = MAVLink_named_value_int_message(time_boot_ms, name, value) + msg.pack(self) + return msg + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + msg = MAVLink_statustext_message(severity, text) + msg.pack(self) + return msg + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + msg = MAVLink_debug_message(time_boot_ms, ind, value) + msg.pack(self) + return msg + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h index 0e27c3264..754ca44e1 100644 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 0, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 242, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 1, 234, 73, 181, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 242, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 0, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 1, 234, 73, 181, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/version.h b/mavlink/include/mavlink/v1.0/ardupilotmega/version.h index be1ca4c83..37d021095 100644 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/version.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/version.h @@ -5,8 +5,8 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Oct 18 13:36:48 2012" +#define MAVLINK_BUILD_DATE "Sat Dec 1 02:05:58 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" -#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 +#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254 #endif // MAVLINK_VERSION_H diff --git a/mavlink/include/mavlink/v1.0/common/common.h b/mavlink/include/mavlink/v1.0/common/common.h index b7f57785b..06f4ed711 100644 --- a/mavlink/include/mavlink/v1.0/common/common.h +++ b/mavlink/include/mavlink/v1.0/common/common.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 0, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 242, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 242, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 0, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -472,6 +472,8 @@ enum MAV_SEVERITY #include "./mavlink_msg_vfr_hud.h" #include "./mavlink_msg_command_long.h" #include "./mavlink_msg_command_ack.h" +#include "./mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h" +#include "./mavlink_msg_manual_setpoint.h" #include "./mavlink_msg_local_position_ned_system_global_offset.h" #include "./mavlink_msg_hil_state.h" #include "./mavlink_msg_hil_controls.h" @@ -482,6 +484,9 @@ enum MAV_SEVERITY #include "./mavlink_msg_vision_speed_estimate.h" #include "./mavlink_msg_vicon_position_estimate.h" #include "./mavlink_msg_highres_imu.h" +#include "./mavlink_msg_file_transfer_start.h" +#include "./mavlink_msg_file_transfer_dir_list.h" +#include "./mavlink_msg_file_transfer_res.h" #include "./mavlink_msg_battery_status.h" #include "./mavlink_msg_setpoint_8dof.h" #include "./mavlink_msg_setpoint_6dof.h" diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h new file mode 100644 index 000000000..27f5a91db --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h @@ -0,0 +1,182 @@ +// MESSAGE FILE_TRANSFER_DIR_LIST PACKING + +#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST 111 + +typedef struct __mavlink_file_transfer_dir_list_t +{ + uint64_t transfer_uid; ///< Unique transfer ID + char dir_path[240]; ///< Directory path to list + uint8_t flags; ///< RESERVED +} mavlink_file_transfer_dir_list_t; + +#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN 249 +#define MAVLINK_MSG_ID_111_LEN 249 + +#define MAVLINK_MSG_FILE_TRANSFER_DIR_LIST_FIELD_DIR_PATH_LEN 240 + +#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST { \ + "FILE_TRANSFER_DIR_LIST", \ + 3, \ + { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_dir_list_t, transfer_uid) }, \ + { "dir_path", NULL, MAVLINK_TYPE_CHAR, 240, 8, offsetof(mavlink_file_transfer_dir_list_t, dir_path) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 248, offsetof(mavlink_file_transfer_dir_list_t, flags) }, \ + } \ +} + + +/** + * @brief Pack a file_transfer_dir_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param transfer_uid Unique transfer ID + * @param dir_path Directory path to list + * @param flags RESERVED + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_dir_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t transfer_uid, const char *dir_path, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[249]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint8_t(buf, 248, flags); + _mav_put_char_array(buf, 8, dir_path, 240); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 249); +#else + mavlink_file_transfer_dir_list_t packet; + packet.transfer_uid = transfer_uid; + packet.flags = flags; + mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 249); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST; + return mavlink_finalize_message(msg, system_id, component_id, 249, 93); +} + +/** + * @brief Pack a file_transfer_dir_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param transfer_uid Unique transfer ID + * @param dir_path Directory path to list + * @param flags RESERVED + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_dir_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t transfer_uid,const char *dir_path,uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[249]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint8_t(buf, 248, flags); + _mav_put_char_array(buf, 8, dir_path, 240); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 249); +#else + mavlink_file_transfer_dir_list_t packet; + packet.transfer_uid = transfer_uid; + packet.flags = flags; + mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 249); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 249, 93); +} + +/** + * @brief Encode a file_transfer_dir_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param file_transfer_dir_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_file_transfer_dir_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_dir_list_t* file_transfer_dir_list) +{ + return mavlink_msg_file_transfer_dir_list_pack(system_id, component_id, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags); +} + +/** + * @brief Send a file_transfer_dir_list message + * @param chan MAVLink channel to send the message + * + * @param transfer_uid Unique transfer ID + * @param dir_path Directory path to list + * @param flags RESERVED + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_file_transfer_dir_list_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dir_path, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[249]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint8_t(buf, 248, flags); + _mav_put_char_array(buf, 8, dir_path, 240); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, 249, 93); +#else + mavlink_file_transfer_dir_list_t packet; + packet.transfer_uid = transfer_uid; + packet.flags = flags; + mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)&packet, 249, 93); +#endif +} + +#endif + +// MESSAGE FILE_TRANSFER_DIR_LIST UNPACKING + + +/** + * @brief Get field transfer_uid from file_transfer_dir_list message + * + * @return Unique transfer ID + */ +static inline uint64_t mavlink_msg_file_transfer_dir_list_get_transfer_uid(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field dir_path from file_transfer_dir_list message + * + * @return Directory path to list + */ +static inline uint16_t mavlink_msg_file_transfer_dir_list_get_dir_path(const mavlink_message_t* msg, char *dir_path) +{ + return _MAV_RETURN_char_array(msg, dir_path, 240, 8); +} + +/** + * @brief Get field flags from file_transfer_dir_list message + * + * @return RESERVED + */ +static inline uint8_t mavlink_msg_file_transfer_dir_list_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 248); +} + +/** + * @brief Decode a file_transfer_dir_list message into a struct + * + * @param msg The message to decode + * @param file_transfer_dir_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_file_transfer_dir_list_decode(const mavlink_message_t* msg, mavlink_file_transfer_dir_list_t* file_transfer_dir_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + file_transfer_dir_list->transfer_uid = mavlink_msg_file_transfer_dir_list_get_transfer_uid(msg); + mavlink_msg_file_transfer_dir_list_get_dir_path(msg, file_transfer_dir_list->dir_path); + file_transfer_dir_list->flags = mavlink_msg_file_transfer_dir_list_get_flags(msg); +#else + memcpy(file_transfer_dir_list, _MAV_PAYLOAD(msg), 249); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h new file mode 100644 index 000000000..f7035ec9e --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h @@ -0,0 +1,166 @@ +// MESSAGE FILE_TRANSFER_RES PACKING + +#define MAVLINK_MSG_ID_FILE_TRANSFER_RES 112 + +typedef struct __mavlink_file_transfer_res_t +{ + uint64_t transfer_uid; ///< Unique transfer ID + uint8_t result; ///< 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device +} mavlink_file_transfer_res_t; + +#define MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN 9 +#define MAVLINK_MSG_ID_112_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES { \ + "FILE_TRANSFER_RES", \ + 2, \ + { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_res_t, transfer_uid) }, \ + { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_file_transfer_res_t, result) }, \ + } \ +} + + +/** + * @brief Pack a file_transfer_res message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param transfer_uid Unique transfer ID + * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_res_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t transfer_uid, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint8_t(buf, 8, result); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_file_transfer_res_t packet; + packet.transfer_uid = transfer_uid; + packet.result = result; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES; + return mavlink_finalize_message(msg, system_id, component_id, 9, 124); +} + +/** + * @brief Pack a file_transfer_res message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param transfer_uid Unique transfer ID + * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_res_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t transfer_uid,uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint8_t(buf, 8, result); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_file_transfer_res_t packet; + packet.transfer_uid = transfer_uid; + packet.result = result; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 124); +} + +/** + * @brief Encode a file_transfer_res struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param file_transfer_res C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_file_transfer_res_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_res_t* file_transfer_res) +{ + return mavlink_msg_file_transfer_res_pack(system_id, component_id, msg, file_transfer_res->transfer_uid, file_transfer_res->result); +} + +/** + * @brief Send a file_transfer_res message + * @param chan MAVLink channel to send the message + * + * @param transfer_uid Unique transfer ID + * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_file_transfer_res_send(mavlink_channel_t chan, uint64_t transfer_uid, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint8_t(buf, 8, result); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, 9, 124); +#else + mavlink_file_transfer_res_t packet; + packet.transfer_uid = transfer_uid; + packet.result = result; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)&packet, 9, 124); +#endif +} + +#endif + +// MESSAGE FILE_TRANSFER_RES UNPACKING + + +/** + * @brief Get field transfer_uid from file_transfer_res message + * + * @return Unique transfer ID + */ +static inline uint64_t mavlink_msg_file_transfer_res_get_transfer_uid(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field result from file_transfer_res message + * + * @return 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device + */ +static inline uint8_t mavlink_msg_file_transfer_res_get_result(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Decode a file_transfer_res message into a struct + * + * @param msg The message to decode + * @param file_transfer_res C-struct to decode the message contents into + */ +static inline void mavlink_msg_file_transfer_res_decode(const mavlink_message_t* msg, mavlink_file_transfer_res_t* file_transfer_res) +{ +#if MAVLINK_NEED_BYTE_SWAP + file_transfer_res->transfer_uid = mavlink_msg_file_transfer_res_get_transfer_uid(msg); + file_transfer_res->result = mavlink_msg_file_transfer_res_get_result(msg); +#else + memcpy(file_transfer_res, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h new file mode 100644 index 000000000..5eaa9b220 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h @@ -0,0 +1,226 @@ +// MESSAGE FILE_TRANSFER_START PACKING + +#define MAVLINK_MSG_ID_FILE_TRANSFER_START 110 + +typedef struct __mavlink_file_transfer_start_t +{ + uint64_t transfer_uid; ///< Unique transfer ID + uint32_t file_size; ///< File size in bytes + char dest_path[240]; ///< Destination path + uint8_t direction; ///< Transfer direction: 0: from requester, 1: to requester + uint8_t flags; ///< RESERVED +} mavlink_file_transfer_start_t; + +#define MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN 254 +#define MAVLINK_MSG_ID_110_LEN 254 + +#define MAVLINK_MSG_FILE_TRANSFER_START_FIELD_DEST_PATH_LEN 240 + +#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START { \ + "FILE_TRANSFER_START", \ + 5, \ + { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_start_t, transfer_uid) }, \ + { "file_size", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_file_transfer_start_t, file_size) }, \ + { "dest_path", NULL, MAVLINK_TYPE_CHAR, 240, 12, offsetof(mavlink_file_transfer_start_t, dest_path) }, \ + { "direction", NULL, MAVLINK_TYPE_UINT8_T, 0, 252, offsetof(mavlink_file_transfer_start_t, direction) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 253, offsetof(mavlink_file_transfer_start_t, flags) }, \ + } \ +} + + +/** + * @brief Pack a file_transfer_start message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param transfer_uid Unique transfer ID + * @param dest_path Destination path + * @param direction Transfer direction: 0: from requester, 1: to requester + * @param file_size File size in bytes + * @param flags RESERVED + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_start_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[254]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint32_t(buf, 8, file_size); + _mav_put_uint8_t(buf, 252, direction); + _mav_put_uint8_t(buf, 253, flags); + _mav_put_char_array(buf, 12, dest_path, 240); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 254); +#else + mavlink_file_transfer_start_t packet; + packet.transfer_uid = transfer_uid; + packet.file_size = file_size; + packet.direction = direction; + packet.flags = flags; + mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 254); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START; + return mavlink_finalize_message(msg, system_id, component_id, 254, 235); +} + +/** + * @brief Pack a file_transfer_start message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param transfer_uid Unique transfer ID + * @param dest_path Destination path + * @param direction Transfer direction: 0: from requester, 1: to requester + * @param file_size File size in bytes + * @param flags RESERVED + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_start_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t transfer_uid,const char *dest_path,uint8_t direction,uint32_t file_size,uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[254]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint32_t(buf, 8, file_size); + _mav_put_uint8_t(buf, 252, direction); + _mav_put_uint8_t(buf, 253, flags); + _mav_put_char_array(buf, 12, dest_path, 240); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 254); +#else + mavlink_file_transfer_start_t packet; + packet.transfer_uid = transfer_uid; + packet.file_size = file_size; + packet.direction = direction; + packet.flags = flags; + mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 254); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 254, 235); +} + +/** + * @brief Encode a file_transfer_start struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param file_transfer_start C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_file_transfer_start_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_start_t* file_transfer_start) +{ + return mavlink_msg_file_transfer_start_pack(system_id, component_id, msg, file_transfer_start->transfer_uid, file_transfer_start->dest_path, file_transfer_start->direction, file_transfer_start->file_size, file_transfer_start->flags); +} + +/** + * @brief Send a file_transfer_start message + * @param chan MAVLink channel to send the message + * + * @param transfer_uid Unique transfer ID + * @param dest_path Destination path + * @param direction Transfer direction: 0: from requester, 1: to requester + * @param file_size File size in bytes + * @param flags RESERVED + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_file_transfer_start_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[254]; + _mav_put_uint64_t(buf, 0, transfer_uid); + _mav_put_uint32_t(buf, 8, file_size); + _mav_put_uint8_t(buf, 252, direction); + _mav_put_uint8_t(buf, 253, flags); + _mav_put_char_array(buf, 12, dest_path, 240); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, 254, 235); +#else + mavlink_file_transfer_start_t packet; + packet.transfer_uid = transfer_uid; + packet.file_size = file_size; + packet.direction = direction; + packet.flags = flags; + mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)&packet, 254, 235); +#endif +} + +#endif + +// MESSAGE FILE_TRANSFER_START UNPACKING + + +/** + * @brief Get field transfer_uid from file_transfer_start message + * + * @return Unique transfer ID + */ +static inline uint64_t mavlink_msg_file_transfer_start_get_transfer_uid(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field dest_path from file_transfer_start message + * + * @return Destination path + */ +static inline uint16_t mavlink_msg_file_transfer_start_get_dest_path(const mavlink_message_t* msg, char *dest_path) +{ + return _MAV_RETURN_char_array(msg, dest_path, 240, 12); +} + +/** + * @brief Get field direction from file_transfer_start message + * + * @return Transfer direction: 0: from requester, 1: to requester + */ +static inline uint8_t mavlink_msg_file_transfer_start_get_direction(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 252); +} + +/** + * @brief Get field file_size from file_transfer_start message + * + * @return File size in bytes + */ +static inline uint32_t mavlink_msg_file_transfer_start_get_file_size(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field flags from file_transfer_start message + * + * @return RESERVED + */ +static inline uint8_t mavlink_msg_file_transfer_start_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 253); +} + +/** + * @brief Decode a file_transfer_start message into a struct + * + * @param msg The message to decode + * @param file_transfer_start C-struct to decode the message contents into + */ +static inline void mavlink_msg_file_transfer_start_decode(const mavlink_message_t* msg, mavlink_file_transfer_start_t* file_transfer_start) +{ +#if MAVLINK_NEED_BYTE_SWAP + file_transfer_start->transfer_uid = mavlink_msg_file_transfer_start_get_transfer_uid(msg); + file_transfer_start->file_size = mavlink_msg_file_transfer_start_get_file_size(msg); + mavlink_msg_file_transfer_start_get_dest_path(msg, file_transfer_start->dest_path); + file_transfer_start->direction = mavlink_msg_file_transfer_start_get_direction(msg); + file_transfer_start->flags = mavlink_msg_file_transfer_start_get_flags(msg); +#else + memcpy(file_transfer_start, _MAV_PAYLOAD(msg), 254); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h new file mode 100644 index 000000000..71db380a1 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h @@ -0,0 +1,276 @@ +// MESSAGE MANUAL_SETPOINT PACKING + +#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81 + +typedef struct __mavlink_manual_setpoint_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot + float roll; ///< Desired roll rate in radians per second + float pitch; ///< Desired pitch rate in radians per second + float yaw; ///< Desired yaw rate in radians per second + float thrust; ///< Collective thrust, normalized to 0 .. 1 + uint8_t mode_switch; ///< Flight mode switch position, 0.. 255 + uint8_t manual_override_switch; ///< Override mode switch position, 0.. 255 +} mavlink_manual_setpoint_t; + +#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 +#define MAVLINK_MSG_ID_81_LEN 22 + + + +#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ + "MANUAL_SETPOINT", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ + { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ + { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ + } \ +} + + +/** + * @brief Pack a manual_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 22, 106); +} + +/** + * @brief Pack a manual_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust,uint8_t mode_switch,uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 106); +} + +/** + * @brief Encode a manual_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param manual_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) +{ + return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); +} + +/** + * @brief Send a manual_setpoint message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, 22, 106); +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, 22, 106); +#endif +} + +#endif + +// MESSAGE MANUAL_SETPOINT UNPACKING + + +/** + * @brief Get field time_boot_ms from manual_setpoint message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from manual_setpoint message + * + * @return Desired roll rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from manual_setpoint message + * + * @return Desired pitch rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from manual_setpoint message + * + * @return Desired yaw rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field thrust from manual_setpoint message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field mode_switch from manual_setpoint message + * + * @return Flight mode switch position, 0.. 255 + */ +static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field manual_override_switch from manual_setpoint message + * + * @return Override mode switch position, 0.. 255 + */ +static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a manual_setpoint message into a struct + * + * @param msg The message to decode + * @param manual_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg); + manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg); + manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg); + manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg); + manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg); + manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg); + manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg); +#else + memcpy(manual_setpoint, _MAV_PAYLOAD(msg), 22); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h new file mode 100644 index 000000000..47772e004 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT PACKING + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT 80 + +typedef struct __mavlink_roll_pitch_yaw_rates_thrust_setpoint_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot + float roll_rate; ///< Desired roll rate in radians per second + float pitch_rate; ///< Desired pitch rate in radians per second + float yaw_rate; ///< Desired yaw rate in radians per second + float thrust; ///< Collective thrust, normalized to 0 .. 1 +} mavlink_roll_pitch_yaw_rates_thrust_setpoint_t; + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN 20 +#define MAVLINK_MSG_ID_80_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT { \ + "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT", \ + 5, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, time_boot_ms) }, \ + { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, roll_rate) }, \ + { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, pitch_rate) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, yaw_rate) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, thrust) }, \ + } \ +} + + +/** + * @brief Pack a roll_pitch_yaw_rates_thrust_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_rate Desired roll rate in radians per second + * @param pitch_rate Desired pitch rate in radians per second + * @param yaw_rate Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_rate); + _mav_put_float(buf, 8, pitch_rate); + _mav_put_float(buf, 12, yaw_rate); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 20, 127); +} + +/** + * @brief Pack a roll_pitch_yaw_rates_thrust_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_rate Desired roll rate in radians per second + * @param pitch_rate Desired pitch rate in radians per second + * @param yaw_rate Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll_rate,float pitch_rate,float yaw_rate,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_rate); + _mav_put_float(buf, 8, pitch_rate); + _mav_put_float(buf, 12, yaw_rate); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 127); +} + +/** + * @brief Encode a roll_pitch_yaw_rates_thrust_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param roll_pitch_yaw_rates_thrust_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint) +{ + return mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms, roll_pitch_yaw_rates_thrust_setpoint->roll_rate, roll_pitch_yaw_rates_thrust_setpoint->pitch_rate, roll_pitch_yaw_rates_thrust_setpoint->yaw_rate, roll_pitch_yaw_rates_thrust_setpoint->thrust); +} + +/** + * @brief Send a roll_pitch_yaw_rates_thrust_setpoint message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_rate Desired roll rate in radians per second + * @param pitch_rate Desired pitch rate in radians per second + * @param yaw_rate Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_rate); + _mav_put_float(buf, 8, pitch_rate); + _mav_put_float(buf, 12, yaw_rate); + _mav_put_float(buf, 16, thrust); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, 20, 127); +#else + mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + packet.thrust = thrust; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)&packet, 20, 127); +#endif +} + +#endif + +// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT UNPACKING + + +/** + * @brief Get field time_boot_ms from roll_pitch_yaw_rates_thrust_setpoint message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll_rate from roll_pitch_yaw_rates_thrust_setpoint message + * + * @return Desired roll rate in radians per second + */ +static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_roll_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch_rate from roll_pitch_yaw_rates_thrust_setpoint message + * + * @return Desired pitch rate in radians per second + */ +static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_pitch_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw_rate from roll_pitch_yaw_rates_thrust_setpoint message + * + * @return Desired yaw rate in radians per second + */ +static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field thrust from roll_pitch_yaw_rates_thrust_setpoint message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a roll_pitch_yaw_rates_thrust_setpoint message into a struct + * + * @param msg The message to decode + * @param roll_pitch_yaw_rates_thrust_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_time_boot_ms(msg); + roll_pitch_yaw_rates_thrust_setpoint->roll_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_roll_rate(msg); + roll_pitch_yaw_rates_thrust_setpoint->pitch_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_pitch_rate(msg); + roll_pitch_yaw_rates_thrust_setpoint->yaw_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(msg); + roll_pitch_yaw_rates_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(msg); +#else + memcpy(roll_pitch_yaw_rates_thrust_setpoint, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/testsuite.h b/mavlink/include/mavlink/v1.0/common/testsuite.h index 8b51c0959..ef70550c0 100644 --- a/mavlink/include/mavlink/v1.0/common/testsuite.h +++ b/mavlink/include/mavlink/v1.0/common/testsuite.h @@ -3178,6 +3178,112 @@ static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, ma MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet_in = { + 963497464, + 45.0, + 73.0, + 101.0, + 129.0, + }; + mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.time_boot_ms = packet_in.time_boot_ms; + packet1.roll_rate = packet_in.roll_rate; + packet1.pitch_rate = packet_in.pitch_rate; + packet1.yaw_rate = packet_in.yaw_rate; + packet1.thrust = packet_in.thrust; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate , packet1.thrust ); + mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate , packet1.thrust ); + mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i