diff --git a/libs/mavlink-skyward-lib b/libs/mavlink-skyward-lib index 132a3522b41e20947f216c95c67909be54a1d6fe..de06e61ed14af989716122ae5adf4e487e565c14 160000 --- a/libs/mavlink-skyward-lib +++ b/libs/mavlink-skyward-lib @@ -1 +1 @@ -Subproject commit 132a3522b41e20947f216c95c67909be54a1d6fe +Subproject commit de06e61ed14af989716122ae5adf4e487e565c14 diff --git a/src/shared/Modules/CommandPad/MessagesList.h b/src/shared/Modules/CommandPad/MessagesList.h index 57ae63d73ef3ebd863ddd687dc36de913d199778..75630297cc4b607b1b6eff82cac8dde06a22acbf 100644 --- a/src/shared/Modules/CommandPad/MessagesList.h +++ b/src/shared/Modules/CommandPad/MessagesList.h @@ -27,24 +27,26 @@ namespace MessagesList { -static const QStringList messagesList{ - "PING_TC", - "COMMAND_TC", - "SYSTEM_TM_REQUEST_TC", - "SENSOR_TM_REQUEST_TC", - "SERVO_TM_REQUEST_TC", - "SET_SERVO_ANGLE_TC", - "WIGGLE_SERVO_TC", - "RESET_SERVO_TC", - "SET_REFERENCE_ALTITUDE_TC", - "SET_REFERENCE_TEMPERATURE_TC", - "SET_ORIENTATION_TC", - "SET_COORDINATES_TC", - "RAW_EVENT_TC", - "SET_DEPLOYMENT_ALTITUDE_TC", - "SET_TARGET_COORDINATES_TC", - "SET_ALGORITHM_TC", -}; +static const QStringList messagesList{"PING_TC", + "COMMAND_TC", + "SYSTEM_TM_REQUEST_TC", + "SENSOR_TM_REQUEST_TC", + "SERVO_TM_REQUEST_TC", + "SET_SERVO_ANGLE_TC", + "WIGGLE_SERVO_TC", + "RESET_SERVO_TC", + "SET_REFERENCE_ALTITUDE_TC", + "SET_REFERENCE_TEMPERATURE_TC", + "SET_ORIENTATION_TC", + "SET_COORDINATES_TC", + "RAW_EVENT_TC", + "SET_DEPLOYMENT_ALTITUDE_TC", + "SET_TARGET_COORDINATES_TC", + "SET_ALGORITHM_TC", + "SET_ATOMIC_VALVE_TIMING_TC", + "SET_VALVE_MAXIMUM_APERTURE_TC", + "SET_IGNITION_TIME_TC", + "CONRIG_STATE_TC"}; static const QMap<QString, int> systemTmList{ {"MAV_SYS_ID", MAV_SYS_ID}, @@ -59,7 +61,9 @@ static const QMap<QString, int> systemTmList{ {"MAV_FLIGHT_ID", MAV_FLIGHT_ID}, {"MAV_STATS_ID", MAV_STATS_ID}, {"MAV_SENSORS_STATE_ID", MAV_SENSORS_STATE_ID}, -}; + {"MAV_GSE_ID", MAV_GSE_ID}, + {"MAV_MOTOR_ID", MAV_MOTOR_ID}, + {"MAV_TARS_ID", MAV_TARS_ID}}; static const QMap<QString, int> sensorsList{ {"MAV_GPS_ID", MAV_GPS_ID}, @@ -76,33 +80,49 @@ static const QMap<QString, int> sensorsList{ {"MAV_PITOT_PRESS_ID", MAV_PITOT_PRESS_ID}, {"MAV_BATTERY_VOLTAGE_ID", MAV_BATTERY_VOLTAGE_ID}, {"MAV_LOAD_CELL_ID", MAV_LOAD_CELL_ID}, -}; + {"MAV_FILLING_PRESS_ID", MAV_FILLING_PRESS_ID}, + {"MAV_VESSEL_PRESS_ID", MAV_VESSEL_PRESS_ID}, + {"MAV_TANK_TOP_PRESS_ID", MAV_TANK_TOP_PRESS_ID}, + {"MAV_TANK_BOTTOM_PRESS_ID", MAV_TANK_BOTTOM_PRESS_ID}, + {"MAV_TANK_TEMP_ID", MAV_TANK_TEMP_ID}, + {"MAV_COMBUSTION_PRESS_ID", MAV_COMBUSTION_PRESS_ID}, + {"MAV_LOAD_CELL_VESSEL_ID", MAV_LOAD_CELL_VESSEL_ID}, + {"MAV_LOAD_CELL_TANK_ID", MAV_LOAD_CELL_TANK_ID}, + {"MAV_LIS2MDL_ID", MAV_LIS2MDL_ID}, + {"MAV_LPS28DFW_ID", MAV_LPS28DFW_ID}, + {"MAV_LSM6DSRX_ID", MAV_LSM6DSRX_ID}, + {"MAV_H3LIS331DL_ID", MAV_H3LIS331DL_ID}, + {"MAV_LPS22DF_ID", MAV_LPS22DF_ID}}; static const QMap<QString, int> commandsList{ {"MAV_CMD_ARM", MAV_CMD_ARM}, {"MAV_CMD_DISARM", MAV_CMD_DISARM}, {"MAV_CMD_CALIBRATE", MAV_CMD_CALIBRATE}, + {"MAV_CMD_SAVE_CALIBRATION", MAV_CMD_SAVE_CALIBRATION}, {"MAV_CMD_FORCE_INIT", MAV_CMD_FORCE_INIT}, {"MAV_CMD_FORCE_LAUNCH", MAV_CMD_FORCE_LAUNCH}, {"MAV_CMD_FORCE_LANDING", MAV_CMD_FORCE_LANDING}, {"MAV_CMD_FORCE_APOGEE", MAV_CMD_FORCE_APOGEE}, {"MAV_CMD_FORCE_EXPULSION", MAV_CMD_FORCE_EXPULSION}, - {"MAV_CMD_FORCE_MAIN", MAV_CMD_FORCE_MAIN}, + {"MAV_CMD_FORCE_MAIN", MAV_CMD_FORCE_DEPLOYMENT}, {"MAV_CMD_START_LOGGING", MAV_CMD_START_LOGGING}, {"MAV_CMD_STOP_LOGGING", MAV_CMD_STOP_LOGGING}, {"MAV_CMD_FORCE_REBOOT", MAV_CMD_FORCE_REBOOT}, {"MAV_CMD_ENTER_TEST_MODE", MAV_CMD_ENTER_TEST_MODE}, {"MAV_CMD_EXIT_TEST_MODE", MAV_CMD_EXIT_TEST_MODE}, {"MAV_CMD_START_RECORDING", MAV_CMD_START_RECORDING}, - {"MAV_CMD_STOP_RECORDING", MAV_CMD_STOP_RECORDING}, -}; + {"MAV_CMD_STOP_RECORDING", MAV_CMD_STOP_RECORDING}}; const QMap<QString, int> servosList{ {"AIR_BRAKES_SERVO", AIR_BRAKES_SERVO}, {"EXPULSION_SERVO", EXPULSION_SERVO}, {"PARAFOIL_LEFT_SERVO", PARAFOIL_LEFT_SERVO}, {"PARAFOIL_RIGHT_SERVO", PARAFOIL_RIGHT_SERVO}, -}; + {"MAIN_VALVE", MAIN_VALVE}, + {"VENTING_VALVE", VENTING_VALVE}, + {"RELEASE_VALVE", RELEASE_VALVE}, + {"FILLING_VALVE", FILLING_VALVE}, + {"DISCONNECT_SERVO", DISCONNECT_SERVO}}; inline void fillMessagesMap(QMap<QString, MessageFormElement *> &formElements) { @@ -176,6 +196,30 @@ inline void fillMessagesMap(QMap<QString, MessageFormElement *> &formElements) element = new MessageFormElement(); element->addInteger("algorithm_number", "Algorithm:", 0, 999); formElements["SET_ALGORITHM_TC"] = element; + + element = new MessageFormElement(); + element->addComboBox("servo_id", "Servo:", servosList); + element->addInteger("maximum_timing", "Timing [ms]:", 0, 3600000); + formElements["SET_ATOMIC_VALVE_TIMING_TC"] = element; + + element = new MessageFormElement(); + element->addComboBox("servo_id", "Servo:", servosList); + element->addFloat("maximum_aperture", "Aperture [0-1]:", 0, 1); + formElements["SET_VALVE_MAXIMUM_APERTURE_TC"] = element; + + element = new MessageFormElement(); + element->addInteger("timing", "Timing [ms]:", 0, 3600000); + formElements["SET_IGNITION_TIME_TC"] = element; + + element = new MessageFormElement(); + element->addInteger("ignition_btn", "Ignition:", 0, 1); + element->addInteger("filling_valve_btn", "Filling:", 0, 1); + element->addInteger("venting_valve_btn", "Venting:", 0, 1); + element->addInteger("release_pressure_btn", "Release:", 0, 1); + element->addInteger("quick_connector_btn", "Quick connector:", 0, 1); + element->addInteger("start_tars_btn", "Tars:", 0, 1); + element->addInteger("arm_switch", "Arm:", 0, 1); + formElements["CONRIG_STATE_TC"] = element; } -} // namespace MessagesList \ No newline at end of file +} // namespace MessagesList