mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: mode_thermal: adjust messages to reference parameter names
This commit is contained in:
parent
0c381435cc
commit
5e5452cf73
@ -94,17 +94,17 @@ void ModeThermal::update_soaring()
|
||||
// Heading lined up and loiter status not good to continue. Need to restore previous mode.
|
||||
switch (loiterStatus) {
|
||||
case SoaringController::LoiterStatus::ALT_TOO_HIGH:
|
||||
restore_mode("Too high", ModeReason::SOARING_ALT_TOO_HIGH);
|
||||
restore_mode("Reached SOAR_ALT_MAX", ModeReason::SOARING_ALT_TOO_HIGH);
|
||||
break;
|
||||
case SoaringController::LoiterStatus::ALT_TOO_LOW:
|
||||
restore_mode("Too low", ModeReason::SOARING_ALT_TOO_LOW);
|
||||
restore_mode("Reached SOAR_ALT_MIN", ModeReason::SOARING_ALT_TOO_LOW);
|
||||
break;
|
||||
default:
|
||||
case SoaringController::LoiterStatus::THERMAL_WEAK:
|
||||
restore_mode("Thermal ended", ModeReason::SOARING_THERMAL_ESTIMATE_DETERIORATED);
|
||||
restore_mode("Climb below SOAR_VSPEED", ModeReason::SOARING_THERMAL_ESTIMATE_DETERIORATED);
|
||||
break;
|
||||
case SoaringController::LoiterStatus::DRIFT_EXCEEDED:
|
||||
restore_mode("Drifted too far", ModeReason::SOARING_DRIFT_EXCEEDED);
|
||||
restore_mode("Reached SOAR_MAX_DRIFT", ModeReason::SOARING_DRIFT_EXCEEDED);
|
||||
break;
|
||||
case SoaringController::LoiterStatus::EXIT_COMMANDED:
|
||||
restore_mode("Exit via RC switch", ModeReason::RC_COMMAND);
|
||||
|
Loading…
Reference in New Issue
Block a user