Skip to content

Commit

Permalink
SITL: SIM_Motor: include momentum drag in derived torque
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Feb 20, 2024
1 parent bedcbc2 commit c54529a
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions libraries/SITL/SIM_Motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
Expand Down

0 comments on commit c54529a

Please sign in to comment.