From 0e6b0cbf3576d9748bd0c66d863861181d3fa4a1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 11 Oct 2021 12:06:48 +1100 Subject: [PATCH] autotest: add trivial test for MegaSquirt EFI system --- Tools/autotest/arduplane.py | 23 +++++++++++++++++++++++ Tools/autotest/common.py | 11 +++++++---- 2 files changed, 30 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 50deb3bfb3..bd812f0915 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -10,6 +10,7 @@ from __future__ import print_function import math import os import signal +import sys import time from pymavlink import quaternion @@ -3172,6 +3173,24 @@ class AutoTestPlane(AutoTest): self.fly_home_land_and_disarm() + def MegaSquirt(self): + self.assert_not_receiving_message('EFI_STATUS') + self.set_parameters({ + 'SIM_EFI_TYPE': 1, + 'EFI_TYPE': 1, + 'SERIAL5_PROTOCOL': 24, + }) + self.customise_SITL_commandline(["--uartF=sim:megasquirt"]) + self.delay_sim_time(5) + m = self.assert_receive_message('EFI_STATUS') + mavutil.dump_message_verbose(sys.stdout, m) + if m.throttle_out != 0: + raise NotAchievedException("Expected zero throttle") + if m.health != 1: + raise NotAchievedException("Not healthy") + if m.intake_manifold_temperature < 20: + raise NotAchievedException("Bad intake manifold temperature") + def tests(self): '''return list of all tests''' ret = super(AutoTestPlane, self).tests() @@ -3405,6 +3424,10 @@ class AutoTestPlane(AutoTest): "Test AutoTune mode", self.AUTOTUNE), + ("MegaSquirt", + "Test MegaSquirt EFI", + self.MegaSquirt), + ("LogUpload", "Log upload", self.log_upload), diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 6f6cf006b8..14e275efdd 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -9296,11 +9296,14 @@ switch value''' want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) self.disarm_vehicle() - def test_pid_tuning(self): - self.progress("making sure we're not getting PID_TUNING messages") - m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=5) + def assert_not_receiving_message(self, message, timeout=1): + self.progress("making sure we're not getting %s messages" % message) + m = self.mav.recv_match(type=message, blocking=True, timeout=timeout) if m is not None: - raise PreconditionFailedException("Receiving PID_TUNING already") + raise PreconditionFailedException("Receiving %s messags" % message) + + def test_pid_tuning(self): + self.assert_not_receiving_message('PID_TUNING', timeout=5) self.set_parameter("GCS_PID_MASK", 1) self.progress("making sure we are now getting PID_TUNING messages") m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=5)