autotest: correct hook removal for Copter tests

these hooks were remaining active if the test failed
This commit is contained in:
Peter Barker 2023-10-11 22:27:54 +11:00 committed by Peter Barker
parent 816adbf820
commit acf8162e5e
1 changed files with 6 additions and 4 deletions

View File

@ -8653,9 +8653,10 @@ class AutoTestCopter(AutoTest):
if m.yawspeed > yawspeed_thresh_rads: if m.yawspeed > yawspeed_thresh_rads:
raise NotAchievedException("Excessive yaw on takeoff: %f deg/s > %f deg/s (frame=%s)" % raise NotAchievedException("Excessive yaw on takeoff: %f deg/s > %f deg/s (frame=%s)" %
(math.degrees(m.yawspeed), math.degrees(yawspeed_thresh_rads), frame)) (math.degrees(m.yawspeed), math.degrees(yawspeed_thresh_rads), frame))
self.install_message_hook(verify_yaw) self.context_push()
self.install_message_hook_context(verify_yaw)
self.takeoff(10) self.takeoff(10)
self.remove_message_hook(verify_yaw) self.context_pop()
self.hover() self.hover()
self.change_mode('ALT_HOLD') self.change_mode('ALT_HOLD')
self.delay_sim_time(1) self.delay_sim_time(1)
@ -8671,13 +8672,14 @@ class AutoTestCopter(AutoTest):
if m.roll > roll_thresh_rad: if m.roll > roll_thresh_rad:
raise NotAchievedException("Excessive roll %f deg > %f deg" % raise NotAchievedException("Excessive roll %f deg > %f deg" %
(math.degrees(m.roll), math.degrees(roll_thresh_rad))) (math.degrees(m.roll), math.degrees(roll_thresh_rad)))
self.install_message_hook(verify_rollpitch) self.context_push()
self.install_message_hook_context(verify_rollpitch)
for i in range(5): for i in range(5):
self.set_rc(4, 2000) self.set_rc(4, 2000)
self.delay_sim_time(0.5) self.delay_sim_time(0.5)
self.set_rc(4, 1500) self.set_rc(4, 1500)
self.delay_sim_time(5) self.delay_sim_time(5)
self.remove_message_hook(verify_rollpitch) self.context_pop()
self.do_RTL() self.do_RTL()