From 1735563bb790ff70b346b1bf5c5342afb34f61c2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 12 Sep 2019 17:52:51 +1000 Subject: [PATCH] AP_HAL_SITL: set initial PWM values to a flag value These should never be used. Setting them to a flag value may give a hint to someone trying to debug a problem in the future. --- libraries/AP_HAL_SITL/SITL_State.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index fea3d0179f..4892e5042c 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -539,9 +539,12 @@ void SITL_State::_simulator_servos(struct sitl_input &input) void SITL_State::init(int argc, char * const argv[]) { - pwm_input[0] = pwm_input[1] = pwm_input[3] = 1500; - pwm_input[4] = pwm_input[7] = 1800; - pwm_input[2] = pwm_input[5] = pwm_input[6] = 1000; + for (uint8_t i=0; i