Revert "AP_HAL_SITL: set initial PWM values to a flag value"

This reverts commit 1735563bb7.

This commit broke RC input on high channels with sim_vehicle.py, plane
getc RC failsafe immediately
This commit is contained in:
Andrew Tridgell 2019-09-15 16:46:13 +10:00
parent 4a35e8ee74
commit f86a7d347d

View File

@ -539,12 +539,9 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
void SITL_State::init(int argc, char * const argv[])
{
for (uint8_t i=0; i<ARRAY_SIZE(pwm_input); i++) {
// this is simply a magic flag value. If you ever see this
// being used there is a bug as the values in this array
// should be overwritten before they are considered valid.
pwm_input[i] = 65530;
}
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;
_scheduler = Scheduler::from(hal.scheduler);
_parse_command_line(argc, argv);