mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: added GliderPullup test
This commit is contained in:
parent
2f19dfef8a
commit
d27d34987c
@ -0,0 +1,3 @@
|
|||||||
|
QGC WPL 110
|
||||||
|
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.000000 1
|
||||||
|
1 0 0 83 2000.000000 10.000000 30.000000 0.000000 0.000000 0.000000 0.000000 1
|
@ -6114,6 +6114,43 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||||||
self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd)
|
self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd)
|
||||||
self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd_int)
|
self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd_int)
|
||||||
|
|
||||||
|
def GliderPullup(self):
|
||||||
|
'''test pullup of glider after ALTITUDE_WAIT'''
|
||||||
|
self.start_subtest("test glider pullup")
|
||||||
|
|
||||||
|
self.customise_SITL_commandline(
|
||||||
|
[],
|
||||||
|
model="glider",
|
||||||
|
defaults_filepath="Tools/autotest/default_params/glider.parm",
|
||||||
|
wipe=True)
|
||||||
|
|
||||||
|
self.set_parameters({
|
||||||
|
"PUP_ENABLE": 1,
|
||||||
|
"SERVO6_FUNCTION": 0, # balloon lift
|
||||||
|
"SERVO10_FUNCTION": 156, # lift release
|
||||||
|
"EK3_IMU_MASK": 1, # lane switches just make log harder to read
|
||||||
|
})
|
||||||
|
|
||||||
|
self.set_servo(6, 1000)
|
||||||
|
|
||||||
|
self.load_mission("glider-pullup-mission.txt")
|
||||||
|
self.change_mode("AUTO")
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.arm_vehicle()
|
||||||
|
self.context_collect('STATUSTEXT')
|
||||||
|
|
||||||
|
self.progress("Start balloon lift")
|
||||||
|
self.set_servo(6, 2000)
|
||||||
|
|
||||||
|
self.wait_text("Reached altitude", check_context=True, timeout=300)
|
||||||
|
self.wait_text("Start pullup airspeed", check_context=True)
|
||||||
|
self.wait_text("Pullup airspeed", check_context=True)
|
||||||
|
self.wait_text("Pullup pitch", check_context=True)
|
||||||
|
self.wait_text("Pullup level", check_context=True)
|
||||||
|
self.wait_text("Mission complete, changing mode to RTL", check_context=True)
|
||||||
|
|
||||||
|
self.fly_home_land_and_disarm(timeout=400)
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
ret = super(AutoTestPlane, self).tests()
|
ret = super(AutoTestPlane, self).tests()
|
||||||
@ -6246,6 +6283,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||||||
self.SetHomeAltChange,
|
self.SetHomeAltChange,
|
||||||
self.ForceArm,
|
self.ForceArm,
|
||||||
self.MAV_CMD_EXTERNAL_WIND_ESTIMATE,
|
self.MAV_CMD_EXTERNAL_WIND_ESTIMATE,
|
||||||
|
self.GliderPullup,
|
||||||
])
|
])
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user