autotest: add test for accelerometer pose calibration

This commit is contained in:
Peter Barker 2020-01-01 10:43:58 +11:00 committed by Peter Barker
parent 881eadb993
commit e080493a7c
2 changed files with 46 additions and 0 deletions

View File

@ -5021,6 +5021,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
"Upload/Download of items in different frames", "Upload/Download of items in different frames",
self.test_mission_frames), self.test_mission_frames),
("AccelCal",
"Accelerometer Calibration testing",
self.accelcal),
("DownLoadLogs", "Download logs", lambda: ("DownLoadLogs", "Download logs", lambda:
self.log_download( self.log_download(
self.buildlogs_path("APMrover2-log.bin"), self.buildlogs_path("APMrover2-log.bin"),

View File

@ -3655,6 +3655,48 @@ switch value'''
if self.get_distance_int(gps1, gps2) > 1: if self.get_distance_int(gps1, gps2) > 1:
raise NotAchievedException("NMEA output inaccurate") raise NotAchievedException("NMEA output inaccurate")
def mavproxy_load_module(self, module):
self.mavproxy.send("module load %s\n" % module)
self.mavproxy.expect("Loaded module %s" % module)
def mavproxy_unload_module(self, module):
self.mavproxy.send("module unload %s\n" % module)
self.mavproxy.expect("Unloaded module %s" % module)
def accelcal(self):
ex = None
try:
self.customise_SITL_commandline(["-M", "calibration"])
self.mavproxy_load_module("sitl_calibration")
self.mavproxy_load_module("calibration")
self.mavproxy_load_module("relay")
self.mavproxy.send("sitl_accelcal\n")
self.mavproxy.send("accelcal\n")
self.mavproxy.expect("Init Gyro")
self.mavproxy.expect("Calibrated")
for wanted in [ "level",
"on its LEFT side",
"on its RIGHT side",
"nose DOWN",
"nose UP",
"on its BACK",
]:
timeout = 2
self.mavproxy.expect("Place vehicle %s and press any key." % wanted, timeout=timeout)
self.mavproxy.expect("sitl_accelcal: sending attitude, please wait..", timeout=timeout)
self.mavproxy.expect("sitl_accelcal: attitude detected, please press any key..", timeout=timeout)
self.mavproxy.send("\n")
self.mavproxy.expect("APM: Calibration successful", timeout=timeout)
except Exception as e:
self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e
self.mavproxy_unload_module("relay")
self.mavproxy_unload_module("calibration")
self.mavproxy_unload_module("sitl_calibration")
if ex is not None:
raise ex
def test_button(self): def test_button(self):
self.set_parameter("SIM_PIN_MASK", 0) self.set_parameter("SIM_PIN_MASK", 0)
self.set_parameter("BTN_ENABLE", 1) self.set_parameter("BTN_ENABLE", 1)