diff --git a/libraries/AP_OSD/AP_OSD_ParamScreen.cpp b/libraries/AP_OSD/AP_OSD_ParamScreen.cpp index 4e25178439..5fdfccffe1 100644 --- a/libraries/AP_OSD/AP_OSD_ParamScreen.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamScreen.cpp @@ -26,9 +26,9 @@ #include #include #include -#include #include #include +#include extern const AP_HAL::HAL& hal; @@ -629,7 +629,7 @@ void AP_OSD_ParamScreen::save_parameters() // handle OSD configuration messages #if HAL_GCS_ENABLED -void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& packet, const GCS_MAVLINK& link) +void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& packet, const class GCS_MAVLINK& link) { // request out of range - return an error if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) { @@ -642,7 +642,7 @@ void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& pack } // handle OSD show configuration messages -void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t& packet, const GCS_MAVLINK& link) +void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t& packet, const class GCS_MAVLINK& link) { // request out of range - return an error if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) {