Tools: Add simple Blimp autotest, testing Manual, Loiter and RTL modes

This commit is contained in:
Michelle Rossouw 2023-08-24 14:28:48 +10:00 committed by Peter Barker
parent 1d138c7630
commit b57d17123f
3 changed files with 144 additions and 18 deletions

View File

@ -729,6 +729,7 @@ def write_fullresults():
results.addglob('APM:Copter documentation', 'docs/ArduCopter/index.html')
results.addglob('APM:Rover documentation', 'docs/Rover/index.html')
results.addglob('APM:Sub documentation', 'docs/ArduSub/index.html')
results.addglob('APM:Blimp documentation', 'docs/Blimp/index.html')
results.addglobimage("Flight Track", '*.png')
write_webresults(results)

View File

@ -14,15 +14,15 @@ from common import AutoTest
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 584, 270)
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 584, 0)
# Flight mode switch positions are set-up in arducopter.param to be
# switch 1 = Circle
# switch 2 = Land
# switch 3 = RTL
# switch 4 = Auto
# switch 5 = Loiter
# switch 6 = Stabilize
# Flight mode switch positions are set-up in blimp.parm to be
# switch 1 = Land
# switch 2 = Manual
# switch 3 = Velocity
# switch 4 = Loiter
# switch 5 = Manual
# switch 6 = Manual
class AutoTestBlimp(AutoTest):
@ -105,16 +105,136 @@ class AutoTestBlimp(AutoTest):
def set_autodisarm_delay(self, delay):
self.set_parameter("DISARM_DELAY", delay)
def Speed(self):
'''test we can move'''
def FlyManual(self):
'''test manual mode'''
self.change_mode('MANUAL')
self.wait_ready_to_arm()
self.arm_vehicle()
acc = 0.5
# make sure we don't drift:
start = self.mav.location()
bl = self.mav.location()
tl = self.offset_location_ne(location=bl, metres_north=2, metres_east=0)
ttl = self.offset_location_ne(location=bl, metres_north=4, metres_east=0)
tr = self.offset_location_ne(location=bl, metres_north=4, metres_east=2)
ttr = self.offset_location_ne(location=bl, metres_north=4, metres_east=4)
if self.mavproxy is not None:
self.mavproxy.send(f"map icon {bl.lat} {bl.lng} flag\n")
self.mavproxy.send(f"map icon {tl.lat} {tl.lng} flag\n")
self.mavproxy.send(f"map icon {ttl.lat} {ttl.lng} flag\n")
self.mavproxy.send(f"map icon {tr.lat} {tr.lng} flag\n")
self.mavproxy.send(f"map icon {ttr.lat} {ttr.lng} flag\n")
self.set_rc(2, 2000)
self.wait_distance_to_location(start, 2, 10, timeout=40)
self.wait_distance_to_location(tl, 0, acc, timeout=10)
self.set_rc(2, 1500)
self.wait_distance_to_location(ttl, 0, acc, timeout=15)
self.set_rc(1, 2000)
self.wait_distance_to_location(tr, 0, acc, timeout=10)
self.set_rc(1, 1500)
self.wait_distance_to_location(ttr, 0, acc, timeout=15)
self.change_mode('RTL')
self.wait_distance_to_location(bl, 0, 0.5, timeout=30, minimum_duration=5) # make sure it can hold position
self.change_mode('MANUAL')
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
self.set_rc(3, 2000)
self.wait_altitude(5, 5.5, relative=True, timeout=15)
self.set_rc(3, 1500)
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
self.set_rc(4, 1000)
self.wait_heading(340, accuracy=5, timeout=5) # short timeout to check yawrate
self.set_rc(4, 1500)
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
self.set_rc(3, 1000)
self.wait_altitude(0, 0.5, relative=True, timeout=20)
self.set_rc(3, 1500)
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
self.set_rc(4, 2000)
self.wait_heading(135, accuracy=5, timeout=10) # short timeout to check yawrate
self.set_rc(4, 1500)
self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot
self.disarm_vehicle()
def FlyLoiter(self):
'''test loiter mode'''
self.change_mode('LOITER')
self.wait_ready_to_arm()
self.arm_vehicle()
siz = 5
tim = 60
# make sure we don't drift:
bl = self.mav.location()
tl = self.offset_location_ne(location=bl, metres_north=siz, metres_east=0)
tr = self.offset_location_ne(location=bl, metres_north=siz, metres_east=siz)
br = self.offset_location_ne(location=bl, metres_north=0, metres_east=siz)
print("Locations are:")
print("bottom left ", bl.lat, bl.lng)
print("top left ", tl.lat, tl.lng)
print("top right ", tr.lat, tr.lng)
print("bottom right ", br.lat, br.lng)
if self.mavproxy is not None:
self.mavproxy.send(f"map icon {bl.lat} {bl.lng} flag\n")
self.mavproxy.send(f"map icon {tl.lat} {tl.lng} flag\n")
self.mavproxy.send(f"map icon {tr.lat} {tr.lng} flag\n")
self.mavproxy.send(f"map icon {br.lat} {br.lng} flag\n")
self.set_parameter("SIMPLE_MODE", 1)
self.set_rc(2, 2000)
self.wait_distance_to_location(tl, 0, 0.2, timeout=tim)
self.set_rc(2, 1500)
self.set_rc(1, 2000)
self.wait_distance_to_location(tr, 0, 0.5, timeout=tim)
self.set_rc(1, 1500)
self.set_rc(2, 1000)
self.wait_distance_to_location(br, 0, 0.5, timeout=tim)
self.set_rc(2, 1500)
self.set_rc(1, 1000)
self.wait_distance_to_location(bl, 0, 0.5, timeout=tim)
self.set_rc(1, 1500)
fin = self.mav.location()
self.set_rc(4, 1700)
self.wait_heading(135, accuracy=2, timeout=tim)
self.set_rc(4, 1500)
self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot
self.set_rc(3, 2000)
self.wait_altitude(5, 5.5, relative=True, timeout=60)
self.set_rc(3, 1000)
self.wait_altitude(0, 0.5, relative=True, timeout=60)
self.set_rc(3, 1500)
self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot
self.set_rc(4, 1300)
self.wait_heading(0, accuracy=2, timeout=tim)
self.set_rc(4, 1500)
self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot
self.disarm_vehicle()
def tests(self):
@ -122,7 +242,8 @@ class AutoTestBlimp(AutoTest):
# ret = super(AutoTestBlimp, self).tests()
ret = []
ret.extend([
self.Speed,
self.FlyManual,
self.FlyLoiter,
])
return ret

