Skip to content

Commit 322eb62

Browse files
committed
autotest: add test for defaults readonly parameters
1 parent 329a342 commit 322eb62

File tree

1 file changed

+42
-0
lines changed

1 file changed

+42
-0
lines changed

Tools/autotest/arducopter.py

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
import math
99
import os
1010
import shutil
11+
import tempfile
1112
import time
1213
import numpy
1314

@@ -11990,6 +11991,7 @@ def tests1e(self):
1199011991
self.MAV_CMD_NAV_RETURN_TO_LAUNCH,
1199111992
self.MAV_CMD_NAV_VTOL_LAND,
1199211993
self.clear_roi,
11994+
self.ReadOnlyDefaults,
1199311995
])
1199411996
return ret
1199511997

@@ -13410,6 +13412,46 @@ def CommonOrigin(self):
1341013412
# restart GPS driver
1341113413
self.reboot_sitl()
1341213414

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+
mavproxy.send(f"param ftpload {new_values_filepath.name}\n")
13447+
mavproxy.expect("Loaded")
13448+
self.delay_sim_time(1)
13449+
self.stop_mavproxy(mavproxy)
13450+
13451+
self.assert_parameter_value("DISARM_DELAY", 77)
13452+
self.assert_parameter_value("RTL_ALT", 111)
13453+
self.assert_parameter_value('RTL_ALT_FINAL', 101)
13454+
1341313455
def ScriptingFlipMode(self):
1341413456
'''test adding custom mode from scripting'''
1341513457
# Really it would be nice to check for the AVAILABLE_MODES message, but pymavlink does not understand them yet.

0 commit comments

Comments
 (0)