Browse Source

Autotest: Sub: Add depth hold cases of large buoyancies and small inputs

apm_2208
Willian Galvani 5 years ago
parent
commit
e23e2cb63f
  1. 12
      Tools/autotest/ardusub.py

12
Tools/autotest/ardusub.py

@ -152,9 +152,21 @@ class AutoTestSub(AutoTest): @@ -152,9 +152,21 @@ class AutoTestSub(AutoTest):
# let the vehicle settle (momentum / stopping point shenanigans....)
self.delay_sim_time(1)
self.watch_altitude_maintained()
# Make sure the code can handle buoyancy changes
self.set_parameter("SIM_BUOYANCY", 10)
self.watch_altitude_maintained()
self.set_parameter("SIM_BUOYANCY", -10)
self.watch_altitude_maintained()
# Make sure that the ROV will dive with a small input down even if there is a 10N buoyancy force upwards
self.set_parameter("SIM_BUOYANCY", 10)
self.set_rc(Joystick.Throttle, 1450)
self.wait_altitude(altitude_min=-6, altitude_max=-5.5)
self.set_rc(Joystick.Throttle, 1500)
self.watch_altitude_maintained()
self.disarm_vehicle()
def test_pos_hold(self):

Loading…
Cancel
Save