mirror of https://github.com/ArduPilot/ardupilot
autotest: let heading settle before testing WP_YAW_BEHAVIOR=0
2022-08-19T02:22:48.3161982Z AT-0229.9: Exception caught: Unexpected heading=94.000000 want=91.000000 2022-08-19T02:22:48.3162341Z Traceback (most recent call last): 2022-08-19T02:22:48.3162738Z File "/__w/ardupilot/ardupilot/Tools/autotest/common.py", line 7173, in run_one_test_attempt 2022-08-19T02:22:48.3163101Z test_function() 2022-08-19T02:22:48.3163507Z File "/__w/ardupilot/ardupilot/Tools/autotest/arducopter.py", line 4414, in GuidedSubModeChange 2022-08-19T02:22:48.3164012Z self.assert_heading(orig_heading) 2022-08-19T02:22:48.3164419Z File "/__w/ardupilot/ardupilot/Tools/autotest/common.py", line 5610, in assert_heading 2022-08-19T02:22:48.3164866Z raise NotAchievedException("Unexpected heading=%f want=%f" % 2022-08-19T02:22:48.3165290Z common.NotAchievedException: Unexpected heading=94.000000 want=91.000000
This commit is contained in:
parent
2170c86b9c
commit
668ec44968
|
@ -4407,8 +4407,9 @@ class AutoTestCopter(AutoTest):
|
|||
self.fly_guided_move_local(5, 5, 10)
|
||||
|
||||
self.start_subtest("Checking that WP_YAW_BEHAVIOUR 0 works")
|
||||
orig_heading = self.get_heading()
|
||||
self.set_parameter('WP_YAW_BEHAVIOR', 0)
|
||||
self.delay_sim_time(2)
|
||||
orig_heading = self.get_heading()
|
||||
self.fly_guided_move_local(5, 0, 10)
|
||||
# ensure our heading hasn't changed:
|
||||
self.assert_heading(orig_heading)
|
||||
|
|
Loading…
Reference in New Issue