diff --git a/Modules/CommandPad/commandpad.cpp b/Modules/CommandPad/commandpad.cpp index 3ad65a420cc8ce64f5133c933c54926721369b41..59af9eba265a1973e8ce83fd26355d91604f26e6 100644 --- a/Modules/CommandPad/commandpad.cpp +++ b/Modules/CommandPad/commandpad.cpp @@ -9,7 +9,6 @@ const QMap<QString, uint8_t> CommandPad::systemTMList { { "MAV_LOGGER_ID", 4 }, { "MAV_MAVLINK_STATS", 5 }, { "MAV_TASK_STATS_ID", 6 }, - { "MAV_DPL_ID", 7 }, { "MAV_ADA_ID", 8 }, { "MAV_NAS_ID", 9 }, { "MAV_CAN_ID", 10 }, @@ -25,13 +24,14 @@ const QMap<QString, uint8_t> CommandPad::sensorsTMList = { { "MAV_MPU9250_ID", 4 }, { "MAV_ADS_ID", 5 }, { "MAV_MS5803_ID", 6 }, - { "MAV_CURRENT_SENSE_ID", 7 }, - { "MAV_LIS3MDL_ID", 8 }, - { "MAV_DPL_PRESS_ID", 9 }, - { "MAV_STATIC_PRESS_ID", 10 }, - { "MAV_PITOT_PRESS_ID", 11 }, - { "MAV_BATTERY_VOLTAGE_ID", 12 }, - { "MAV_STRAIN_GAUGE_ID", 13 }, + { "MAV_BME280_ID", 7 }, + { "MAV_CURRENT_SENSE_ID", 8 }, + { "MAV_LIS3MDL_ID", 9 }, + { "MAV_DPL_PRESS_ID", 10 }, + { "MAV_STATIC_PRESS_ID", 11 }, + { "MAV_PITOT_PRESS_ID", 12 }, + { "MAV_BATTERY_VOLTAGE_ID", 13 }, + { "MAV_STRAIN_GAUGE_ID", 14 }, }; const QMap<QString, uint8_t> CommandPad::mavCommandList = { @@ -180,6 +180,13 @@ void CommandPad::setupUi() { _CMD_UINT8_PROP(rawEvent, topic_id) _CMD_UINT8_PROP(rawEvent, event_id) _CMD_END + _CMD(setTargetCoordinates, "SET_TARGET_COORDINATES_TC") + _CMD_FLOAT_PROP(setTargetCoordinates, latitude) + _CMD_FLOAT_PROP(setTargetCoordinates, longitude) + _CMD_END + _CMD(setAlgorithm, "SET_ALGORITHM_TC") + _CMD_UINT8_PROP(setAlgorithm, algorithm_number) + _CMD_END QPushButton* send = new QPushButton(tr("Send")); connect(send, &QPushButton::clicked, [ = ]() { @@ -226,6 +233,13 @@ void CommandPad::setupUi() { _SEND_UINT8_PROP(rawEvent, topic_id) _SEND_UINT8_PROP(rawEvent, event_id) _SEND_END + _SEND(setTargetCoordinates, "SET_TARGET_COORDINATES_TC") + _SEND_FLOAT_PROP(setTargetCoordinates, latitude) + _SEND_FLOAT_PROP(setTargetCoordinates, longitude) + _SEND_END + _SEND(setAlgorithm, "SET_ALGORITHM_TC") + _SEND_UINT8_PROP(setAlgorithm, algorithm_number) + _SEND_END }); QVBoxLayout* layout = new QVBoxLayout; diff --git a/Modules/Mavlink/mavlinkcommandadapter.cpp b/Modules/Mavlink/mavlinkcommandadapter.cpp index 55f885c557e4c440ca3f0e59d67677f8864c8d5a..09932533161601f69e1c35cd5bc3cae74dddad63 100644 --- a/Modules/Mavlink/mavlinkcommandadapter.cpp +++ b/Modules/Mavlink/mavlinkcommandadapter.cpp @@ -58,6 +58,12 @@ bool MavlinkCommandAdapter::encodeCommand(const ModuleMessage& msg, mavlink_mess } else if(messageName == "RAW_EVENT_TC") { mavlink_msg_raw_event_tc_pack(MAV_SYS, MAV_CMP, &output, msg.getField("topic_id").getUInteger(0), msg.getField("event_id").getUInteger(0)); return true; + } else if(messageName == "SET_TARGET_COORDINATES_TC") { + mavlink_msg_set_target_coordinates_tc_pack(MAV_SYS, MAV_CMP, &output, msg.getField("latitude").getDouble(0.0), msg.getField("longitude").getDouble(0.0)); + return true; + } else if(messageName == "SET_ALGORITHM_TC") { + mavlink_msg_set_algorithm_tc_pack(MAV_SYS, MAV_CMP, &output, msg.getField("algorithm_number").getUInteger(0)); + return true; } return false; }