|
|
|
@ -5677,6 +5677,27 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
@@ -5677,6 +5677,27 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|
|
|
|
target_compid=target_compid, |
|
|
|
|
want_result=mavutil.mavlink.MAV_RESULT_FAILED) |
|
|
|
|
|
|
|
|
|
def FlashStorage(self): |
|
|
|
|
self.set_parameter("LOG_BITMASK", 1) |
|
|
|
|
self.reboot_sitl() |
|
|
|
|
|
|
|
|
|
self.customise_SITL_commandline([ |
|
|
|
|
"--set-storage-posix-enabled", "0", |
|
|
|
|
"--set-storage-flash-enabled", "1", |
|
|
|
|
]) |
|
|
|
|
if self.get_parameter("LOG_BITMASK") == 1: |
|
|
|
|
raise NotAchievedException("not using flash storage?") |
|
|
|
|
self.set_parameter("LOG_BITMASK", 2) |
|
|
|
|
self.reboot_sitl() |
|
|
|
|
self.assert_parameter_value("LOG_BITMASK", 2) |
|
|
|
|
self.set_parameter("LOG_BITMASK", 3) |
|
|
|
|
self.reboot_sitl() |
|
|
|
|
self.assert_parameter_value("LOG_BITMASK", 3) |
|
|
|
|
|
|
|
|
|
self.customise_SITL_commandline([]) |
|
|
|
|
# make sure we're back at our original value: |
|
|
|
|
self.assert_parameter_value("LOG_BITMASK", 1) |
|
|
|
|
|
|
|
|
|
def tests(self): |
|
|
|
|
'''return list of all tests''' |
|
|
|
|
ret = super(AutoTestRover, self).tests() |
|
|
|
@ -5899,6 +5920,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
@@ -5899,6 +5920,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|
|
|
|
"Test end mission behavior", |
|
|
|
|
self.test_end_mission_behavior), |
|
|
|
|
|
|
|
|
|
("FlashStorage", |
|
|
|
|
"Test flash storage (for parameters etc)", |
|
|
|
|
self.FlashStorage), |
|
|
|
|
|
|
|
|
|
("LogUpload", |
|
|
|
|
"Upload logs", |
|
|
|
|
self.log_upload), |
|
|
|
|