From a6206bde3c86f0b568dc9d1ea0a17aa316106151 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 24 Oct 2023 02:41:37 +0100 Subject: [PATCH] Plane: move to new `using_airspeed_sensor` ahrs method --- ArduPlane/Attitude.cpp | 2 +- ArduPlane/quadplane.cpp | 2 +- ArduPlane/radio.cpp | 2 +- ArduPlane/servos.cpp | 4 ++-- ArduPlane/takeoff.cpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 39a9461ea6..3c59d8a315 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -49,7 +49,7 @@ float Plane::calc_speed_scaler(void) // no speed estimate and not armed, use a unit scaling speed_scaler = 1; } - if (!plane.ahrs.airspeed_sensor_enabled() && + if (!plane.ahrs.using_airspeed_sensor() && (plane.flight_option_enabled(FlightOptions::SURPRESS_TKOFF_SCALING)) && (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) { //scaling is suppressed during climb phase of automatic takeoffs with no airspeed sensor being used due to problems with inaccurate airspeed estimates return MIN(speed_scaler, 1.0f) ; diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index fbb1b3c9fe..839d76b92d 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1475,7 +1475,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed) // assistance due to Q_ASSIST_SPEED // if option bit is enabled only allow assist with real airspeed sensor if ((have_airspeed && aspeed < assist_speed) && - (!option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || ahrs.airspeed_sensor_enabled())) { + (!option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || ahrs.using_airspeed_sensor())) { in_angle_assist = false; angle_error_start_ms = 0; return true; diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index cb7e68ff22..68ee2cb998 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -196,7 +196,7 @@ void Plane::read_radio() && channel_throttle->get_control_in() > 50 && stickmixing) { float nudge = (channel_throttle->get_control_in() - 50) * 0.02f; - if (ahrs.airspeed_sensor_enabled()) { + if (ahrs.using_airspeed_sensor()) { airspeed_nudge_cm = (aparm.airspeed_max * 100 - aparm.airspeed_cruise_cm) * nudge; } else { throttle_nudge = (aparm.throttle_max - aparm.throttle_cruise) * nudge; diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index ced4252578..d193a678e9 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -134,7 +134,7 @@ bool Plane::suppress_throttle(void) // require 5m/s. This prevents throttle up due to spiky GPS // groundspeed with bad GPS reception #if AP_AIRSPEED_ENABLED - if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) { + if ((!ahrs.using_airspeed_sensor()) || airspeed.get_airspeed() >= 5) { // we're moving at more than 5 m/s throttle_suppressed = false; return false; @@ -605,7 +605,7 @@ void Plane::set_servos_flaps(void) if (control_mode->does_auto_throttle()) { int16_t flapSpeedSource = 0; - if (ahrs.airspeed_sensor_enabled()) { + if (ahrs.using_airspeed_sensor()) { flapSpeedSource = target_airspeed_cm * 0.01f; } else { flapSpeedSource = aparm.throttle_cruise; diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 5574ad2c9b..ce2264f8c8 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -185,7 +185,7 @@ void Plane::takeoff_calc_pitch(void) return; } - if (ahrs.airspeed_sensor_enabled()) { + if (ahrs.using_airspeed_sensor()) { int16_t takeoff_pitch_min_cd = get_takeoff_pitch_min_cd(); calc_nav_pitch(); if (nav_pitch_cd < takeoff_pitch_min_cd) {