From 446b8ae3c415b05cbc10f25d196cff5c3af6094c Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Thu, 16 May 2024 12:41:13 +0200 Subject: [PATCH] FEATURE: Make sure step 19 has correct data to work with --- MethodicConfigurator/ArduCopter_configuration_steps.json | 3 +++ vehicle_templates/ArduCopter/X11_plus/07_esc.param | 2 ++ .../ArduCopter/diatone_taycan_mxc/4.5.1-params/07_esc.param | 2 ++ 3 files changed, 7 insertions(+) diff --git a/MethodicConfigurator/ArduCopter_configuration_steps.json b/MethodicConfigurator/ArduCopter_configuration_steps.json index 65eb18fb..2838cd4f 100644 --- a/MethodicConfigurator/ArduCopter_configuration_steps.json +++ b/MethodicConfigurator/ArduCopter_configuration_steps.json @@ -72,6 +72,9 @@ "external_tool_url": "https://www.mediafire.com/file/fj1p9qlbzo5bl5g/BLHeliSuite32_32.9.0.6.zip/file", "mandatory_text": "100% mandatory (0% optional)", "auto_changed_by": "", + "forced_parameters": { + "MOT_HOVER_LEARN": { "New Value": 2, "Change Reason": "So that it can tune the throttle controller on file 19" } + }, "derived_parameters": { "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, "SERVO_BLH_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" } diff --git a/vehicle_templates/ArduCopter/X11_plus/07_esc.param b/vehicle_templates/ArduCopter/X11_plus/07_esc.param index 132557a3..822c88b3 100644 --- a/vehicle_templates/ArduCopter/X11_plus/07_esc.param +++ b/vehicle_templates/ArduCopter/X11_plus/07_esc.param @@ -314,3 +314,5 @@ MOT_PWM_MIN,1050 MOT_SPOOL_TIME,3 TKOFF_SLEW_TIME,4 + +MOT_HOVER_LEARN,2 diff --git a/vehicle_templates/ArduCopter/diatone_taycan_mxc/4.5.1-params/07_esc.param b/vehicle_templates/ArduCopter/diatone_taycan_mxc/4.5.1-params/07_esc.param index 538c626c..8d21f7a3 100644 --- a/vehicle_templates/ArduCopter/diatone_taycan_mxc/4.5.1-params/07_esc.param +++ b/vehicle_templates/ArduCopter/diatone_taycan_mxc/4.5.1-params/07_esc.param @@ -27,3 +27,5 @@ SERVO4_MAX,2000 # Use the full available 1000-2000 DShot range SERVO4_MIN,1000 # Use the full available 1000-2000 DShot range SERVO4_TRIM,1000 # Use the full available 1000-2000 DShot range TKOFF_RPM_MIN,1400 # Our motors should idle at around 1400 RPM, see https://ardupilot.org/copter/docs/tkoff-rpm-min.html + +MOT_HOVER_LEARN,2