Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SITL: SIM_Motor: include momentum drag in derived torque #26255

Merged
merged 1 commit into from
Feb 20, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading