diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 91804cd69fde9e96601007bf5e1dc15048496c5d..484404ae8e370b5ba355c082c56e160b55a41c8b 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -705,9 +705,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) } break; // EXECUTE OPERATOR ACTIONS - case MAVLINK_MSG_ID_COMMAND_SHORT: { - mavlink_command_short_t action; - mavlink_msg_command_short_decode(&msg, &action); + case MAVLINK_MSG_ID_COMMAND_LONG: { + mavlink_command_long_t action; + mavlink_msg_command_long_decode(&msg, &action); qDebug() << "SIM" << "received action" << action.command << "for system" << action.target_system; diff --git a/src/comm/MAVLinkSimulationWaypointPlanner.cc b/src/comm/MAVLinkSimulationWaypointPlanner.cc index e1b794a3583807f788106b55427a5afe2bc373c7..a53f17c5d974f930d15017ef95f894b3b6f6293e 100644 --- a/src/comm/MAVLinkSimulationWaypointPlanner.cc +++ b/src/comm/MAVLinkSimulationWaypointPlanner.cc @@ -815,10 +815,10 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* break; } - case MAVLINK_MSG_ID_COMMAND_SHORT: + case MAVLINK_MSG_ID_COMMAND_LONG: { // special action from ground station - mavlink_command_short_t action; - mavlink_msg_command_short_decode(msg, &action); + mavlink_command_long_t action; + mavlink_msg_command_long_decode(msg, &action); if(action.target_system == systemid) { if (verbose) qDebug("Waypoint: received message with action %d\n", action.command); // switch (action.action) { diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc index 538c3e226af11135376706c93adecf798482ab65..703e09f6382c1210e208bb29a78b65262e02d11c 100644 --- a/src/ui/MAVLinkDecoder.cc +++ b/src/ui/MAVLinkDecoder.cc @@ -12,7 +12,6 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false); messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false); messageFilter.insert(MAVLINK_MSG_ID_STATUSTEXT, false); - messageFilter.insert(MAVLINK_MSG_ID_COMMAND_SHORT, false); messageFilter.insert(MAVLINK_MSG_ID_COMMAND_LONG, false); messageFilter.insert(MAVLINK_MSG_ID_COMMAND_ACK, false); messageFilter.insert(MAVLINK_MSG_ID_PARAM_SET, false);