GCS_MAVLink: move use of AP_AHRS_NAVEKF_AVAILABLE into cpp file

This is defined in AP_AHRS which we only get transitively in the header
This commit is contained in:
Peter Barker 2019-07-09 20:47:04 +10:00 committed by Peter Barker
parent 9f33fb6085
commit 6cb8fcc466
2 changed files with 2 additions and 4 deletions

View File

@ -420,9 +420,7 @@ public:
virtual void send_simstate() const; virtual void send_simstate() const;
void send_ahrs(); void send_ahrs();
void send_battery2(); void send_battery2();
#if AP_AHRS_NAVEKF_AVAILABLE
void send_opticalflow(); void send_opticalflow();
#endif
virtual void send_attitude() const; virtual void send_attitude() const;
void send_autopilot_version() const; void send_autopilot_version() const;
void send_extended_sys_state() const; void send_extended_sys_state() const;

View File

@ -2368,12 +2368,12 @@ MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32
return result; return result;
} }
#if AP_AHRS_NAVEKF_AVAILABLE
/* /*
send OPTICAL_FLOW message send OPTICAL_FLOW message
*/ */
void GCS_MAVLINK::send_opticalflow() void GCS_MAVLINK::send_opticalflow()
{ {
#if AP_AHRS_NAVEKF_AVAILABLE
const OpticalFlow *optflow = AP::opticalflow(); const OpticalFlow *optflow = AP::opticalflow();
// exit immediately if no optical flow sensor or not healthy // exit immediately if no optical flow sensor or not healthy
@ -2407,8 +2407,8 @@ void GCS_MAVLINK::send_opticalflow()
hagl, // ground distance (in meters) set to zero hagl, // ground distance (in meters) set to zero
flowRate.x, flowRate.x,
flowRate.y); flowRate.y);
}
#endif #endif
}
/* /*
send AUTOPILOT_VERSION packet send AUTOPILOT_VERSION packet