diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index fa23641f83..4343eb5de1 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1215,7 +1215,7 @@ static void handle_auto_mode(void) // allowed for level flight nav_roll_cd = constrain_int32(nav_roll_cd, -g.level_roll_limit*100UL, g.level_roll_limit*100UL); } else { - if (!airspeed.use()) { + if (!ahrs.airspeed_sensor_enabled()) { // when not under airspeed control, don't allow // down pitch in landing nav_pitch_cd = constrain_int32(nav_pitch_cd, 0, nav_pitch_cd); diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 6266040b4d..9d360ab44f 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -558,7 +558,7 @@ static bool is_flying(void) bool gpsMovement = (gps.status() < AP_GPS::GPS_OK_FIX_2D || gps.ground_speed() >= 5); - bool airspeedMovement = !airspeed.use() || airspeed.get_airspeed() >= 5; + bool airspeedMovement = (!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5; // we're more than 5m from the home altitude bool inAir = relative_altitude_abs_cm() > 500; @@ -614,7 +614,7 @@ static bool suppress_throttle(void) // if we have an airspeed sensor, then check it too, and // require 5m/s. This prevents throttle up due to spiky GPS // groundspeed with bad GPS reception - if (!airspeed.use() || airspeed.get_airspeed() >= 5) { + if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) { // we're moving at more than 5 m/s throttle_suppressed = false; return false; @@ -869,7 +869,7 @@ static void set_servos(void) if (auto_throttle_mode) { int16_t flapSpeedSource = 0; - if (airspeed.use()) { + if (ahrs.airspeed_sensor_enabled()) { flapSpeedSource = target_airspeed_cm * 0.01f; } else { flapSpeedSource = aparm.throttle_cruise; diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index dfe0c6682c..5313f9c67d 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -163,7 +163,7 @@ static void read_radio() if (g.throttle_nudge && channel_throttle->servo_out > 50) { float nudge = (channel_throttle->servo_out - 50) * 0.02f; - if (airspeed.use()) { + if (ahrs.airspeed_sensor_enabled()) { airspeed_nudge_cm = (aparm.airspeed_max * 100 - g.airspeed_cruise_cm) * nudge; } else { throttle_nudge = (aparm.throttle_max - aparm.throttle_cruise) * nudge; diff --git a/ArduPlane/takeoff.pde b/ArduPlane/takeoff.pde index 54f83951f2..d0fd0005ac 100644 --- a/ArduPlane/takeoff.pde +++ b/ArduPlane/takeoff.pde @@ -115,7 +115,7 @@ static void takeoff_calc_pitch(void) return; } - if (airspeed.use()) { + if (ahrs.airspeed_sensor_enabled()) { calc_nav_pitch(); if (nav_pitch_cd < auto_state.takeoff_pitch_cd) { nav_pitch_cd = auto_state.takeoff_pitch_cd;