From 20f58afa9366c384a6ae19edc005cca697e18f75 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 13 Aug 2021 10:48:19 +1000 Subject: [PATCH] Tools: complete rewrite of the ESC-configuration state machine Co-authored-by: Dr.-Ing. Amilcar do Carmo Lucas tidy message sending using templates Calculate and enforce the minimum update period. Disable unused features to save flash forced time gaps between all transmits correct ESC reset functionality Avoid re-initialization repeatition Make sure we stop FETtec if safety is on (ignore reverse) this reduces duplicated code Error count calculation changed as the telemetry error count is absolute only the overflow status can be safed and used for the percentage calculation Update the README to add autotests information FETtec needs a time gap between frames This allows running at high fast_loop_rates do not send fast_throttle data if a configuration command just got sent Example parameter configuration file is for a Quadcopter with ESCs connected to Telem2 remove two FIXME fix compilation in master Fix the ESC not re-initializing issue. Now we re-init whenever we loose connection RVMASK parameter changes only take effect when not armed Improve documentation Always use the same wording when referring to fast-throttle commands fix pre-arm check message assure the length of the memmove is positive Set HAL_AP_FETTEC_CONFIGURE_ESCS to 0 when no ESC hardware is available and you want to test the UART send function --- Tools/autotest/arducopter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index d761367622..c0523ac964 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -7247,7 +7247,7 @@ class AutoTestCopter(AutoTest): if self.get_sim_time_cached() - tstart > 20: raise NotAchievedException("Expected mask to be only problem within 20 seconds") try: - self.assert_prearm_failure("Invalid motor mask; need consecuti") + self.assert_prearm_failure("Invalid motor mask") break except NotAchievedException: self.delay_sim_time(1)