Skip to content

Commit acf8162

Browse files
committed
autotest: correct hook removal for Copter tests
these hooks were remaining active if the test failed
1 parent 816adbf commit acf8162

File tree

1 file changed

+6
-4
lines changed

1 file changed

+6
-4
lines changed

Tools/autotest/arducopter.py

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -8653,9 +8653,10 @@ def verify_yaw(mav, m):
86538653
if m.yawspeed > yawspeed_thresh_rads:
86548654
raise NotAchievedException("Excessive yaw on takeoff: %f deg/s > %f deg/s (frame=%s)" %
86558655
(math.degrees(m.yawspeed), math.degrees(yawspeed_thresh_rads), frame))
8656-
self.install_message_hook(verify_yaw)
8656+
self.context_push()
8657+
self.install_message_hook_context(verify_yaw)
86578658
self.takeoff(10)
8658-
self.remove_message_hook(verify_yaw)
8659+
self.context_pop()
86598660
self.hover()
86608661
self.change_mode('ALT_HOLD')
86618662
self.delay_sim_time(1)
@@ -8671,13 +8672,14 @@ def verify_rollpitch(mav, m):
86718672
if m.roll > roll_thresh_rad:
86728673
raise NotAchievedException("Excessive roll %f deg > %f deg" %
86738674
(math.degrees(m.roll), math.degrees(roll_thresh_rad)))
8674-
self.install_message_hook(verify_rollpitch)
8675+
self.context_push()
8676+
self.install_message_hook_context(verify_rollpitch)
86758677
for i in range(5):
86768678
self.set_rc(4, 2000)
86778679
self.delay_sim_time(0.5)
86788680
self.set_rc(4, 1500)
86798681
self.delay_sim_time(5)
8680-
self.remove_message_hook(verify_rollpitch)
8682+
self.context_pop()
86818683

86828684
self.do_RTL()
86838685

0 commit comments

Comments
 (0)