mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
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:
parent
357293fb2c
commit
078c8d0096
@ -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…
Reference in New Issue
Block a user