mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
Plane: Fix redundant call to SpdHgt_Controller->get_land_airspeed()
This commit is contained in:
parent
b3d755d018
commit
99ad126986
@ -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…
Reference in New Issue
Block a user