diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 491b330a23..68a56ef772 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -698,6 +698,10 @@ void SITL_State::_simulator_servos(struct sitl_input &input) if (_vehicle == Rover) { 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