From 8b497cc61d8b1a037d98e74d0afb96f9d3e1c520 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Mon, 31 Dec 2012 13:32:27 +0900 Subject: [PATCH] ArduCopter: log watchdog event to dataflash --- ArduCopter/defines.h | 5 +++-- ArduCopter/events.pde | 4 ++-- ArduCopter/failsafe.pde | 3 ++- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index abb485250d..47d2b68ce6 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -446,8 +446,9 @@ enum gcs_severity { // subsystem specific error codes -- radio #define ERROR_CODE_RADIO_LATE_FRAME 2 // subsystem specific error codes -- failsafe -#define ERROR_CODE_RADIO_FAILSAFE_THROTTLE 2 -#define ERROR_CODE_RADIO_FAILSAFE_BATTERY 3 +#define ERROR_CODE_FAILSAFE_THROTTLE 2 +#define ERROR_CODE_FAILSAFE_BATTERY 3 +#define ERROR_CODE_FAILSAFE_WATCHDOG 4 diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde index 7a7f4e3260..7b189af963 100644 --- a/ArduCopter/events.pde +++ b/ArduCopter/events.pde @@ -48,7 +48,7 @@ static void failsafe_on_event() } // log the error to the dataflash - Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE, ERROR_CODE_RADIO_FAILSAFE_THROTTLE); + Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE, ERROR_CODE_FAILSAFE_THROTTLE); } @@ -95,7 +95,7 @@ static void low_battery_event(void) // warn the ground station and log to dataflash gcs_send_text_P(SEVERITY_LOW,PSTR("Low Battery!")); - Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE, ERROR_CODE_RADIO_FAILSAFE_BATTERY); + Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE, ERROR_CODE_FAILSAFE_BATTERY); #if COPTER_LEDS == ENABLED if ( bitRead(g.copter_leds_mode, 3) ) { // Only Activate if a battery is connected to avoid alarm on USB only diff --git a/ArduCopter/failsafe.pde b/ArduCopter/failsafe.pde index c39dc7d9c1..09dfb51859 100644 --- a/ArduCopter/failsafe.pde +++ b/ArduCopter/failsafe.pde @@ -48,13 +48,14 @@ void failsafe_check(uint32_t tnow) in_failsafe = true; } - if (in_failsafe && tnow - failsafe_last_timestamp > 1000000) { + if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) { // disarm motors every second failsafe_last_timestamp = tnow; if(motors.armed()) { motors.armed(false); set_armed(true); motors.output(); + Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE, ERROR_CODE_FAILSAFE_WATCHDOG); } } } \ No newline at end of file