From 5bd67d8e04a67133f9d547bce582c009d88d3544 Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Sun, 1 Oct 2023 18:45:39 +0100 Subject: [PATCH] AP_Motors: Set default heli thrust linearisation to linear. --- libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp index a87e85c6c7..92d4f800c9 100644 --- a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp +++ b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp @@ -17,9 +17,10 @@ #endif #if APM_BUILD_TYPE(APM_BUILD_Heli) - #define THRST_LIN_THST_EXPO_DEFAULT 0.55f // set to 0 for linear and 1 for second order approximation - #define THRST_LIN_SPIN_MIN_DEFAULT 0.15f // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range - #define THRST_LIN_SPIN_MAX_DEFAULT 0.95f // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range + // defaults to no linearisation to not break users existing setups + #define THRST_LIN_THST_EXPO_DEFAULT 0.0f // set to 0 for linear and 1 for second order approximation + #define THRST_LIN_SPIN_MIN_DEFAULT 0.0f // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range + #define THRST_LIN_SPIN_MAX_DEFAULT 1.0f // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range #define THRST_LIN_BAT_VOLT_MAX_DEFAULT 0.0f // voltage limiting max default #define THRST_LIN_BAT_VOLT_MIN_DEFAULT 0.0f // voltage limiting min default (voltage dropping below this level will have no effect) #else