Tools: autotest FlyEachFrame yaw rate relaxed

This commit is contained in:
Randy Mackay 2023-09-14 10:04:17 +09:00 committed by Andrew Tridgell
parent 3f531d18bc
commit 2835deb0de

View File

@ -8662,7 +8662,7 @@ class AutoTestCopter(AutoTest):
def verify_yaw(mav, m):
if m.get_type() != 'ATTITUDE':
return
yawspeed_thresh_rads = math.radians(10)
yawspeed_thresh_rads = math.radians(20)
if m.yawspeed > yawspeed_thresh_rads:
raise NotAchievedException("Excessive yaw on takeoff: %f deg/s > %f deg/s (frame=%s)" %
(math.degrees(m.yawspeed), math.degrees(yawspeed_thresh_rads), frame))