From b2086d1e96c6026a60bbce2d446233f8819fc586 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 21 May 2022 18:45:33 +1000 Subject: [PATCH] HAL_ChibiOS: always start with safety enabled we want it enabled during early boot to prevent incorrect ESC and servo output --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 3177ba126a..3c37d8fd7e 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -140,9 +140,7 @@ void RCOutput::init() // setup default output rate of 50Hz set_freq(0xFFFF ^ ((1U<pinMode(54, 1);