Autotest: Add copter weathervane tests

This commit is contained in:
Gone4Dirt 2022-04-14 10:59:10 +01:00 committed by Bill Geyer
parent 66a4ba6256
commit 01481b2ec4
2 changed files with 51 additions and 0 deletions

View File

@ -0,0 +1,6 @@
QGC WPL 110
0 1 0 16 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 582.000000 1
1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.36328940 149.16516420 20.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.36300830 149.16518770 20.000000 1
4 0 3 19 20.000000 0.000000 0.000000 1.000000 0.000000 0.000000 20.000000 1
12 0 3 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1

View File

@ -4554,6 +4554,50 @@ class AutoTestCopter(AutoTest):
if ex is not None:
raise ex
def Weathervane(self):
'''Test copter weathervaning'''
# We test nose into wind code paths and yaw direction here and test side into wind
# yaw direction in QuadPlane tests to reduce repetition.
self.set_parameters({
"SIM_WIND_SPD": 10,
"SIM_WIND_DIR": 100,
"GUID_OPTIONS": 129, # allow weathervaning and arming from tx in guided
"AUTO_OPTIONS": 131, # allow arming in auto, take off without raising the stick, and weathervaning
"WVANE_ENABLE": 1,
"WVANE_GAIN": 3,
"WVANE_VELZ_MAX": 1,
"WVANE_SPD_MAX": 2
})
self.progress("Test weathervaning in auto")
self.load_mission("weathervane_mission.txt", strict=False)
self.change_mode("AUTO")
self.wait_ready_to_arm()
self.arm_vehicle()
self.wait_statustext("Weathervane Active", timeout=60)
self.do_RTL()
self.wait_disarmed()
self.change_mode("GUIDED")
# After take off command in guided we enter the velaccl sub mode
self.progress("Test weathervaning in guided vel-accel")
self.set_rc(3, 1000)
self.wait_ready_to_arm()
self.arm_vehicle()
self.user_takeoff(alt_min=15)
# Wait for heading to match wind direction.
self.wait_heading(100, accuracy=8, timeout=100)
self.progress("Test weathervaning in guided pos only")
# Travel directly north to align heading north and build some airspeed.
self.fly_guided_move_local(x=40, y=0, z_up=15)
# Wait for heading to match wind direction.
self.wait_heading(100, accuracy=8, timeout=100)
self.do_RTL()
def GuidedSubModeChange(self):
""""Ensure we can move around in guided after a takeoff command."""
@ -9225,6 +9269,7 @@ class AutoTestCopter(AutoTest):
self.RichenPower,
self.IE24,
self.MAVLandedStateTakeoff,
self.Weathervane,
])
return ret