|
|
|
@ -3655,6 +3655,48 @@ switch value'''
@@ -3655,6 +3655,48 @@ switch value'''
|
|
|
|
|
if self.get_distance_int(gps1, gps2) > 1: |
|
|
|
|
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): |
|
|
|
|
self.set_parameter("SIM_PIN_MASK", 0) |
|
|
|
|
self.set_parameter("BTN_ENABLE", 1) |
|
|
|
|