AP_Motors: Set default heli thrust linearisation to linear.

This commit is contained in:
Gone4Dirt 2023-10-01 18:45:39 +01:00 committed by Andrew Tridgell
parent 55d7965379
commit 5bd67d8e04
1 changed files with 4 additions and 3 deletions

View File

@ -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