From d908d85129dc3db86093a99d1e6acbe7eda75afa Mon Sep 17 00:00:00 2001 From: Davide Mor <davide.mor@skywarder.eu> Date: Thu, 5 Sep 2024 12:53:57 +0000 Subject: [PATCH] [Mavlink] Update mavlink --- libs/mavlink-skyward-lib | 2 +- scripts/udp_gs_tester.py | 94 +++++++++----------- src/shared/Modules/CommandPad/MessagesList.h | 13 ++- src/shared/Modules/Mavlink/MavlinkCodec.cpp | 12 +++ 4 files changed, 68 insertions(+), 53 deletions(-) diff --git a/libs/mavlink-skyward-lib b/libs/mavlink-skyward-lib index afdea943..83b02b9a 160000 --- a/libs/mavlink-skyward-lib +++ b/libs/mavlink-skyward-lib @@ -1 +1 @@ -Subproject commit afdea9432a5844b1591c0fb90c17612cc7ea878c +Subproject commit 83b02b9af8adfe0d2d95b54dc3d16124cfc754b5 diff --git a/scripts/udp_gs_tester.py b/scripts/udp_gs_tester.py index 87fb0a14..0c4e0869 100755 --- a/scripts/udp_gs_tester.py +++ b/scripts/udp_gs_tester.py @@ -46,58 +46,50 @@ def get_timestamp(): def fake_data(i): return MAVLink_rocket_flight_tm_message( get_timestamp(), # timestamp - 0, # ada_state - i % 15, # fmm_state - 0, # dpl_state - 0, # abk_state - 0, # nas_state - 0, # mea_state - 0.0, # pressure_ada - 0.0, # pressure_digi - 0.0, # pressure_static - 0.0, # pressure_dpl - 0.0, # airspeed_pitot - 0.0, # altitude_agl - 0.0, # ada_vert_speed - 0.0, # mea_mass - i * 2, # acc_x - i * 3, # acc_y - i * 4, # acc_z - 0.0, # gyro_x - 0.0, # gyro_y - 0.0, # gyro_z - 0.0, # mag_x - 0.0, # mag_y - 0.0, # mag_z + 0, # pressure_ada + 0, # pressure_digi + 0, # pressure_static + 0, # pressure_dpl + 0, # airspeed_pitot + 0, # altitude_agl + 0, # ada_vert_speed + 0, # mea_mass + 0, # mea_apogee + 0, # acc_x + 0, # acc_y + 0, # acc_z + 0, # gyro_x + 0, # gyro_y + 0, # gyro_z + 0, # mag_x + 0, # mag_y + 0, # mag_z + 0, # vn100_qx + 0, # vn100_qy + 0, # vn100_qz + 0, # vn100_qw 0, # gps_fix - 0.0, # gps_lat - 0.0, # gps_lon - 0.0, # gps_alt - 0.0, # abk_angle - 0.0, # nas_n - 0.0, # nas_e - 0.0, # nas_d - 0.0, # nas_vn - 0.0, # nas_ve - 0.0, # nas_vd - 0.0, # nas_qx - 0.0, # nas_qy - 0.0, # nas_qz - 0.0, # nas_qw - 0.0, # nas_bias_x - 0.0, # nas_bias_y - 0.0, # nas_bias_z - 0, # pin_quick_connector - 0, # pin_launch - 0, # pin_nosecone - 0, # pin_expulsion - 0, # cutter_presence - 0.0, # battery_voltage - 0.0, # current_consumption - 0.0, # cam_battery_voltage - 0.0, # temperature - 0, # logger_error - + 0, # gps_lat + 0, # gps_lon + 0, # gps_alt + 0, # fmm_state + 0, # abk_angle + 0, # nas_n + 0, # nas_e + 0, # nas_d + 0, # nas_vn + 0, # nas_ve + 0, # nas_vd + 0, # nas_qx + 0, # nas_qy + 0, # nas_qz + 0, # nas_qw + 0, # nas_bias_x + 0, # nas_bias_y + 0, # nas_bias_z + 0, # battery_voltage + 0, # cam_battery_voltage + 0, # temperature ) def build_ack(msg): diff --git a/src/shared/Modules/CommandPad/MessagesList.h b/src/shared/Modules/CommandPad/MessagesList.h index 9c5f6dc7..9def5fed 100644 --- a/src/shared/Modules/CommandPad/MessagesList.h +++ b/src/shared/Modules/CommandPad/MessagesList.h @@ -55,6 +55,8 @@ static const QStringList messagesList{"PING_TC", "SET_IGNITION_TIME_TC", "SET_NITROGEN_TIME_TC", "SET_COOLING_TIME_TC", + "SET_INITIAL_MEA_MASS_TC", + "SET_CALIBRATION_PRESSURE_TC", "CONRIG_STATE_TC"}; static const QMap<QString, int> systemTmList{ @@ -73,7 +75,8 @@ static const QMap<QString, int> systemTmList{ {"MAV_GSE_ID", MAV_GSE_ID}, {"MAV_MOTOR_ID", MAV_MOTOR_ID}, {"MAV_REGISTRY_ID", MAV_REGISTRY_ID}, - {"MAV_REFERENCE_ID", MAV_REFERENCE_ID}}; + {"MAV_REFERENCE_ID", MAV_REFERENCE_ID}, + {"MAV_CALIBRATION_ID", MAV_CALIBRATION_ID}}; static const QMap<QString, int> sensorsList{ {"MAV_BMX160_ID", MAV_BMX160_ID}, @@ -319,6 +322,14 @@ inline void fillMessagesMap(QMap<QString, MessageFormElement *> &formElements) element->addFloat("longitude", "Longitude:", -90, 90, 6); element->addFloat("height", "Height:", 0, 9999, 6); formElements["SET_ROCKET_COORDINATES_ARP_TC"] = element; + + element = new MessageFormElement(); + element->addFloat("mass", "Mass:", 100, 100, 2); + formElements["SET_INITIAL_MEA_MASS_TC"] = element; + + element = new MessageFormElement(); + element->addFloat("pressure", "Pressure:", 0, 200000, 2); + formElements["SET_CALIBRATION_PRESSURE_TC"] = element; } } // namespace MessagesList diff --git a/src/shared/Modules/Mavlink/MavlinkCodec.cpp b/src/shared/Modules/Mavlink/MavlinkCodec.cpp index 33e3980f..122c642f 100644 --- a/src/shared/Modules/Mavlink/MavlinkCodec.cpp +++ b/src/shared/Modules/Mavlink/MavlinkCodec.cpp @@ -467,6 +467,18 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId, msg.getField("multiplier").getDouble()); return true; } + else if (messageName == "SET_CALIBRATION_PRESSURE_TC") + { + mavlink_msg_set_calibration_pressure_tc_pack( + sysId, compId, &output, msg.getField("pressure").getDouble()); + return true; + } + else if (messageName == "SET_INITIAL_MEA_MASS_TC") + { + mavlink_msg_set_calibration_pressure_tc_pack( + sysId, compId, &output, msg.getField("mass").getDouble()); + return true; + } return false; } -- GitLab