From 5ec1f95ee4cf79d2ef41dbe60b5d11db055689af Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Sun, 2 Feb 2020 00:29:53 +0900 Subject: [PATCH] Rover: display the type of failsafe on GCS --- APMrover2/Rover.cpp | 2 +- APMrover2/Rover.h | 2 +- APMrover2/failsafe.cpp | 6 +++--- APMrover2/radio.cpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index 444859b9c1..586294b5c2 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -205,7 +205,7 @@ void Rover::gcs_failsafe_check(void) } // check for updates from GCS within 2 seconds - failsafe_trigger(FAILSAFE_EVENT_GCS, failsafe.last_heartbeat_ms != 0 && (millis() - failsafe.last_heartbeat_ms) > 2000); + failsafe_trigger(FAILSAFE_EVENT_GCS, "GCS", failsafe.last_heartbeat_ms != 0 && (millis() - failsafe.last_heartbeat_ms) > 2000); } /* diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 082f766063..6c3db2b68a 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -319,7 +319,7 @@ private: void failsafe_ekf_off_event(void); // failsafe.cpp - void failsafe_trigger(uint8_t failsafe_type, bool on); + void failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool on); void handle_battery_failsafe(const char* type_str, const int8_t action); #if ADVANCED_FAILSAFE == ENABLED void afs_fs_check(void); diff --git a/APMrover2/failsafe.cpp b/APMrover2/failsafe.cpp index 574e282653..3df6e10848 100644 --- a/APMrover2/failsafe.cpp +++ b/APMrover2/failsafe.cpp @@ -45,7 +45,7 @@ void Rover::failsafe_check() /* called to set/unset a failsafe event. */ -void Rover::failsafe_trigger(uint8_t failsafe_type, bool on) +void Rover::failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool on) { uint8_t old_bits = failsafe.bits; if (on) { @@ -59,7 +59,7 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on) } if (failsafe.triggered != 0 && failsafe.bits == 0) { // a failsafe event has ended - gcs().send_text(MAV_SEVERITY_INFO, "Failsafe ended"); + gcs().send_text(MAV_SEVERITY_INFO, "%s Failsafe Cleared", type_str); } failsafe.triggered &= failsafe.bits; @@ -70,7 +70,7 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on) (control_mode != &mode_rtl) && ((control_mode != &mode_hold || (g2.fs_options & (uint32_t)Failsafe_Options::Failsafe_Option_Active_In_Hold)))) { failsafe.triggered = failsafe.bits; - gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe trigger 0x%x", (unsigned int)failsafe.triggered); + gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe", type_str); // clear rc overrides RC_Channels::clear_overrides(); diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 8f99b4092f..28b5edd8df 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -135,7 +135,7 @@ void Rover::radio_failsafe_check(uint16_t pwm) if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 500) { failed = true; } - failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed); + failsafe_trigger(FAILSAFE_EVENT_THROTTLE, "Radio", failed); } bool Rover::trim_radio()