AP_HAL_SITL: init ArduSub pwm_output to [1500, ...]

Signed-off-by: Clyde McQueen <clyde@mcqueen.net>
This commit is contained in:
Clyde McQueen 2022-03-30 09:56:15 -07:00 committed by Andrew Tridgell
parent 53a7866ba3
commit 25fd69b947
1 changed files with 4 additions and 0 deletions

View File

@ -698,6 +698,10 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
if (_vehicle == Rover) { if (_vehicle == Rover) {
pwm_output[0] = pwm_output[1] = pwm_output[2] = pwm_output[3] = 1500; pwm_output[0] = pwm_output[1] = pwm_output[2] = pwm_output[3] = 1500;
} }
if (_vehicle == ArduSub) {
pwm_output[0] = pwm_output[1] = pwm_output[2] = pwm_output[3] =
pwm_output[4] = pwm_output[5] = pwm_output[6] = pwm_output[7] = 1500;
}
} }
// output at chosen framerate // output at chosen framerate