mirror of https://github.com/ArduPilot/ardupilot
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:
parent
9f33fb6085
commit
6cb8fcc466
|
@ -420,9 +420,7 @@ public:
|
|||
virtual void send_simstate() const;
|
||||
void send_ahrs();
|
||||
void send_battery2();
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
void send_opticalflow();
|
||||
#endif
|
||||
virtual void send_attitude() const;
|
||||
void send_autopilot_version() const;
|
||||
void send_extended_sys_state() const;
|
||||
|
|
|
@ -2368,12 +2368,12 @@ MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32
|
|||
return result;
|
||||
}
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
/*
|
||||
send OPTICAL_FLOW message
|
||||
*/
|
||||
void GCS_MAVLINK::send_opticalflow()
|
||||
{
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
const OpticalFlow *optflow = AP::opticalflow();
|
||||
|
||||
// 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
|
||||
flowRate.x,
|
||||
flowRate.y);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
send AUTOPILOT_VERSION packet
|
||||
|
|
Loading…
Reference in New Issue