mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_BoardConfig: auto-restore safety state on watchdog reset
This commit is contained in:
parent
0a263cf202
commit
ff3527eef5
@ -161,7 +161,7 @@ public:
|
||||
|
||||
// return true if watchdog enabled
|
||||
static bool watchdog_enabled(void) {
|
||||
return _singleton?(_singleton->_options & BOARD_OPTION_WATCHDOG)!=0:false;
|
||||
return instance?(instance->_options & BOARD_OPTION_WATCHDOG)!=0:false;
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -18,6 +18,7 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_BoardConfig.h"
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <stdio.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -28,7 +29,12 @@ extern const AP_HAL::HAL& hal;
|
||||
*/
|
||||
void AP_BoardConfig::board_init_safety()
|
||||
{
|
||||
if (state.safety_enable.get() == 0) {
|
||||
bool force_safety_off = (state.safety_enable.get() == 0);
|
||||
if (!force_safety_off && hal.util->was_watchdog_safety_off()) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Forcing safety off for watchdog\n");
|
||||
force_safety_off = true;
|
||||
}
|
||||
if (force_safety_off) {
|
||||
hal.rcout->force_safety_off();
|
||||
hal.rcout->force_safety_no_wait();
|
||||
// wait until safety has been turned off
|
||||
|
Loading…
Reference in New Issue
Block a user