mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Events: consolodate failsafe evnt to single print
This commit is contained in:
parent
ed642df063
commit
3a4e07a73c
@ -24,7 +24,6 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
||||
failsafe.state = fstype;
|
||||
failsafe.short_timer_ms = millis();
|
||||
failsafe.saved_mode_number = control_mode->mode_number();
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "RC Short Failsafe On");
|
||||
switch (control_mode->mode_number())
|
||||
{
|
||||
case Mode::Number::MANUAL:
|
||||
@ -46,7 +45,6 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
||||
} else {
|
||||
set_mode(mode_circle, reason); // circle if action = 0 or 1
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Flight mode = %s", control_mode->name());
|
||||
break;
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
@ -64,7 +62,6 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
||||
} else {
|
||||
set_mode(mode_qland, reason);
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Flight mode = %s", control_mode->name());
|
||||
break;
|
||||
#endif // HAL_QUADPLANE_ENABLED
|
||||
|
||||
@ -88,7 +85,6 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
||||
} else {
|
||||
set_mode(mode_circle, reason);
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Flight mode = %s", control_mode->name());
|
||||
}
|
||||
break;
|
||||
case Mode::Number::CIRCLE: // these modes never take any short failsafe action and continue
|
||||
@ -102,17 +98,16 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
||||
case Mode::Number::INITIALISING:
|
||||
break;
|
||||
}
|
||||
if (failsafe.saved_mode_number != control_mode->mode_number()) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "RC Short Failsafe: switched to %s", control_mode->name());
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "RC Short Failsafe On");
|
||||
}
|
||||
}
|
||||
|
||||
void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason)
|
||||
{
|
||||
// This is how to handle a long loss of control signal failsafe.
|
||||
if (reason == ModeReason:: GCS_FAILSAFE) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe On");
|
||||
}
|
||||
else {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "RC Long Failsafe On");
|
||||
}
|
||||
// If the GCS is locked up we allow control to revert to RC
|
||||
RC_Channels::clear_overrides();
|
||||
failsafe.state = fstype;
|
||||
@ -192,7 +187,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
|
||||
case Mode::Number::INITIALISING:
|
||||
break;
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Flight mode = %s", control_mode->name());
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe On: %s", (reason == ModeReason:: GCS_FAILSAFE) ? "GCS" : "RC Long", control_mode->name());
|
||||
}
|
||||
|
||||
void Plane::failsafe_short_off_event(ModeReason reason)
|
||||
|
Loading…
Reference in New Issue
Block a user