|
8 | 8 | import math
|
9 | 9 | import os
|
10 | 10 | import shutil
|
| 11 | +import tempfile |
11 | 12 | import time
|
12 | 13 | import numpy
|
13 | 14 |
|
@@ -11990,6 +11991,7 @@ def tests1e(self):
|
11990 | 11991 | self.MAV_CMD_NAV_RETURN_TO_LAUNCH,
|
11991 | 11992 | self.MAV_CMD_NAV_VTOL_LAND,
|
11992 | 11993 | self.clear_roi,
|
| 11994 | + self.ReadOnlyDefaults, |
11993 | 11995 | ])
|
11994 | 11996 | return ret
|
11995 | 11997 |
|
@@ -13410,6 +13412,48 @@ def CommonOrigin(self):
|
13410 | 13412 | # restart GPS driver
|
13411 | 13413 | self.reboot_sitl()
|
13412 | 13414 |
|
| 13415 | + def ReadOnlyDefaults(self): |
| 13416 | + '''test that defaults marked "readonly" can't be set''' |
| 13417 | + defaults_filepath = tempfile.NamedTemporaryFile(mode='w', delete=False) |
| 13418 | + defaults_filepath.write(""" |
| 13419 | +DISARM_DELAY 77 @READONLY |
| 13420 | +RTL_ALT 123 |
| 13421 | +RTL_ALT_FINAL 129 |
| 13422 | +""") |
| 13423 | + defaults_filepath.close() |
| 13424 | + self.customise_SITL_commandline([ |
| 13425 | + ], defaults_filepath=defaults_filepath.name) |
| 13426 | + |
| 13427 | + self.context_collect('STATUSTEXT') |
| 13428 | + self.send_set_parameter_direct("DISARM_DELAY", 88) |
| 13429 | + |
| 13430 | + self.wait_statustext("Param write denied (DISARM_DELAY)") |
| 13431 | + self.assert_parameter_value("DISARM_DELAY", 77) |
| 13432 | + self.assert_parameter_value("RTL_ALT", 123) |
| 13433 | + |
| 13434 | + self.start_subtest('Ensure something is writable....') |
| 13435 | + self.set_parameter('RTL_ALT_FINAL', 101) |
| 13436 | + |
| 13437 | + new_values_filepath = tempfile.NamedTemporaryFile(mode='w', delete=False) |
| 13438 | + new_values_filepath.write(""" |
| 13439 | +DISARM_DELAY 99 |
| 13440 | +RTL_ALT 111 |
| 13441 | +""") |
| 13442 | + new_values_filepath.close() |
| 13443 | + |
| 13444 | + self.start_subtest("Ensure parameters can't be set via FTP either") |
| 13445 | + mavproxy = self.start_mavproxy() |
| 13446 | + # can't do two FTP things at once, so wait until parameters are received |
| 13447 | + mavproxy.expect("Received .* parameters") |
| 13448 | + mavproxy.send(f"param ftpload {new_values_filepath.name}\n") |
| 13449 | + mavproxy.expect("Loaded") |
| 13450 | + self.delay_sim_time(1) |
| 13451 | + self.stop_mavproxy(mavproxy) |
| 13452 | + |
| 13453 | + self.assert_parameter_value("DISARM_DELAY", 77) |
| 13454 | + self.assert_parameter_value("RTL_ALT", 111) |
| 13455 | + self.assert_parameter_value('RTL_ALT_FINAL', 101) |
| 13456 | + |
13413 | 13457 | def ScriptingFlipMode(self):
|
13414 | 13458 | '''test adding custom mode from scripting'''
|
13415 | 13459 | # Really it would be nice to check for the AVAILABLE_MODES message, but pymavlink does not understand them yet.
|
|
0 commit comments