View File

@ -163,6 +163,10 @@ for t in $CI_BUILD_TARGET; do
run_autotest "Sub" "build.Sub" "test.Sub"
continue
fi
if [ "$t" == "sitltest-blimp" ]; then
run_autotest "Blimp" "build.Blimp" "test.Blimp"
continue
fi
if [ "$t" == "unit-tests" ]; then
run_autotest "Unit Tests" "build.unit_tests" "run.unit_tests"
@ -267,7 +271,7 @@ for t in $CI_BUILD_TARGET; do
$waf bootloader
continue
fi
if [ "$t" == "stm32f7" ]; then
echo "Building mRoX21-777/"
$waf configure --Werror --board mRoX21-777
@ -339,7 +343,7 @@ for t in $CI_BUILD_TARGET; do
$waf tests
continue
fi
if [ "$t" == "fmuv2-plane" ]; then
echo "Building fmuv2 plane"
$waf configure --board fmuv2
@ -367,11 +371,11 @@ for t in $CI_BUILD_TARGET; do
if [ "$t" == "replay" ]; then
echo "Building replay"
$waf configure --board sitl --debug --disable-scripting
$waf replay
echo "Building AP_DAL standalone test"
$waf configure --board sitl --debug --disable-scripting --no-gcs
$waf --target tool/AP_DAL_Standalone
$waf clean
continue
@ -407,7 +411,7 @@ for t in $CI_BUILD_TARGET; do
./Tools/scripts/build_bootloaders.py --signing-key testkey_public_key.dat MatekL431-DShot
continue
fi
if [ "$t" == "python-cleanliness" ]; then
echo "Checking Python code cleanliness"
./Tools/scripts/run_flake8.py