|
|
|
@ -25,6 +25,7 @@
@@ -25,6 +25,7 @@
|
|
|
|
|
#include <AP_HAL_ChibiOS/RCOutput.h> |
|
|
|
|
#include "analog.h" |
|
|
|
|
#include "rc.h" |
|
|
|
|
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h> |
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL &hal; |
|
|
|
|
|
|
|
|
@ -40,6 +41,9 @@ void loop();
@@ -40,6 +41,9 @@ void loop();
|
|
|
|
|
|
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); |
|
|
|
|
|
|
|
|
|
// enable testing of IOMCU watchdog using safety switch
|
|
|
|
|
#define IOMCU_ENABLE_WATCHDOG_TEST 0 |
|
|
|
|
|
|
|
|
|
// pending events on the main thread
|
|
|
|
|
enum ioevents { |
|
|
|
|
IOEVENT_PWM=1, |
|
|
|
@ -207,6 +211,7 @@ void AP_IOMCU_FW::update()
@@ -207,6 +211,7 @@ void AP_IOMCU_FW::update()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
uint32_t now = last_ms; |
|
|
|
|
reg_status.timestamp_ms = last_ms; |
|
|
|
|
|
|
|
|
|
// output SBUS if enabled
|
|
|
|
|
if ((reg_setup.features & P_SETUP_FEATURES_SBUS1_OUT) && |
|
|
|
@ -672,6 +677,22 @@ void AP_IOMCU_FW::safety_update(void)
@@ -672,6 +677,22 @@ void AP_IOMCU_FW::safety_update(void)
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if IOMCU_ENABLE_WATCHDOG_TEST |
|
|
|
|
if (safety_button_counter == 50) { |
|
|
|
|
// deliberate lockup of IOMCU on 5s button press, for testing
|
|
|
|
|
// watchdog
|
|
|
|
|
while (true) { |
|
|
|
|
hal.scheduler->delay(50); |
|
|
|
|
palToggleLine(HAL_GPIO_PIN_SAFETY_LED); |
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_SAFETY_INPUT)) { |
|
|
|
|
// only trigger watchdog on button release, so we
|
|
|
|
|
// don't end up stuck in the bootloader
|
|
|
|
|
stm32_watchdog_pat(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
led_counter = (led_counter+1) % 16; |
|
|
|
|
const uint16_t led_pattern = reg_status.flag_safety_off?0xFFFF:0x5500; |
|
|
|
|
palWriteLine(HAL_GPIO_PIN_SAFETY_LED, (led_pattern & (1U << led_counter))?0:1); |
|
|
|
|