Plane: use handle_common_message()

This commit is contained in:
Andrew Tridgell 2016-11-07 11:04:15 +11:00
parent da7ed73051
commit cb57945e9e

View File

@ -1564,12 +1564,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
{
handle_param_request_read(msg);
break;
}
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
{
handle_mission_clear_all(plane.mission, msg);
@ -2083,8 +2077,8 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
plane.adsb.handle_message(chan, msg);
break;
case MAVLINK_MSG_ID_SETUP_SIGNING:
handle_setup_signing(msg);
default:
handle_common_message(msg);
break;
} // end switch
} // end handle mavlink