mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_IOCMU: improved the safety button reset test code
this allows testing of either watchdog or hard-fault reset
This commit is contained in:
parent
65fadfa2fe
commit
d921c427b1
@ -41,8 +41,13 @@ void loop();
|
|||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
// enable testing of IOMCU watchdog using safety switch
|
/*
|
||||||
#define IOMCU_ENABLE_WATCHDOG_TEST 0
|
enable testing of IOMCU reset using safety switch
|
||||||
|
a value of 0 means normal operation
|
||||||
|
a value of 1 means test with watchdog
|
||||||
|
a value of 2 means test with reboot
|
||||||
|
*/
|
||||||
|
#define IOMCU_ENABLE_RESET_TEST 0
|
||||||
|
|
||||||
// pending events on the main thread
|
// pending events on the main thread
|
||||||
enum ioevents {
|
enum ioevents {
|
||||||
@ -707,21 +712,40 @@ void AP_IOMCU_FW::safety_update(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if IOMCU_ENABLE_WATCHDOG_TEST
|
#if IOMCU_ENABLE_RESET_TEST
|
||||||
if (safety_button_counter == 50) {
|
{
|
||||||
// deliberate lockup of IOMCU on 5s button press, for testing
|
// deliberate lockup of IOMCU on 5s button press, for testing
|
||||||
// watchdog
|
// watchdog
|
||||||
while (true) {
|
static uint32_t safety_test_counter;
|
||||||
hal.scheduler->delay(50);
|
static bool should_lockup;
|
||||||
palToggleLine(HAL_GPIO_PIN_SAFETY_LED);
|
if (palReadLine(HAL_GPIO_PIN_SAFETY_INPUT)) {
|
||||||
if (palReadLine(HAL_GPIO_PIN_SAFETY_INPUT)) {
|
safety_test_counter++;
|
||||||
// only trigger watchdog on button release, so we
|
} else {
|
||||||
// don't end up stuck in the bootloader
|
safety_test_counter = 0;
|
||||||
stm32_watchdog_pat();
|
}
|
||||||
|
if (safety_test_counter == 50) {
|
||||||
|
should_lockup = true;
|
||||||
|
}
|
||||||
|
// wait for lockup for safety to be released so we don't end
|
||||||
|
// up in the bootloader
|
||||||
|
if (should_lockup && palReadLine(HAL_GPIO_PIN_SAFETY_INPUT) == 0) {
|
||||||
|
#if IOMCU_ENABLE_RESET_TEST == 1
|
||||||
|
// lockup with watchdog
|
||||||
|
while (true) {
|
||||||
|
hal.scheduler->delay(50);
|
||||||
|
palToggleLine(HAL_GPIO_PIN_SAFETY_LED);
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
// hard fault to simulate power reset or software fault
|
||||||
|
void *foo = (void*)0xE000ED38;
|
||||||
|
typedef void (*fptr)();
|
||||||
|
fptr gptr = (fptr) (void *) foo;
|
||||||
|
gptr();
|
||||||
|
while (true) {}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif // IOMCU_ENABLE_RESET_TEST
|
||||||
|
|
||||||
led_counter = (led_counter+1) % 16;
|
led_counter = (led_counter+1) % 16;
|
||||||
const uint16_t led_pattern = reg_status.flag_safety_off?0xFFFF:0x5500;
|
const uint16_t led_pattern = reg_status.flag_safety_off?0xFFFF:0x5500;
|
||||||
|
Loading…
Reference in New Issue
Block a user