Skip to content
Snippets Groups Projects
Commit 3301e719 authored by Davide Mor's avatar Davide Mor Committed by Alberto Nidasio
Browse files

[Mavlink] Updated GS with updated Lyra mavlink

parent b977301f
No related branches found
No related tags found
No related merge requests found
Subproject commit b4c2b98d38a0d15049b7fc9afcfb615aea2403a1
Subproject commit 314bb59188ccd68155cc61391fe4d75a7178a59e
......@@ -38,6 +38,7 @@ static const QStringList messagesList{"PING_TC",
"SET_REFERENCE_ALTITUDE_TC",
"SET_REFERENCE_TEMPERATURE_TC",
"SET_ORIENTATION_TC",
"SET_ORIENTATION_QUAT_TC",
"SET_COORDINATES_TC",
"RAW_EVENT_TC",
"SET_DEPLOYMENT_ALTITUDE_TC",
......@@ -46,18 +47,20 @@ static const QStringList messagesList{"PING_TC",
"SET_ATOMIC_VALVE_TIMING_TC",
"SET_VALVE_MAXIMUM_APERTURE_TC",
"SET_IGNITION_TIME_TC",
"SET_NITROGEN_TIME_TC",
"SET_COOLING_TIME_TC",
"CONRIG_STATE_TC"};
static const QMap<QString, int> systemTmList{
{"MAV_SYS_ID", MAV_SYS_ID},
{"MAV_FSM_ID", MAV_FSM_ID},
{"MAV_PIN_OBS_ID", MAV_PIN_OBS_ID},
{"MAV_LOGGER_ID", MAV_LOGGER_ID},
{"MAV_MAVLINK_STATS", MAV_MAVLINK_STATS},
{"MAV_MAVLINK_STATS_ID", MAV_MAVLINK_STATS_ID},
{"MAV_TASK_STATS_ID", MAV_TASK_STATS_ID},
{"MAV_ADA_ID", MAV_ADA_ID},
{"MAV_NAS_ID", MAV_NAS_ID},
{"MAV_CAN_ID", MAV_CAN_ID},
{"MAV_MEA_ID", MAV_MEA_ID},
{"MAV_CAN_STATS_ID", MAV_CAN_STATS_ID},
{"MAV_FLIGHT_ID", MAV_FLIGHT_ID},
{"MAV_STATS_ID", MAV_STATS_ID},
{"MAV_SENSORS_STATE_ID", MAV_SENSORS_STATE_ID},
......@@ -66,33 +69,37 @@ static const QMap<QString, int> systemTmList{
{"MAV_REGISTRY_ID", MAV_REGISTRY_ID}};
static const QMap<QString, int> sensorsList{
{"MAV_GPS_ID", MAV_GPS_ID},
{"MAV_BMX160_ID", MAV_BMX160_ID},
{"MAV_VN100_ID", MAV_VN100_ID},
{"MAV_MPU9250_ID", MAV_MPU9250_ID},
{"MAV_ADS_ID", MAV_ADS_ID},
{"MAV_ADS131M08_ID", MAV_ADS131M08_ID},
{"MAV_MS5803_ID", MAV_MS5803_ID},
{"MAV_BME280_ID", MAV_BME280_ID},
{"MAV_CURRENT_SENSE_ID", MAV_CURRENT_SENSE_ID},
{"MAV_LIS3MDL_ID", MAV_LIS3MDL_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},
{"MAV_GPS_ID", MAV_GPS_ID},
{"MAV_CURRENT_SENSE_ID", MAV_CURRENT_SENSE_ID},
{"MAV_BATTERY_VOLTAGE_ID", MAV_BATTERY_VOLTAGE_ID},
{"MAV_ROTATED_IMU_ID", MAV_ROTATED_IMU_ID},
{"MAV_DPL_PRESS_ID", MAV_DPL_PRESS_ID},
{"MAV_STATIC_PRESS_ID", MAV_STATIC_PRESS_ID},
{"MAV_PITOT_PRESS_ID", MAV_PITOT_PRESS_ID},
{"MAV_BATTERY_VOLTAGE_ID", MAV_BATTERY_VOLTAGE_ID},
{"MAV_BACKUP_STATIC_PRESS_ID", MAV_BACKUP_STATIC_PRESS_ID},
{"MAV_STATIC_PITOT_PRESS_ID", MAV_STATIC_PITOT_PRESS_ID},
{"MAV_TOTAL_PITOT_PRESS_ID", MAV_TOTAL_PITOT_PRESS_ID},
{"MAV_DYNAMIC_PITOT_PRESS_ID", MAV_DYNAMIC_PITOT_PRESS_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_FILLING_PRESS_ID", MAV_FILLING_PRESS_ID},
{"MAV_VESSEL_PRESS_ID", MAV_VESSEL_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}};
{"MAV_LOAD_CELL_TANK_ID", MAV_LOAD_CELL_TANK_ID}};
static const QMap<QString, int> commandsList{
{"MAV_CMD_ARM", MAV_CMD_ARM},
......@@ -101,10 +108,10 @@ static const QMap<QString, int> commandsList{
{"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_ENGINE_SHUTDOWN", MAV_CMD_FORCE_ENGINE_SHUTDOWN},
{"MAV_CMD_FORCE_EXPULSION", MAV_CMD_FORCE_EXPULSION},
{"MAV_CMD_FORCE_MAIN", MAV_CMD_FORCE_DEPLOYMENT},
{"MAV_CMD_FORCE_DEPLOYMENT", MAV_CMD_FORCE_DEPLOYMENT},
{"MAV_CMD_FORCE_LANDING", MAV_CMD_FORCE_LANDING},
{"MAV_CMD_START_LOGGING", MAV_CMD_START_LOGGING},
{"MAV_CMD_STOP_LOGGING", MAV_CMD_STOP_LOGGING},
{"MAV_CMD_FORCE_REBOOT", MAV_CMD_FORCE_REBOOT},
......@@ -115,7 +122,8 @@ static const QMap<QString, int> commandsList{
{"MAV_CMD_OPEN_NITROGEN", MAV_CMD_OPEN_NITROGEN},
{"MAV_CMD_REGISTRY_LOAD", MAV_CMD_REGISTRY_LOAD},
{"MAV_CMD_REGISTRY_SAVE", MAV_CMD_REGISTRY_SAVE},
{"MAV_CMD_REGISTRY_CLEAR", MAV_CMD_REGISTRY_CLEAR}};
{"MAV_CMD_REGISTRY_CLEAR", MAV_CMD_REGISTRY_CLEAR},
{"MAV_CMD_ENTER_HIL", MAV_CMD_ENTER_HIL}};
const QMap<QString, int> servosList{
{"AIR_BRAKES_SERVO", AIR_BRAKES_SERVO},
......@@ -178,6 +186,13 @@ inline void fillMessagesMap(QMap<QString, MessageFormElement *> &formElements)
element->addFloat("roll", "Roll:", -180, 180, 2);
formElements["SET_ORIENTATION_TC"] = element;
element = new MessageFormElement();
element->addFloat("quat_x", "Quat X:", 0, 1, 2);
element->addFloat("quat_y", "Quat Y:", 0, 1, 2);
element->addFloat("quat_z", "Quat Z:", 0, 1, 2);
element->addFloat("quat_w", "Quat W:", 0, 1, 2);
formElements["SET_ORIENTATION_QUAT_TC"] = element;
element = new MessageFormElement();
element->addFloat("latitude", "Latitude:", -90, 90, 6);
element->addFloat("longitude", "Longitude:", -90, 90, 6);
......@@ -215,6 +230,14 @@ inline void fillMessagesMap(QMap<QString, MessageFormElement *> &formElements)
element->addInteger("timing", "Timing [ms]:", 0, 3600000);
formElements["SET_IGNITION_TIME_TC"] = element;
element = new MessageFormElement();
element->addInteger("timing", "Timing [ms]:", 0, 3600000);
formElements["SET_NITROGEN_TIME_TC"] = element;
element = new MessageFormElement();
element->addInteger("timing", "Timing [ms]:", 0, 3600000);
formElements["SET_COOLING_TIME_TC"] = element;
element = new MessageFormElement();
element->addInteger("ignition_btn", "Ignition:", 0, 1);
element->addInteger("filling_valve_btn", "Filling:", 0, 1);
......
......@@ -318,12 +318,6 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId,
sysId, compId, &output, msg.getField("ref_temp").getDouble());
return true;
}
else if (messageName == "SET_DEPLOYMENT_ALTITUDE_TC")
{
mavlink_msg_set_deployment_altitude_tc_pack(
sysId, compId, &output, msg.getField("dpl_altitude").getDouble());
return true;
}
else if (messageName == "SET_ORIENTATION_TC")
{
mavlink_msg_set_orientation_tc_pack(sysId, compId, &output,
......@@ -332,6 +326,15 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId,
msg.getField("roll").getDouble());
return true;
}
else if (messageName == "SET_ORIENTATION_QUAT_TC")
{
mavlink_msg_set_orientation_quat_tc_pack(
sysId, compId, &output, msg.getField("quat_x").getDouble(),
msg.getField("quat_y").getDouble(),
msg.getField("quat_z").getDouble(),
msg.getField("quat_w").getDouble());
return true;
}
else if (messageName == "SET_COORDINATES_TC")
{
mavlink_msg_set_coordinates_tc_pack(
......@@ -347,6 +350,12 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId,
msg.getField("event_id").getUnsignedInteger());
return true;
}
else if (messageName == "SET_DEPLOYMENT_ALTITUDE_TC")
{
mavlink_msg_set_deployment_altitude_tc_pack(
sysId, compId, &output, msg.getField("dpl_altitude").getDouble());
return true;
}
else if (messageName == "SET_TARGET_COORDINATES_TC")
{
mavlink_msg_set_target_coordinates_tc_pack(
......@@ -384,6 +393,20 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId,
msg.getField("timing").getUnsignedInteger());
return true;
}
else if (messageName == "SET_NITROGEN_TIME_TC")
{
mavlink_msg_set_nitrogen_time_tc_pack(
sysId, compId, &output,
msg.getField("timing").getUnsignedInteger());
return true;
}
else if (messageName == "SET_COOLING_TIME_TC")
{
mavlink_msg_set_cooling_time_tc_pack(
sysId, compId, &output,
msg.getField("timing").getUnsignedInteger());
return true;
}
else if (messageName == "CONRIG_STATE_TC")
{
mavlink_msg_conrig_state_tc_pack(
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment