From 9c0130d08ba37f2e5deb1fca4ff924e97749bf50 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Wed, 27 Nov 2024 14:22:34 +1100 Subject: [PATCH] autotest: add QuadPlane.RealFlightHover --- Tools/autotest/autotest.py | 5 ++ .../realflight-autotest-extra.parm | 2 + Tools/autotest/quadplane.py | 62 +++++++++++++++++++ Tools/autotest/vehicle_test_suite.py | 2 + 4 files changed, 71 insertions(+) create mode 100644 Tools/autotest/default_params/realflight-autotest-extra.parm diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 296c930d4faf7e..2004665f33972b 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -525,6 +525,8 @@ def run_step(step): } if opts.speedup is not None: fly_opts["speedup"] = opts.speedup + if opts.realflight_address is not None: + fly_opts["realflight_address"] = opts.realflight_address # handle "test.Copter" etc: if step in tester_class_map: @@ -1017,6 +1019,9 @@ def format_epilog(self, formatter): group_sim.add_option("", "--replay", action='store_true', help="enable replay logging for tests") + group_sim.add_option("--realflight-address", + default=None, + help="IP address of RealFlight simulator") parser.add_option_group(group_sim) group_completion = optparse.OptionGroup(parser, "Completion helpers") diff --git a/Tools/autotest/default_params/realflight-autotest-extra.parm b/Tools/autotest/default_params/realflight-autotest-extra.parm new file mode 100644 index 00000000000000..5e0e6d65425b90 --- /dev/null +++ b/Tools/autotest/default_params/realflight-autotest-extra.parm @@ -0,0 +1,2 @@ +SIM_RFL_OPTS,9 # Reset vehicle on start | Don't print frame rate stats +RC_PROTOCOLS,0x40000 # Only accept UDP RC input diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 0e6ef03d3f6c27..e81c20088bb75c 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -2072,6 +2072,64 @@ def WindEstimateConsistency(self): self.progress("Wind estimates correlated") break + def setup_RealFlight_vehicle(self, model, home): + ''' + Restart the SITL for RealFlight. RealFlight must already be running and + the correct airport and model must be loaded. + ''' + defaults_filepath = self.model_defaults_filepath(model) + extra_params = 'default_params/realflight-autotest-extra.parm' + defaults_filepath.append(os.path.join(testdir, extra_params)) + self.customise_SITL_commandline( + [ + f"--home={home}", + ], + model=f"flightaxis:{self.realflight_address}", + defaults_filepath=defaults_filepath + ) + + def RealFlightHover(self, model, home): + ''' + Perform a simple hover test in RealFlight. Useful for generating logs + for comparative analysis. + ''' + if not self.realflight_address: + self.progress("Specify an IP address with --realflight-address or REALFLIGHT_IPADDR to run this test") + return + + # Log fullrate attitude for PID Review Tool + self.set_parameters({ + "LOG_BITMASK": 0x10FFFF, + }) + self.setup_RealFlight_vehicle(model, home) + + self.wait_ready_to_arm() + self.change_mode("QLOITER") + self.arm_vehicle() + self.set_rc(3, 2000) + self.wait_altitude(8, 12, relative=True) + self.set_rc(3, 1500) + stick_deflections = [ + (2000, 1500, "Roll right"), + (1500, 1500, "Center"), + (1000, 1500, "Roll left"), + (1500, 1500, "Center"), + (1500, 2000, "Pitch forward"), + (1500, 1500, "Center"), + (1500, 1000, "Pitch back"), + (1500, 1500, "Center"), + ] + n_iterations = 10 + for i in range(n_iterations): + print(f"Control input cycle: {i+1}/{n_iterations}") + for roll, pitch, msg in stick_deflections: + self.progress(f"{msg}") + self.set_rc(1, roll) + self.set_rc(2, pitch) + self.delay_sim_time(0.5) + self.change_mode("QLAND") + self.wait_disarmed(timeout=120) + def tests(self): '''return list of all tests''' @@ -2123,5 +2181,9 @@ def tests(self): self.RTL_AUTOLAND_1, # as in fly-home then go to landing sequence self.RTL_AUTOLAND_1_FROM_GUIDED, # as in fly-home then go to landing sequence self.AHRSFlyForwardFlag, + Test(self.RealFlightHover, speedup=1, kwargs={ + 'model': 'realflight-titan-cobra', + 'home': 'EliField' + }), ]) return ret diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 5885c21267fc9f..1b2e463a1a4695 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -1906,6 +1906,7 @@ def __init__(self, dronecan_tests=False, generate_junit=False, enable_fgview=False, + realflight_address=None, build_opts={}): self.start_time = time.time() @@ -1973,6 +1974,7 @@ def __init__(self, self.in_drain_mav = False self.tlog = None self.enable_fgview = enable_fgview + self.realflight_address = realflight_address or os.getenv("REALFLIGHT_IPADDR") self.rc_thread = None self.rc_thread_should_quit = False