mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
SITL: Sub: Use proper phyisics for thrusters
This commit is contained in:
parent
237ad94f92
commit
a1c5b7ba55
@ -83,9 +83,8 @@ void Submarine::calculate_forces(const struct sitl_input &input, Vector3f &rot_a
|
||||
}
|
||||
|
||||
// 2.5 scalar for approximate real-life performance of T200 thruster
|
||||
body_accel += t.linear * output * 2.5;
|
||||
|
||||
rot_accel += t.rotational * output;
|
||||
body_accel += t.linear * output * frame_property.thrust / frame_property.weight;
|
||||
rot_accel += t.rotational * output * frame_property.thrust * frame_property.thruster_mount_radius / frame_property.moment_of_inertia;
|
||||
}
|
||||
|
||||
// Limit movement at the sea floor
|
||||
|
Loading…
Reference in New Issue
Block a user