Skip to content
Permalink
Browse files

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.
  • Loading branch information...
peterbarker committed Sep 12, 2019
1 parent f881e4a commit 331afc24911d7a1b3ca57b5b1400095126febbb4
Showing with 5 additions and 3 deletions.
  1. +5 −3 libraries/AP_HAL_SITL/SITL_State.cpp
@@ -539,9 +539,11 @@ 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<ARRAY_SIZE(pwm_input); i++) {
// this is simple a magic flag value. If you ever see this
// being used there is a bug.
pwm_input[i] = 65530;
}

_scheduler = Scheduler::from(hal.scheduler);
_parse_command_line(argc, argv);

0 comments on commit 331afc2

Please sign in to comment.
You can’t perform that action at this time.