Tools: autotest: add test for camera trigger distance

This commit is contained in:
Peter Barker 2018-10-23 21:52:05 +11:00 committed by Peter Barker
parent d690baecf9
commit f290a72d9c
2 changed files with 58 additions and 0 deletions

View File

@ -736,6 +736,54 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
if ex is not None:
raise ex
def test_camera_mission_items(self):
self.context_push()
ex = None
try:
self.mavproxy.send('wp load %s\n' %
os.path.join(testdir, "rover-camera-mission.txt"))
self.wait_ready_to_arm()
self.mavproxy.send('mode auto\n')
self.wait_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
prev_cf = None
while True:
cf = self.mav.recv_match(type='CAMERA_FEEDBACK', blocking=True)
if prev_cf is None:
prev_cf = cf
continue
dist_travelled = self.get_distance_int(prev_cf, cf)
prev_cf = cf
mc = self.mav.messages.get("MISSION_CURRENT", None)
if mc is None:
continue
elif mc.seq == 2:
expected_distance = 2
elif mc.seq == 4:
expected_distance = 5
elif mc.seq ==5:
break
else:
continue
self.progress("Expected distance %f got %f" %
(expected_distance, dist_travelled))
error = abs(expected_distance - dist_travelled)
# Rover moves at ~5m/s; we appear to do something at
# 5Hz, so we do see over a meter of error!
max_error = 1.5
if error > max_error:
raise NotAchievedException("Camera distance error: %f (%f)" %
(error, max_error))
self.disarm_vehicle()
except Exception as e:
self.progress("Exception caught")
ex = e
self.context_pop()
if ex is not None:
raise ex
def autotest(self):
"""Autotest APMrover2 in SITL."""
self.check_test_syntax(test_file=os.path.realpath(__file__))
@ -811,6 +859,9 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.run_test("Test AC Avoidance switch",
self.drive_fence_ac_avoidance)
self.run_test("Test Camera Mission Items",
self.test_camera_mission_items)
self.run_test("Download logs", lambda:
self.log_download(
self.buildlogs_path("APMrover2-log.bin")))

View File

@ -0,0 +1,7 @@
QGC WPL 110
0 0 0 16 0.000000 0.000000 0.000000 0.000000 40.071377 -105.229790 -0.110000 1
1 0 0 206 2.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 40.071968 -105.229782 0.000000 1
3 0 0 206 5.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 40.072365 -105.229774 0.000000 1
5 0 3 16 0.000000 0.000000 0.000000 0.000000 40.072872 -105.229752 0.000000 1