mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: init ArduSub pwm_output to [1500, ...]
Signed-off-by: Clyde McQueen <clyde@mcqueen.net>
This commit is contained in:
parent
53a7866ba3
commit
25fd69b947
|
@ -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
|
||||||
|
|
Loading…
Reference in New Issue