diff --git a/mavlink_lib.py b/mavlink_lib.py index a884aec26ddde6d78105db11a4a5bce7dea654dc..88b070e5d3c619324a5a6946e43f5e95c7069f37 100644 --- a/mavlink_lib.py +++ b/mavlink_lib.py @@ -1805,23 +1805,23 @@ class MAVLink_arp_tm_message(MAVLink_message): ''' id = MAVLINK_MSG_ID_ARP_TM name = 'ARP_TM' - fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix'] - ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix'] - fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t'] + fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'ethernet_present', 'ethernet_status', 'battery_voltage'] + ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'main_rx_rssi', 'battery_voltage', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'gps_fix', 'main_radio_present', 'ethernet_present', 'ethernet_status'] + fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint8_t', 'float'] fielddisplays_by_name = {} fieldenums_by_name = {} - fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m"} - format = '<QffffffffffffffB' - native_format = bytearray('<QffffffffffffffB', 'ascii') - orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15] - lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] - array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] - crc_extra = 122 - unpacker = struct.Struct('<QffffffffffffffB') + fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "battery_voltage": "V"} + format = '<QffffffffffffffffHHHHHBBBB' + native_format = bytearray('<QffffffffffffffffHHHHHBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 22, 23, 17, 18, 19, 20, 21, 15, 24, 25, 16] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 2 + unpacker = struct.Struct('<QffffffffffffffffHHHHHBBBB') instance_field = None instance_offset = -1 - def __init__(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix): + def __init__(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage): MAVLink_message.__init__(self, MAVLink_arp_tm_message.id, MAVLink_arp_tm_message.name) self._fieldnames = MAVLink_arp_tm_message.fieldnames self._instance_field = MAVLink_arp_tm_message.instance_field @@ -1842,9 +1842,19 @@ class MAVLink_arp_tm_message(MAVLink_message): self.gps_longitude = gps_longitude self.gps_height = gps_height self.gps_fix = gps_fix + self.main_radio_present = main_radio_present + self.main_packet_tx_error_count = main_packet_tx_error_count + self.main_tx_bitrate = main_tx_bitrate + self.main_packet_rx_success_count = main_packet_rx_success_count + self.main_packet_rx_drop_count = main_packet_rx_drop_count + self.main_rx_bitrate = main_rx_bitrate + self.main_rx_rssi = main_rx_rssi + self.ethernet_present = ethernet_present + self.ethernet_status = ethernet_status + self.battery_voltage = battery_voltage def pack(self, mav, force_mavlink1=False): - return MAVLink_message.pack(self, mav, 122, struct.pack('<QffffffffffffffB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.gps_fix), force_mavlink1=force_mavlink1) + return MAVLink_message.pack(self, mav, 2, struct.pack('<QffffffffffffffffHHHHHBBBB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.main_rx_rssi, self.battery_voltage, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.gps_fix, self.main_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1) class MAVLink_set_antenna_coordinates_arp_tc_message(MAVLink_message): ''' @@ -3922,7 +3932,7 @@ class MAVLink(object): ''' return self.send(self.receiver_tm_encode(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage), force_mavlink1=force_mavlink1) - def arp_tm_encode(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix): + def arp_tm_encode(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage): ''' @@ -3932,21 +3942,31 @@ class MAVLink(object): roll : Current Roll [deg] (type:float) target_yaw : Target Yaw [deg] (type:float) target_pitch : Target Pitch [deg] (type:float) - stepperX_pos : StepperX current pos [deg] (type:float) - stepperX_delta : StepperX actuated delta [deg] (type:float) - stepperX_speed : StepperX Speed [rps] (type:float) - stepperY_pos : StepperY current pos [deg] (type:float) - stepperY_delta : StepperY actuated delta [deg] (type:float) - stepperY_speed : StepperY Speed [rps] (type:float) + stepperX_pos : StepperX current position wrt the boot position [deg] (type:float) + stepperX_delta : StepperX last actuated delta angle [deg] (type:float) + stepperX_speed : StepperX current speed [rps] (type:float) + stepperY_pos : StepperY current position wrt the boot position [deg] (type:float) + stepperY_delta : StepperY last actuated delta angle [deg] (type:float) + stepperY_speed : StepperY current Speed [rps] (type:float) gps_latitude : Latitude [deg] (type:float) gps_longitude : Longitude [deg] (type:float) gps_height : Altitude [m] (type:float) gps_fix : Wether the GPS has a FIX (type:uint8_t) + main_radio_present : Boolean indicating the presence of the main radio (type:uint8_t) + main_packet_tx_error_count : Number of errors during send (type:uint16_t) + main_tx_bitrate : Send bitrate [b/s] (type:uint16_t) + main_packet_rx_success_count : Number of succesfull received mavlink packets (type:uint16_t) + main_packet_rx_drop_count : Number of dropped mavlink packets (type:uint16_t) + main_rx_bitrate : Receive bitrate [b/s] (type:uint16_t) + main_rx_rssi : Receive RSSI [dBm] (type:float) + ethernet_present : Boolean indicating the presence of the ethernet module (type:uint8_t) + ethernet_status : Status flag indicating the status of the ethernet PHY (type:uint8_t) + battery_voltage : Battery voltage [V] (type:float) ''' - return MAVLink_arp_tm_message(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix) + return MAVLink_arp_tm_message(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage) - def arp_tm_send(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, force_mavlink1=False): + def arp_tm_send(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage, force_mavlink1=False): ''' @@ -3956,19 +3976,29 @@ class MAVLink(object): roll : Current Roll [deg] (type:float) target_yaw : Target Yaw [deg] (type:float) target_pitch : Target Pitch [deg] (type:float) - stepperX_pos : StepperX current pos [deg] (type:float) - stepperX_delta : StepperX actuated delta [deg] (type:float) - stepperX_speed : StepperX Speed [rps] (type:float) - stepperY_pos : StepperY current pos [deg] (type:float) - stepperY_delta : StepperY actuated delta [deg] (type:float) - stepperY_speed : StepperY Speed [rps] (type:float) + stepperX_pos : StepperX current position wrt the boot position [deg] (type:float) + stepperX_delta : StepperX last actuated delta angle [deg] (type:float) + stepperX_speed : StepperX current speed [rps] (type:float) + stepperY_pos : StepperY current position wrt the boot position [deg] (type:float) + stepperY_delta : StepperY last actuated delta angle [deg] (type:float) + stepperY_speed : StepperY current Speed [rps] (type:float) gps_latitude : Latitude [deg] (type:float) gps_longitude : Longitude [deg] (type:float) gps_height : Altitude [m] (type:float) gps_fix : Wether the GPS has a FIX (type:uint8_t) + main_radio_present : Boolean indicating the presence of the main radio (type:uint8_t) + main_packet_tx_error_count : Number of errors during send (type:uint16_t) + main_tx_bitrate : Send bitrate [b/s] (type:uint16_t) + main_packet_rx_success_count : Number of succesfull received mavlink packets (type:uint16_t) + main_packet_rx_drop_count : Number of dropped mavlink packets (type:uint16_t) + main_rx_bitrate : Receive bitrate [b/s] (type:uint16_t) + main_rx_rssi : Receive RSSI [dBm] (type:float) + ethernet_present : Boolean indicating the presence of the ethernet module (type:uint8_t) + ethernet_status : Status flag indicating the status of the ethernet PHY (type:uint8_t) + battery_voltage : Battery voltage [V] (type:float) ''' - return self.send(self.arp_tm_encode(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix), force_mavlink1=force_mavlink1) + return self.send(self.arp_tm_encode(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage), force_mavlink1=force_mavlink1) def set_antenna_coordinates_arp_tc_encode(self, latitude, longitude): ''' diff --git a/mavlink_lib/lyra/lyra.h b/mavlink_lib/lyra/lyra.h index 856050d9a13f0c18e07ab1cc8cdf24f613283569..aa09b7c7ddfe2d4e25915f8465aa7e99a5496f9a 100644 --- a/mavlink_lib/lyra/lyra.h +++ b/mavlink_lib/lyra/lyra.h @@ -11,7 +11,7 @@ #endif #undef MAVLINK_THIS_XML_HASH -#define MAVLINK_THIS_XML_HASH -9018180599407197224 +#define MAVLINK_THIS_XML_HASH -6834851485668065312 #ifdef __cplusplus extern "C" { @@ -20,11 +20,11 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 60, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 65, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 29, 176, 163, 92, 76, 42, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 60, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 86, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 29, 176, 163, 92, 76, 42, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 180, 246, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 229, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 117, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 122, 202, 164, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 11, 214, 84, 245, 115, 63, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 180, 246, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 229, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 117, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 202, 164, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 11, 214, 84, 245, 115, 63, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #endif #include "../protocol.h" @@ -246,7 +246,7 @@ typedef enum PinsList #undef MAVLINK_THIS_XML_HASH -#define MAVLINK_THIS_XML_HASH -9018180599407197224 +#define MAVLINK_THIS_XML_HASH -6834851485668065312 #if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH # define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_ARP_TM, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} diff --git a/mavlink_lib/lyra/mavlink.h b/mavlink_lib/lyra/mavlink.h index e9d09c0ef3bfb71896445fb46316037314f1e22b..20de852be485f52799c1360308e7abec8122a18b 100644 --- a/mavlink_lib/lyra/mavlink.h +++ b/mavlink_lib/lyra/mavlink.h @@ -6,7 +6,7 @@ #ifndef MAVLINK_H #define MAVLINK_H -#define MAVLINK_PRIMARY_XML_HASH -9018180599407197224 +#define MAVLINK_PRIMARY_XML_HASH -6834851485668065312 #ifndef MAVLINK_STX #define MAVLINK_STX 254 diff --git a/mavlink_lib/lyra/mavlink_msg_arp_tm.h b/mavlink_lib/lyra/mavlink_msg_arp_tm.h index 388b3d7d8997287aa3f5208df85eef7507c01cb0..0a20a8023588f8961ac5fdb386c407d53d138200 100644 --- a/mavlink_lib/lyra/mavlink_msg_arp_tm.h +++ b/mavlink_lib/lyra/mavlink_msg_arp_tm.h @@ -11,25 +11,35 @@ typedef struct __mavlink_arp_tm_t { float roll; /*< [deg] Current Roll*/ float target_yaw; /*< [deg] Target Yaw*/ float target_pitch; /*< [deg] Target Pitch*/ - float stepperX_pos; /*< [deg] StepperX current pos*/ - float stepperX_delta; /*< [deg] StepperX actuated delta*/ - float stepperX_speed; /*< [rps] StepperX Speed*/ - float stepperY_pos; /*< [deg] StepperY current pos*/ - float stepperY_delta; /*< [deg] StepperY actuated delta*/ - float stepperY_speed; /*< [rps] StepperY Speed*/ + float stepperX_pos; /*< [deg] StepperX current position wrt the boot position*/ + float stepperX_delta; /*< [deg] StepperX last actuated delta angle*/ + float stepperX_speed; /*< [rps] StepperX current speed*/ + float stepperY_pos; /*< [deg] StepperY current position wrt the boot position*/ + float stepperY_delta; /*< [deg] StepperY last actuated delta angle*/ + float stepperY_speed; /*< [rps] StepperY current Speed*/ float gps_latitude; /*< [deg] Latitude*/ float gps_longitude; /*< [deg] Longitude*/ float gps_height; /*< [m] Altitude*/ + float main_rx_rssi; /*< [dBm] Receive RSSI*/ + float battery_voltage; /*< [V] Battery voltage*/ + uint16_t main_packet_tx_error_count; /*< Number of errors during send*/ + uint16_t main_tx_bitrate; /*< [b/s] Send bitrate*/ + uint16_t main_packet_rx_success_count; /*< Number of succesfull received mavlink packets*/ + uint16_t main_packet_rx_drop_count; /*< Number of dropped mavlink packets*/ + uint16_t main_rx_bitrate; /*< [b/s] Receive bitrate*/ uint8_t gps_fix; /*< Wether the GPS has a FIX*/ + uint8_t main_radio_present; /*< Boolean indicating the presence of the main radio*/ + uint8_t ethernet_present; /*< Boolean indicating the presence of the ethernet module*/ + uint8_t ethernet_status; /*< Status flag indicating the status of the ethernet PHY*/ } mavlink_arp_tm_t; -#define MAVLINK_MSG_ID_ARP_TM_LEN 65 -#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 65 -#define MAVLINK_MSG_ID_169_LEN 65 -#define MAVLINK_MSG_ID_169_MIN_LEN 65 +#define MAVLINK_MSG_ID_ARP_TM_LEN 86 +#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 86 +#define MAVLINK_MSG_ID_169_LEN 86 +#define MAVLINK_MSG_ID_169_MIN_LEN 86 -#define MAVLINK_MSG_ID_ARP_TM_CRC 122 -#define MAVLINK_MSG_ID_169_CRC 122 +#define MAVLINK_MSG_ID_ARP_TM_CRC 2 +#define MAVLINK_MSG_ID_169_CRC 2 @@ -37,7 +47,7 @@ typedef struct __mavlink_arp_tm_t { #define MAVLINK_MESSAGE_INFO_ARP_TM { \ 169, \ "ARP_TM", \ - 16, \ + 26, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \ @@ -53,13 +63,23 @@ typedef struct __mavlink_arp_tm_t { { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \ { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \ { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \ - { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_arp_tm_t, gps_fix) }, \ + { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_arp_tm_t, gps_fix) }, \ + { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_arp_tm_t, main_radio_present) }, \ + { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 72, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \ + { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 74, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \ + { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \ + { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \ + { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \ + { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, main_rx_rssi) }, \ + { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_arp_tm_t, ethernet_present) }, \ + { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_arp_tm_t, ethernet_status) }, \ + { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, battery_voltage) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_ARP_TM { \ "ARP_TM", \ - 16, \ + 26, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \ @@ -75,7 +95,17 @@ typedef struct __mavlink_arp_tm_t { { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \ { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \ { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \ - { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_arp_tm_t, gps_fix) }, \ + { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_arp_tm_t, gps_fix) }, \ + { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_arp_tm_t, main_radio_present) }, \ + { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 72, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \ + { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 74, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \ + { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \ + { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \ + { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \ + { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, main_rx_rssi) }, \ + { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_arp_tm_t, ethernet_present) }, \ + { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_arp_tm_t, ethernet_status) }, \ + { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, battery_voltage) }, \ } \ } #endif @@ -92,20 +122,30 @@ typedef struct __mavlink_arp_tm_t { * @param roll [deg] Current Roll * @param target_yaw [deg] Target Yaw * @param target_pitch [deg] Target Pitch - * @param stepperX_pos [deg] StepperX current pos - * @param stepperX_delta [deg] StepperX actuated delta - * @param stepperX_speed [rps] StepperX Speed - * @param stepperY_pos [deg] StepperY current pos - * @param stepperY_delta [deg] StepperY actuated delta - * @param stepperY_speed [rps] StepperY Speed + * @param stepperX_pos [deg] StepperX current position wrt the boot position + * @param stepperX_delta [deg] StepperX last actuated delta angle + * @param stepperX_speed [rps] StepperX current speed + * @param stepperY_pos [deg] StepperY current position wrt the boot position + * @param stepperY_delta [deg] StepperY last actuated delta angle + * @param stepperY_speed [rps] StepperY current Speed * @param gps_latitude [deg] Latitude * @param gps_longitude [deg] Longitude * @param gps_height [m] Altitude * @param gps_fix Wether the GPS has a FIX + * @param main_radio_present Boolean indicating the presence of the main radio + * @param main_packet_tx_error_count Number of errors during send + * @param main_tx_bitrate [b/s] Send bitrate + * @param main_packet_rx_success_count Number of succesfull received mavlink packets + * @param main_packet_rx_drop_count Number of dropped mavlink packets + * @param main_rx_bitrate [b/s] Receive bitrate + * @param main_rx_rssi [dBm] Receive RSSI + * @param ethernet_present Boolean indicating the presence of the ethernet module + * @param ethernet_status Status flag indicating the status of the ethernet PHY + * @param battery_voltage [V] Battery voltage * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix) + uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_ARP_TM_LEN]; @@ -124,7 +164,17 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon _mav_put_float(buf, 52, gps_latitude); _mav_put_float(buf, 56, gps_longitude); _mav_put_float(buf, 60, gps_height); - _mav_put_uint8_t(buf, 64, gps_fix); + _mav_put_float(buf, 64, main_rx_rssi); + _mav_put_float(buf, 68, battery_voltage); + _mav_put_uint16_t(buf, 72, main_packet_tx_error_count); + _mav_put_uint16_t(buf, 74, main_tx_bitrate); + _mav_put_uint16_t(buf, 76, main_packet_rx_success_count); + _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count); + _mav_put_uint16_t(buf, 80, main_rx_bitrate); + _mav_put_uint8_t(buf, 82, gps_fix); + _mav_put_uint8_t(buf, 83, main_radio_present); + _mav_put_uint8_t(buf, 84, ethernet_present); + _mav_put_uint8_t(buf, 85, ethernet_status); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN); #else @@ -144,7 +194,17 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon packet.gps_latitude = gps_latitude; packet.gps_longitude = gps_longitude; packet.gps_height = gps_height; + packet.main_rx_rssi = main_rx_rssi; + packet.battery_voltage = battery_voltage; + packet.main_packet_tx_error_count = main_packet_tx_error_count; + packet.main_tx_bitrate = main_tx_bitrate; + packet.main_packet_rx_success_count = main_packet_rx_success_count; + packet.main_packet_rx_drop_count = main_packet_rx_drop_count; + packet.main_rx_bitrate = main_rx_bitrate; packet.gps_fix = gps_fix; + packet.main_radio_present = main_radio_present; + packet.ethernet_present = ethernet_present; + packet.ethernet_status = ethernet_status; memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_TM_LEN); #endif @@ -165,21 +225,31 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon * @param roll [deg] Current Roll * @param target_yaw [deg] Target Yaw * @param target_pitch [deg] Target Pitch - * @param stepperX_pos [deg] StepperX current pos - * @param stepperX_delta [deg] StepperX actuated delta - * @param stepperX_speed [rps] StepperX Speed - * @param stepperY_pos [deg] StepperY current pos - * @param stepperY_delta [deg] StepperY actuated delta - * @param stepperY_speed [rps] StepperY Speed + * @param stepperX_pos [deg] StepperX current position wrt the boot position + * @param stepperX_delta [deg] StepperX last actuated delta angle + * @param stepperX_speed [rps] StepperX current speed + * @param stepperY_pos [deg] StepperY current position wrt the boot position + * @param stepperY_delta [deg] StepperY last actuated delta angle + * @param stepperY_speed [rps] StepperY current Speed * @param gps_latitude [deg] Latitude * @param gps_longitude [deg] Longitude * @param gps_height [m] Altitude * @param gps_fix Wether the GPS has a FIX + * @param main_radio_present Boolean indicating the presence of the main radio + * @param main_packet_tx_error_count Number of errors during send + * @param main_tx_bitrate [b/s] Send bitrate + * @param main_packet_rx_success_count Number of succesfull received mavlink packets + * @param main_packet_rx_drop_count Number of dropped mavlink packets + * @param main_rx_bitrate [b/s] Receive bitrate + * @param main_rx_rssi [dBm] Receive RSSI + * @param ethernet_present Boolean indicating the presence of the ethernet module + * @param ethernet_status Status flag indicating the status of the ethernet PHY + * @param battery_voltage [V] Battery voltage * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint64_t timestamp,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float stepperX_pos,float stepperX_delta,float stepperX_speed,float stepperY_pos,float stepperY_delta,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix) + uint64_t timestamp,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float stepperX_pos,float stepperX_delta,float stepperX_speed,float stepperY_pos,float stepperY_delta,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_ARP_TM_LEN]; @@ -198,7 +268,17 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c _mav_put_float(buf, 52, gps_latitude); _mav_put_float(buf, 56, gps_longitude); _mav_put_float(buf, 60, gps_height); - _mav_put_uint8_t(buf, 64, gps_fix); + _mav_put_float(buf, 64, main_rx_rssi); + _mav_put_float(buf, 68, battery_voltage); + _mav_put_uint16_t(buf, 72, main_packet_tx_error_count); + _mav_put_uint16_t(buf, 74, main_tx_bitrate); + _mav_put_uint16_t(buf, 76, main_packet_rx_success_count); + _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count); + _mav_put_uint16_t(buf, 80, main_rx_bitrate); + _mav_put_uint8_t(buf, 82, gps_fix); + _mav_put_uint8_t(buf, 83, main_radio_present); + _mav_put_uint8_t(buf, 84, ethernet_present); + _mav_put_uint8_t(buf, 85, ethernet_status); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN); #else @@ -218,7 +298,17 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c packet.gps_latitude = gps_latitude; packet.gps_longitude = gps_longitude; packet.gps_height = gps_height; + packet.main_rx_rssi = main_rx_rssi; + packet.battery_voltage = battery_voltage; + packet.main_packet_tx_error_count = main_packet_tx_error_count; + packet.main_tx_bitrate = main_tx_bitrate; + packet.main_packet_rx_success_count = main_packet_rx_success_count; + packet.main_packet_rx_drop_count = main_packet_rx_drop_count; + packet.main_rx_bitrate = main_rx_bitrate; packet.gps_fix = gps_fix; + packet.main_radio_present = main_radio_present; + packet.ethernet_present = ethernet_present; + packet.ethernet_status = ethernet_status; memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_TM_LEN); #endif @@ -237,7 +327,7 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c */ static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm) { - return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix); + return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage); } /** @@ -251,7 +341,7 @@ static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t comp */ static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm) { - return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix); + return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage); } /** @@ -264,20 +354,30 @@ static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t * @param roll [deg] Current Roll * @param target_yaw [deg] Target Yaw * @param target_pitch [deg] Target Pitch - * @param stepperX_pos [deg] StepperX current pos - * @param stepperX_delta [deg] StepperX actuated delta - * @param stepperX_speed [rps] StepperX Speed - * @param stepperY_pos [deg] StepperY current pos - * @param stepperY_delta [deg] StepperY actuated delta - * @param stepperY_speed [rps] StepperY Speed + * @param stepperX_pos [deg] StepperX current position wrt the boot position + * @param stepperX_delta [deg] StepperX last actuated delta angle + * @param stepperX_speed [rps] StepperX current speed + * @param stepperY_pos [deg] StepperY current position wrt the boot position + * @param stepperY_delta [deg] StepperY last actuated delta angle + * @param stepperY_speed [rps] StepperY current Speed * @param gps_latitude [deg] Latitude * @param gps_longitude [deg] Longitude * @param gps_height [m] Altitude * @param gps_fix Wether the GPS has a FIX + * @param main_radio_present Boolean indicating the presence of the main radio + * @param main_packet_tx_error_count Number of errors during send + * @param main_tx_bitrate [b/s] Send bitrate + * @param main_packet_rx_success_count Number of succesfull received mavlink packets + * @param main_packet_rx_drop_count Number of dropped mavlink packets + * @param main_rx_bitrate [b/s] Receive bitrate + * @param main_rx_rssi [dBm] Receive RSSI + * @param ethernet_present Boolean indicating the presence of the ethernet module + * @param ethernet_status Status flag indicating the status of the ethernet PHY + * @param battery_voltage [V] Battery voltage */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix) +static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_ARP_TM_LEN]; @@ -296,7 +396,17 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time _mav_put_float(buf, 52, gps_latitude); _mav_put_float(buf, 56, gps_longitude); _mav_put_float(buf, 60, gps_height); - _mav_put_uint8_t(buf, 64, gps_fix); + _mav_put_float(buf, 64, main_rx_rssi); + _mav_put_float(buf, 68, battery_voltage); + _mav_put_uint16_t(buf, 72, main_packet_tx_error_count); + _mav_put_uint16_t(buf, 74, main_tx_bitrate); + _mav_put_uint16_t(buf, 76, main_packet_rx_success_count); + _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count); + _mav_put_uint16_t(buf, 80, main_rx_bitrate); + _mav_put_uint8_t(buf, 82, gps_fix); + _mav_put_uint8_t(buf, 83, main_radio_present); + _mav_put_uint8_t(buf, 84, ethernet_present); + _mav_put_uint8_t(buf, 85, ethernet_status); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC); #else @@ -316,7 +426,17 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time packet.gps_latitude = gps_latitude; packet.gps_longitude = gps_longitude; packet.gps_height = gps_height; + packet.main_rx_rssi = main_rx_rssi; + packet.battery_voltage = battery_voltage; + packet.main_packet_tx_error_count = main_packet_tx_error_count; + packet.main_tx_bitrate = main_tx_bitrate; + packet.main_packet_rx_success_count = main_packet_rx_success_count; + packet.main_packet_rx_drop_count = main_packet_rx_drop_count; + packet.main_rx_bitrate = main_rx_bitrate; packet.gps_fix = gps_fix; + packet.main_radio_present = main_radio_present; + packet.ethernet_present = ethernet_present; + packet.ethernet_status = ethernet_status; _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)&packet, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC); #endif @@ -330,7 +450,7 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time static inline void mavlink_msg_arp_tm_send_struct(mavlink_channel_t chan, const mavlink_arp_tm_t* arp_tm) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix); + mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage); #else _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)arp_tm, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC); #endif @@ -344,7 +464,7 @@ static inline void mavlink_msg_arp_tm_send_struct(mavlink_channel_t chan, const is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix) +static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -363,7 +483,17 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin _mav_put_float(buf, 52, gps_latitude); _mav_put_float(buf, 56, gps_longitude); _mav_put_float(buf, 60, gps_height); - _mav_put_uint8_t(buf, 64, gps_fix); + _mav_put_float(buf, 64, main_rx_rssi); + _mav_put_float(buf, 68, battery_voltage); + _mav_put_uint16_t(buf, 72, main_packet_tx_error_count); + _mav_put_uint16_t(buf, 74, main_tx_bitrate); + _mav_put_uint16_t(buf, 76, main_packet_rx_success_count); + _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count); + _mav_put_uint16_t(buf, 80, main_rx_bitrate); + _mav_put_uint8_t(buf, 82, gps_fix); + _mav_put_uint8_t(buf, 83, main_radio_present); + _mav_put_uint8_t(buf, 84, ethernet_present); + _mav_put_uint8_t(buf, 85, ethernet_status); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC); #else @@ -383,7 +513,17 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin packet->gps_latitude = gps_latitude; packet->gps_longitude = gps_longitude; packet->gps_height = gps_height; + packet->main_rx_rssi = main_rx_rssi; + packet->battery_voltage = battery_voltage; + packet->main_packet_tx_error_count = main_packet_tx_error_count; + packet->main_tx_bitrate = main_tx_bitrate; + packet->main_packet_rx_success_count = main_packet_rx_success_count; + packet->main_packet_rx_drop_count = main_packet_rx_drop_count; + packet->main_rx_bitrate = main_rx_bitrate; packet->gps_fix = gps_fix; + packet->main_radio_present = main_radio_present; + packet->ethernet_present = ethernet_present; + packet->ethernet_status = ethernet_status; _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)packet, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC); #endif @@ -458,7 +598,7 @@ static inline float mavlink_msg_arp_tm_get_target_pitch(const mavlink_message_t* /** * @brief Get field stepperX_pos from arp_tm message * - * @return [deg] StepperX current pos + * @return [deg] StepperX current position wrt the boot position */ static inline float mavlink_msg_arp_tm_get_stepperX_pos(const mavlink_message_t* msg) { @@ -468,7 +608,7 @@ static inline float mavlink_msg_arp_tm_get_stepperX_pos(const mavlink_message_t* /** * @brief Get field stepperX_delta from arp_tm message * - * @return [deg] StepperX actuated delta + * @return [deg] StepperX last actuated delta angle */ static inline float mavlink_msg_arp_tm_get_stepperX_delta(const mavlink_message_t* msg) { @@ -478,7 +618,7 @@ static inline float mavlink_msg_arp_tm_get_stepperX_delta(const mavlink_message_ /** * @brief Get field stepperX_speed from arp_tm message * - * @return [rps] StepperX Speed + * @return [rps] StepperX current speed */ static inline float mavlink_msg_arp_tm_get_stepperX_speed(const mavlink_message_t* msg) { @@ -488,7 +628,7 @@ static inline float mavlink_msg_arp_tm_get_stepperX_speed(const mavlink_message_ /** * @brief Get field stepperY_pos from arp_tm message * - * @return [deg] StepperY current pos + * @return [deg] StepperY current position wrt the boot position */ static inline float mavlink_msg_arp_tm_get_stepperY_pos(const mavlink_message_t* msg) { @@ -498,7 +638,7 @@ static inline float mavlink_msg_arp_tm_get_stepperY_pos(const mavlink_message_t* /** * @brief Get field stepperY_delta from arp_tm message * - * @return [deg] StepperY actuated delta + * @return [deg] StepperY last actuated delta angle */ static inline float mavlink_msg_arp_tm_get_stepperY_delta(const mavlink_message_t* msg) { @@ -508,7 +648,7 @@ static inline float mavlink_msg_arp_tm_get_stepperY_delta(const mavlink_message_ /** * @brief Get field stepperY_speed from arp_tm message * - * @return [rps] StepperY Speed + * @return [rps] StepperY current Speed */ static inline float mavlink_msg_arp_tm_get_stepperY_speed(const mavlink_message_t* msg) { @@ -552,7 +692,107 @@ static inline float mavlink_msg_arp_tm_get_gps_height(const mavlink_message_t* m */ static inline uint8_t mavlink_msg_arp_tm_get_gps_fix(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 64); + return _MAV_RETURN_uint8_t(msg, 82); +} + +/** + * @brief Get field main_radio_present from arp_tm message + * + * @return Boolean indicating the presence of the main radio + */ +static inline uint8_t mavlink_msg_arp_tm_get_main_radio_present(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 83); +} + +/** + * @brief Get field main_packet_tx_error_count from arp_tm message + * + * @return Number of errors during send + */ +static inline uint16_t mavlink_msg_arp_tm_get_main_packet_tx_error_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 72); +} + +/** + * @brief Get field main_tx_bitrate from arp_tm message + * + * @return [b/s] Send bitrate + */ +static inline uint16_t mavlink_msg_arp_tm_get_main_tx_bitrate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 74); +} + +/** + * @brief Get field main_packet_rx_success_count from arp_tm message + * + * @return Number of succesfull received mavlink packets + */ +static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_success_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 76); +} + +/** + * @brief Get field main_packet_rx_drop_count from arp_tm message + * + * @return Number of dropped mavlink packets + */ +static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_drop_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 78); +} + +/** + * @brief Get field main_rx_bitrate from arp_tm message + * + * @return [b/s] Receive bitrate + */ +static inline uint16_t mavlink_msg_arp_tm_get_main_rx_bitrate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 80); +} + +/** + * @brief Get field main_rx_rssi from arp_tm message + * + * @return [dBm] Receive RSSI + */ +static inline float mavlink_msg_arp_tm_get_main_rx_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 64); +} + +/** + * @brief Get field ethernet_present from arp_tm message + * + * @return Boolean indicating the presence of the ethernet module + */ +static inline uint8_t mavlink_msg_arp_tm_get_ethernet_present(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 84); +} + +/** + * @brief Get field ethernet_status from arp_tm message + * + * @return Status flag indicating the status of the ethernet PHY + */ +static inline uint8_t mavlink_msg_arp_tm_get_ethernet_status(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 85); +} + +/** + * @brief Get field battery_voltage from arp_tm message + * + * @return [V] Battery voltage + */ +static inline float mavlink_msg_arp_tm_get_battery_voltage(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 68); } /** @@ -579,7 +819,17 @@ static inline void mavlink_msg_arp_tm_decode(const mavlink_message_t* msg, mavli arp_tm->gps_latitude = mavlink_msg_arp_tm_get_gps_latitude(msg); arp_tm->gps_longitude = mavlink_msg_arp_tm_get_gps_longitude(msg); arp_tm->gps_height = mavlink_msg_arp_tm_get_gps_height(msg); + arp_tm->main_rx_rssi = mavlink_msg_arp_tm_get_main_rx_rssi(msg); + arp_tm->battery_voltage = mavlink_msg_arp_tm_get_battery_voltage(msg); + arp_tm->main_packet_tx_error_count = mavlink_msg_arp_tm_get_main_packet_tx_error_count(msg); + arp_tm->main_tx_bitrate = mavlink_msg_arp_tm_get_main_tx_bitrate(msg); + arp_tm->main_packet_rx_success_count = mavlink_msg_arp_tm_get_main_packet_rx_success_count(msg); + arp_tm->main_packet_rx_drop_count = mavlink_msg_arp_tm_get_main_packet_rx_drop_count(msg); + arp_tm->main_rx_bitrate = mavlink_msg_arp_tm_get_main_rx_bitrate(msg); arp_tm->gps_fix = mavlink_msg_arp_tm_get_gps_fix(msg); + arp_tm->main_radio_present = mavlink_msg_arp_tm_get_main_radio_present(msg); + arp_tm->ethernet_present = mavlink_msg_arp_tm_get_ethernet_present(msg); + arp_tm->ethernet_status = mavlink_msg_arp_tm_get_ethernet_status(msg); #else uint8_t len = msg->len < MAVLINK_MSG_ID_ARP_TM_LEN? msg->len : MAVLINK_MSG_ID_ARP_TM_LEN; memset(arp_tm, 0, MAVLINK_MSG_ID_ARP_TM_LEN); diff --git a/mavlink_lib/lyra/testsuite.h b/mavlink_lib/lyra/testsuite.h index 37e460f282e2b05b61ff731fd7ff31ab137c35a6..cc485ecebc1914107c152c22331824516ca1683c 100644 --- a/mavlink_lib/lyra/testsuite.h +++ b/mavlink_lib/lyra/testsuite.h @@ -2311,7 +2311,7 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_arp_tm_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,197 + 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,20979,21083,21187,21291,21395,123,190,1,68 }; mavlink_arp_tm_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2330,7 +2330,17 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink packet1.gps_latitude = packet_in.gps_latitude; packet1.gps_longitude = packet_in.gps_longitude; packet1.gps_height = packet_in.gps_height; + packet1.main_rx_rssi = packet_in.main_rx_rssi; + packet1.battery_voltage = packet_in.battery_voltage; + packet1.main_packet_tx_error_count = packet_in.main_packet_tx_error_count; + packet1.main_tx_bitrate = packet_in.main_tx_bitrate; + packet1.main_packet_rx_success_count = packet_in.main_packet_rx_success_count; + packet1.main_packet_rx_drop_count = packet_in.main_packet_rx_drop_count; + packet1.main_rx_bitrate = packet_in.main_rx_bitrate; packet1.gps_fix = packet_in.gps_fix; + packet1.main_radio_present = packet_in.main_radio_present; + packet1.ethernet_present = packet_in.ethernet_present; + packet1.ethernet_status = packet_in.ethernet_status; #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 @@ -2345,12 +2355,12 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix ); + mavlink_msg_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage ); mavlink_msg_arp_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix ); + mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage ); mavlink_msg_arp_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -2363,7 +2373,7 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix ); + mavlink_msg_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage ); mavlink_msg_arp_tm_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); diff --git a/mavlink_lib/lyra/version.h b/mavlink_lib/lyra/version.h index b53ba52bd18e3a1db05542f25c65594211306357..3eba20e8566c37c8f5823d77a2ed5b11049235d7 100644 --- a/mavlink_lib/lyra/version.h +++ b/mavlink_lib/lyra/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Dec 04 2023" +#define MAVLINK_BUILD_DATE "Sun Dec 10 2023" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 176 diff --git a/message_definitions/lyra.xml b/message_definitions/lyra.xml index 013b0004130b58cc156a974aa4d70f75b54c27cf..e2a924657e91af449a680481b2a3123c92089aa1 100644 --- a/message_definitions/lyra.xml +++ b/message_definitions/lyra.xml @@ -490,6 +490,16 @@ <field name="gps_longitude" type="float" units="deg">Longitude</field> <field name="gps_height" type="float" units="m">Altitude</field> <field name="gps_fix" type="uint8_t">Wether the GPS has a FIX</field> + <field name="main_radio_present" type="uint8_t">Boolean indicating the presence of the main radio</field> + <field name="main_packet_tx_error_count" type="uint16_t">Number of errors during send</field> + <field name="main_tx_bitrate" type="uint16_t" units="b/s">Send bitrate</field> + <field name="main_packet_rx_success_count" type="uint16_t">Number of succesfull received mavlink packets</field> + <field name="main_packet_rx_drop_count" type="uint16_t">Number of dropped mavlink packets</field> + <field name="main_rx_bitrate" type="uint16_t" units="b/s">Receive bitrate</field> + <field name="main_rx_rssi" type="float" units="dBm">Receive RSSI</field> + <field name="ethernet_present" type="uint8_t">Boolean indicating the presence of the ethernet module</field> + <field name="ethernet_status" type="uint8_t">Status flag indicating the status of the ethernet PHY</field> + <field name="battery_voltage" type="float" units="V">Battery voltage</field> </message> <message id="170" name="SET_ANTENNA_COORDINATES_ARP_TC"> <description>Sets current antennas coordinates</description>