SITL: Fix buoyancy direction for earth-frame

Previously the sub would just go upwards, so rolling it 180º caused it to sink
This commit is contained in:
Willian Galvani 2019-08-05 13:49:28 -03:00 committed by Andrew Tridgell
parent 9cd0aef53e
commit 9abe4fc445

View File

@ -70,7 +70,7 @@ void Submarine::calculate_forces(const struct sitl_input &input, Vector3f &rot_a
rot_accel = Vector3f(0,0,0);
// slight positive buoyancy
body_accel = Vector3f(0, 0, -calculate_buoyancy_acceleration());
body_accel = dcm.transposed() * Vector3f(0, 0, -calculate_buoyancy_acceleration());
for (int i = 0; i < n_thrusters; i++) {
Thruster t = thrusters[i];