Browse Source

AP_WindVane: add define AP_AIRSPEED_ENABLED

gps-1.3.1
Josh Henderson 3 years ago committed by Andrew Tridgell
parent
commit
0e662bbf35
  1. 2
      libraries/AP_WindVane/AP_WindVane_Airspeed.cpp

2
libraries/AP_WindVane/AP_WindVane_Airspeed.cpp

@ -17,8 +17,10 @@ @@ -17,8 +17,10 @@
void AP_WindVane_Airspeed::update_speed()
{
#if AP_AIRSPEED_ENABLED
const AP_Airspeed* airspeed = AP_Airspeed::get_singleton();
if (airspeed != nullptr) {
_frontend._speed_apparent_raw = airspeed->get_raw_airspeed();
}
#endif
}

Loading…
Cancel
Save