diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 6e19f66d72..85448183c9 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -688,7 +688,26 @@ void SITL_State::_simulator_servos(struct sitl_input &input) } if (_vehicle == ArduPlane) { - throttle = constrain_float((input.servos[2] - 1000) / 1000.0f, 0.0f, 1.0f); + float forward_throttle = constrain_float((input.servos[2] - 1000) / 1000.0f, 0.0f, 1.0f); + // do a little quadplane dance + float hover_throttle = 0.0f; + uint8_t running_motors = 0; + for (i=0; i < sitl_model->get_num_motors() - 1; i++) { + float motor_throttle = constrain_float((input.servos[sitl_model->get_motors_offset() + i] - 1000) / 1000.0f, 0.0f, 1.0f); + // update motor_on flag + if (!is_zero(motor_throttle)) { + hover_throttle += motor_throttle; + running_motors++; + } + } + if (running_motors > 0) { + hover_throttle /= running_motors; + } + if (!is_zero(forward_throttle)) { + throttle = forward_throttle; + } else { + throttle = hover_throttle; + } } else if (_vehicle == APMrover2) { input.servos[2] = static_cast(constrain_int16(input.servos[2], 1000, 2000)); input.servos[0] = static_cast(constrain_int16(input.servos[0], 1000, 2000)); @@ -696,7 +715,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input) } else { // run checks on each motor uint8_t running_motors = 0; - for (i=0; iget_num_motors(); i++) { float motor_throttle = constrain_float((input.servos[i] - 1000) / 1000.0f, 0.0f, 1.0f); // update motor_on flag if (!is_zero(motor_throttle)) {