Skip to content

Commit

Permalink
autotest: fixes for ShipOps test
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Oct 21, 2023
1 parent 97cf9f5 commit 2574db6
Showing 1 changed file with 5 additions and 1 deletion.
6 changes: 5 additions & 1 deletion Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -8084,22 +8084,26 @@ def ShipOps(self):
self.set_rc(3, 2000)

self.start_subtest('Ensure we get to perch altitude')
self.wait_altitude(perch_alt-0.5, perch_alt+0.5, minimum_duration=5, relative=True, timeout=30)
self.wait_altitude(perch_alt-2.5, perch_alt+2.5, minimum_duration=5, relative=True, timeout=30)

self.start_subtest('Ensure we are matching ship speed')
self.wait_groundspeed(ship_speed-0.1, ship_speed+0.1, minimum_duration=10)

# self.set_parameter("SIM_SPEEDUP", 1)

self.start_subtest('Check various perch distances')
self.context_push()
for perch_distance in 20, 25, 15, 0:
self.set_parameter('SHIP_PCH_RAD', perch_distance)
self.ShipOps_wait_perch_distance(perch_distance)
self.context_pop()

self.start_subtest('Check various perch angles')
self.context_push()
for perch_angle in 180, 90, 270, 0, 300:
self.set_parameter('SHIP_PCH_ANG', perch_angle)
self.ShipOps_wait_perch_angle(perch_angle)
self.context_pop()

self.progress("trigger recovery")
self.set_rc(3, 1000)
Expand Down

0 comments on commit 2574db6

Please sign in to comment.