mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
ArduCopter: log watchdog event to dataflash
This commit is contained in:
parent
16f99ebcab
commit
2181ec2ab0
@ -435,8 +435,9 @@ enum gcs_severity {
|
|||||||
// subsystem specific error codes -- radio
|
// subsystem specific error codes -- radio
|
||||||
#define ERROR_CODE_RADIO_LATE_FRAME 2
|
#define ERROR_CODE_RADIO_LATE_FRAME 2
|
||||||
// subsystem specific error codes -- failsafe
|
// subsystem specific error codes -- failsafe
|
||||||
#define ERROR_CODE_RADIO_FAILSAFE_THROTTLE 2
|
#define ERROR_CODE_FAILSAFE_THROTTLE 2
|
||||||
#define ERROR_CODE_RADIO_FAILSAFE_BATTERY 3
|
#define ERROR_CODE_FAILSAFE_BATTERY 3
|
||||||
|
#define ERROR_CODE_FAILSAFE_WATCHDOG 4
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -48,7 +48,7 @@ static void failsafe_on_event()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// log the error to the dataflash
|
// 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
|
// warn the ground station and log to dataflash
|
||||||
gcs_send_text_P(SEVERITY_LOW,PSTR("Low Battery!"));
|
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 COPTER_LEDS == ENABLED
|
||||||
if ( bitRead(g.copter_leds_mode, 3) ) { // Only Activate if a battery is connected to avoid alarm on USB only
|
if ( bitRead(g.copter_leds_mode, 3) ) { // Only Activate if a battery is connected to avoid alarm on USB only
|
||||||
|
@ -48,13 +48,14 @@ void failsafe_check(uint32_t tnow)
|
|||||||
in_failsafe = true;
|
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
|
// disarm motors every second
|
||||||
failsafe_last_timestamp = tnow;
|
failsafe_last_timestamp = tnow;
|
||||||
if(motors.armed()) {
|
if(motors.armed()) {
|
||||||
motors.armed(false);
|
motors.armed(false);
|
||||||
set_armed(true);
|
set_armed(true);
|
||||||
motors.output();
|
motors.output();
|
||||||
|
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE, ERROR_CODE_FAILSAFE_WATCHDOG);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
Loading…
Reference in New Issue
Block a user