Browse Source

SITL: Fix buoyancy direction for earth-frame

Previously the sub would just go upwards, so rolling it 180º caused it to sink
c415-sdk
Willian Galvani 6 years ago committed by Jacob Walser
parent
commit
1e2340fbb4
  1. 2
      libraries/SITL/SIM_Submarine.cpp

2
libraries/SITL/SIM_Submarine.cpp

@ -70,7 +70,7 @@ void Submarine::calculate_forces(const struct sitl_input &input, Vector3f &rot_a @@ -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];

Loading…
Cancel
Save