From e27015f75e9a8b8e17e5bd79d5a3736f25cacb65 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 6 May 2021 11:35:40 +1000 Subject: [PATCH] autotest: verify roll/pitch are not adversely affected by yaw inputs --- Tools/autotest/arducopter.py | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 7d3ab10495..7d5ad0b245 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -6652,6 +6652,29 @@ class AutoTestCopter(AutoTest): self.install_message_hook(verify_yaw) self.takeoff(10) self.remove_message_hook(verify_yaw) + self.hover() + self.change_mode('ALT_HOLD') + self.delay_sim_time(1) + + def verify_rollpitch(mav, m): + if m.get_type() != 'ATTITUDE': + return + pitch_thresh_rad = math.radians(2) + if m.pitch > pitch_thresh_rad: + raise NotAchievedException("Excessive pitch %f deg > %f deg" % + (math.degrees(m.pitch), math.degrees(pitch_thresh_rad))) + roll_thresh_rad = math.radians(2) + if m.roll > roll_thresh_rad: + raise NotAchievedException("Excessive roll %f deg > %f deg" % + (math.degrees(m.roll), math.degrees(roll_thresh_rad))) + self.install_message_hook(verify_rollpitch) + for i in range(5): + self.set_rc(4, 2000) + self.delay_sim_time(0.5) + self.set_rc(4, 1500) + self.delay_sim_time(5) + self.remove_message_hook(verify_rollpitch) + self.do_RTL() def create_simple_relhome_mission(self, items_in, target_system=1, target_component=1):