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 973b2d11a2
commit c8b328c3a1

View File

@ -132,9 +132,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);