Browse Source

Plane: Fix redundant call to SpdHgt_Controller->get_land_airspeed()

c415-sdk
Michael du Breuil 5 years ago committed by Andrew Tridgell
parent
commit
99ad126986
  1. 4
      ArduPlane/navigation.cpp

4
ArduPlane/navigation.cpp

@ -160,9 +160,9 @@ void Plane::calc_airspeed_errors() @@ -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;

Loading…
Cancel
Save