mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: jfb100 gets shorter EXT_WDOG_INTERVAL_MS
This commit is contained in:
parent
9e19e12040
commit
3f3ba237fb
|
@ -343,7 +343,7 @@ PA9 VBAS INPUT PULLDOWN
|
||||||
|
|
||||||
# External watchdog gpio
|
# External watchdog gpio
|
||||||
PH11 EXT_WDOG OUTPUT SPEED_VERYLOW
|
PH11 EXT_WDOG OUTPUT SPEED_VERYLOW
|
||||||
define EXT_WDOG_INTERVAL_MS 100
|
define EXT_WDOG_INTERVAL_MS 50
|
||||||
|
|
||||||
# safety switch
|
# safety switch
|
||||||
PE10 SAFETY_IN INPUT PULLUP
|
PE10 SAFETY_IN INPUT PULLUP
|
||||||
|
|
Loading…
Reference in New Issue