Commit c2fe813e authored by pixhawk's avatar pixhawk

Fixed v10 compile errors;\

parent a81ecc23
......@@ -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;
......
......@@ -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) {
......
......@@ -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);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment