SITL: SIM_Motor: include momentum drag in derived torque

This commit is contained in:
Iampete1 2024-02-18 13:12:35 +00:00 committed by Andrew Tridgell
parent bedcbc24b6
commit c54529aaf8

View File

@ -106,9 +106,6 @@ void Motor::calculate_forces(const struct sitl_input &input,
rotor_torque = rotation * rotor_torque;
}
// calculate total torque in newton-meters
torque = (position % thrust) + rotor_torque;
if (use_drag) {
// calculate momentum drag per motor
const float momentum_drag_factor = momentum_drag_coefficient * sqrtf(air_density * true_prop_area);
@ -124,6 +121,9 @@ void Motor::calculate_forces(const struct sitl_input &input,
thrust -= momentum_drag;
}
// calculate total torque in newton-meters
torque = (position % thrust) + rotor_torque;
// calculate current
float power = power_factor * fabsf(motor_thrust);
current = power / MAX(voltage, 0.1);