mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: test simulated ship takeoff
This commit is contained in:
parent
fb5a06b8da
commit
2c1d77bf8f
@ -4955,6 +4955,21 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
self.fly_rangefinder_mavlink()
|
self.fly_rangefinder_mavlink()
|
||||||
|
|
||||||
|
def fly_ship_takeoff(self):
|
||||||
|
# test ship takeoff
|
||||||
|
self.wait_groundspeed(0, 2)
|
||||||
|
self.set_parameter("SIM_SHIP_ENABLE", 1)
|
||||||
|
self.set_parameter("SIM_SHIP_SPEED", 10)
|
||||||
|
self.set_parameter("SIM_SHIP_DSIZE", 2)
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
# we should be moving with the ship
|
||||||
|
self.wait_groundspeed(9, 11)
|
||||||
|
self.takeoff(10)
|
||||||
|
# above ship our speed drops to 0
|
||||||
|
self.wait_groundspeed(0, 2)
|
||||||
|
self.land_and_disarm()
|
||||||
|
# ship will have moved on, so we land on the water which isn't moving
|
||||||
|
self.wait_groundspeed(0, 2)
|
||||||
|
|
||||||
def test_parameter_validation(self):
|
def test_parameter_validation(self):
|
||||||
self.progress("invalid; min must be less than max:")
|
self.progress("invalid; min must be less than max:")
|
||||||
@ -5155,6 +5170,10 @@ class AutoTestCopter(AutoTest):
|
|||||||
"Test Buttons",
|
"Test Buttons",
|
||||||
self.test_button),
|
self.test_button),
|
||||||
|
|
||||||
|
("ShipTakeoff",
|
||||||
|
"Fly Simulated Ship Takeoff",
|
||||||
|
self.fly_ship_takeoff),
|
||||||
|
|
||||||
("RangeFinder",
|
("RangeFinder",
|
||||||
"Test RangeFinder Basic Functionality",
|
"Test RangeFinder Basic Functionality",
|
||||||
self.test_rangefinder),
|
self.test_rangefinder),
|
||||||
|
Loading…
Reference in New Issue
Block a user