diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 6606753672..7746d76181 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2414,7 +2414,7 @@ MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32 */ void GCS_MAVLINK::send_opticalflow() { - const OpticalFlow *optflow = AP::opticalflow(); + const AP_OpticalFlow *optflow = AP::opticalflow(); // exit immediately if no optical flow sensor or not healthy if (optflow == nullptr || @@ -3510,7 +3510,7 @@ void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg) #if AP_OPTICALFLOW_ENABLED void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg) { - OpticalFlow *optflow = AP::opticalflow(); + AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow == nullptr) { return; }