mirror of https://github.com/ArduPilot/ardupilot
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:
parent
400e5e9117
commit
b2086d1e96
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue