From 99ad126986c3ea3dfea7a999d4ae093a6f284d53 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 30 Jul 2020 13:16:08 -0700 Subject: [PATCH] Plane: Fix redundant call to SpdHgt_Controller->get_land_airspeed() --- ArduPlane/navigation.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 428c5305b3..2dafc91c84 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -160,9 +160,9 @@ void Plane::calc_airspeed_errors() (quadplane.options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH) && ((vtol_approach_s.approach_stage == Landing_ApproachStage::APPROACH_LINE) || (vtol_approach_s.approach_stage == Landing_ApproachStage::VTOL_LANDING))) { - float land_airspeed = SpdHgt_Controller->get_land_airspeed(); + const float land_airspeed = SpdHgt_Controller->get_land_airspeed(); if (is_positive(land_airspeed)) { - target_airspeed_cm = SpdHgt_Controller->get_land_airspeed() * 100; + target_airspeed_cm = land_airspeed * 100; } else { // fallover to normal airspeed target_airspeed_cm = aparm.airspeed_cruise_cm;