5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 15:38:29 -04:00

HAL_ChibiOS: always start with safety enabled

we want it enabled during early boot to prevent incorrect ESC and
servo output
This commit is contained in:
Andrew Tridgell 2022-05-21 18:45:33 +10:00
parent bd22f0073c
commit 9a5e8d3927

View File

@ -140,9 +140,7 @@ void RCOutput::init()
// setup default output rate of 50Hz
set_freq(0xFFFF ^ ((1U<<chan_offset)-1), 50);
#ifdef HAL_GPIO_PIN_SAFETY_IN
safety_state = AP_HAL::Util::SAFETY_DISARMED;
#endif
#if RCOU_DSHOT_TIMING_DEBUG
hal.gpio->pinMode(54, 1);