mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: clarify and simplify RC failsafe messages
This commit is contained in:
parent
f10f3da159
commit
c8bc0b7e0d
@ -21,7 +21,7 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
|||||||
failsafe.state = fstype;
|
failsafe.state = fstype;
|
||||||
failsafe.short_timer_ms = millis();
|
failsafe.short_timer_ms = millis();
|
||||||
failsafe.saved_mode_number = control_mode->mode_number();
|
failsafe.saved_mode_number = control_mode->mode_number();
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Short event on: type=%u/reason=%u", fstype, static_cast<unsigned>(reason));
|
gcs().send_text(MAV_SEVERITY_WARNING, "RC Short Failsafe On");
|
||||||
switch (control_mode->mode_number())
|
switch (control_mode->mode_number())
|
||||||
{
|
{
|
||||||
case Mode::Number::MANUAL:
|
case Mode::Number::MANUAL:
|
||||||
@ -102,7 +102,12 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
|||||||
void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason)
|
void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason)
|
||||||
{
|
{
|
||||||
// This is how to handle a long loss of control signal failsafe.
|
// This is how to handle a long loss of control signal failsafe.
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Long event on: type=%u/reason=%u", fstype, static_cast<unsigned>(reason));
|
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
|
// If the GCS is locked up we allow control to revert to RC
|
||||||
RC_Channels::clear_overrides();
|
RC_Channels::clear_overrides();
|
||||||
failsafe.state = fstype;
|
failsafe.state = fstype;
|
||||||
@ -186,7 +191,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
|
|||||||
void Plane::failsafe_short_off_event(ModeReason reason)
|
void Plane::failsafe_short_off_event(ModeReason reason)
|
||||||
{
|
{
|
||||||
// We're back in radio contact
|
// We're back in radio contact
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Short event off: reason=%u", static_cast<unsigned>(reason));
|
gcs().send_text(MAV_SEVERITY_WARNING, "Short Failsafe Cleared");
|
||||||
failsafe.state = FAILSAFE_NONE;
|
failsafe.state = FAILSAFE_NONE;
|
||||||
//restore entry mode if desired but check that our current mode is still due to failsafe
|
//restore entry mode if desired but check that our current mode is still due to failsafe
|
||||||
if ( _last_reason == ModeReason::RADIO_FAILSAFE) {
|
if ( _last_reason == ModeReason::RADIO_FAILSAFE) {
|
||||||
@ -197,8 +202,13 @@ void Plane::failsafe_short_off_event(ModeReason reason)
|
|||||||
|
|
||||||
void Plane::failsafe_long_off_event(ModeReason reason)
|
void Plane::failsafe_long_off_event(ModeReason reason)
|
||||||
{
|
{
|
||||||
// We're back in radio contact
|
// We're back in radio contact with RC or GCS
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Long event off: reason=%u", static_cast<unsigned>(reason));
|
if (reason == ModeReason:: GCS_FAILSAFE) {
|
||||||
|
gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe Off");
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
gcs().send_text(MAV_SEVERITY_WARNING, "RC Long Failsafe Cleared");
|
||||||
|
}
|
||||||
failsafe.state = FAILSAFE_NONE;
|
failsafe.state = FAILSAFE_NONE;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -280,7 +280,7 @@ void Plane::control_failsafe()
|
|||||||
// throttle has dropped below the mark
|
// throttle has dropped below the mark
|
||||||
failsafe.throttle_counter++;
|
failsafe.throttle_counter++;
|
||||||
if (failsafe.throttle_counter == 10) {
|
if (failsafe.throttle_counter == 10) {
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe on");
|
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe %s", "on");
|
||||||
failsafe.rc_failsafe = true;
|
failsafe.rc_failsafe = true;
|
||||||
AP_Notify::flags.failsafe_radio = true;
|
AP_Notify::flags.failsafe_radio = true;
|
||||||
}
|
}
|
||||||
@ -295,7 +295,7 @@ void Plane::control_failsafe()
|
|||||||
failsafe.throttle_counter = 3;
|
failsafe.throttle_counter = 3;
|
||||||
}
|
}
|
||||||
if (failsafe.throttle_counter == 1) {
|
if (failsafe.throttle_counter == 1) {
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe off");
|
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe %s", "off");
|
||||||
} else if(failsafe.throttle_counter == 0) {
|
} else if(failsafe.throttle_counter == 0) {
|
||||||
failsafe.rc_failsafe = false;
|
failsafe.rc_failsafe = false;
|
||||||
AP_Notify::flags.failsafe_radio = false;
|
AP_Notify::flags.failsafe_radio = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user