AP_Landing: set FW landing speed if not set

This commit is contained in:
Henry Wurzburg 2023-06-25 14:35:45 -05:00 committed by Andrew Tridgell
parent 87b2000d5c
commit c33ef034b4

View File

@ -346,26 +346,24 @@ int32_t AP_Landing::type_slope_get_target_airspeed_cm(void)
const float land_airspeed = tecs_Controller->get_land_airspeed(); const float land_airspeed = tecs_Controller->get_land_airspeed();
int32_t target_airspeed_cm = aparm.airspeed_cruise_cm; int32_t target_airspeed_cm = aparm.airspeed_cruise_cm;
switch (type_slope_stage) {
case SlopeStage::APPROACH:
if (land_airspeed >= 0) { if (land_airspeed >= 0) {
target_airspeed_cm = land_airspeed * 100; target_airspeed_cm = land_airspeed * 100;
} else {
target_airspeed_cm = 0.5 * (aparm.airspeed_cruise_cm * 0.01 + aparm.airspeed_min);
} }
switch (type_slope_stage) {
case SlopeStage::NORMAL:
target_airspeed_cm = aparm.airspeed_cruise_cm;
break;
case SlopeStage::APPROACH:
break; break;
case SlopeStage::PREFLARE: case SlopeStage::PREFLARE:
case SlopeStage::FINAL: case SlopeStage::FINAL:
if (pre_flare_airspeed > 0) { if (pre_flare_airspeed > 0) {
// if we just preflared then continue using the pre-flare airspeed during final flare // if we just preflared then continue using the pre-flare airspeed during final flare
target_airspeed_cm = pre_flare_airspeed * 100; target_airspeed_cm = pre_flare_airspeed * 100;
} else if (land_airspeed >= 0) {
target_airspeed_cm = land_airspeed * 100;
} }
break; break;
default:
break;
} }
// when landing, add half of head-wind. // when landing, add half of head-wind.