mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
Merge branch 'master' into patch_v3.1.6
This commit is contained in:
commit
de3d1d527d
197 changed files with 4476 additions and 4008 deletions
|
@ -28,6 +28,10 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
|
||||
|
@ -46,9 +50,6 @@
|
|||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
#define EXTERNAL_DSHOT_CONVERSION_FACTOR 2
|
||||
// (minimum output value(1001) - (minimum input value(48) / conversion factor(2))
|
||||
#define EXTERNAL_DSHOT_CONVERSION_OFFSET 977
|
||||
|
@ -62,12 +63,6 @@ static float motorMixRange;
|
|||
int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||
int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
static mixerConfig_t *mixerConfig;
|
||||
static flight3DConfig_t *flight3DConfig;
|
||||
static motorConfig_t *motorConfig;
|
||||
static airplaneConfig_t *airplaneConfig;
|
||||
rxConfig_t *rxConfig;
|
||||
|
||||
mixerMode_e currentMixerMode;
|
||||
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
|
@ -236,8 +231,6 @@ const mixer_t mixers[] = {
|
|||
};
|
||||
#endif
|
||||
|
||||
static motorMixer_t *customMixers;
|
||||
|
||||
static uint16_t disarmMotorOutput, deadbandMotor3dHigh, deadbandMotor3dLow;
|
||||
uint16_t motorOutputHigh, motorOutputLow;
|
||||
static float rcCommandThrottleRange, rcCommandThrottleRange3dLow, rcCommandThrottleRange3dHigh;
|
||||
|
@ -254,7 +247,7 @@ float getMotorMixRange()
|
|||
|
||||
bool isMotorProtocolDshot(void) {
|
||||
#ifdef USE_DSHOT
|
||||
switch(motorConfig->motorPwmProtocol) {
|
||||
switch(motorConfig()->dev.motorPwmProtocol) {
|
||||
case PWM_TYPE_DSHOT1200:
|
||||
case PWM_TYPE_DSHOT600:
|
||||
case PWM_TYPE_DSHOT300:
|
||||
|
@ -274,47 +267,31 @@ void initEscEndpoints(void) {
|
|||
if (isMotorProtocolDshot()) {
|
||||
disarmMotorOutput = DSHOT_DISARM_COMMAND;
|
||||
if (feature(FEATURE_3D))
|
||||
motorOutputLow = DSHOT_MIN_THROTTLE + lrintf(((DSHOT_3D_DEADBAND_LOW - DSHOT_MIN_THROTTLE) / 100.0f) * motorConfig->digitalIdleOffsetPercent);
|
||||
motorOutputLow = DSHOT_MIN_THROTTLE + lrintf(((DSHOT_3D_DEADBAND_LOW - DSHOT_MIN_THROTTLE) / 100.0f) * motorConfig()->digitalIdleOffsetPercent);
|
||||
else
|
||||
motorOutputLow = DSHOT_MIN_THROTTLE + lrintf(((DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) / 100.0f) * motorConfig->digitalIdleOffsetPercent);
|
||||
motorOutputLow = DSHOT_MIN_THROTTLE + lrintf(((DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) / 100.0f) * motorConfig()->digitalIdleOffsetPercent);
|
||||
motorOutputHigh = DSHOT_MAX_THROTTLE;
|
||||
deadbandMotor3dHigh = DSHOT_3D_DEADBAND_HIGH + lrintf(((DSHOT_MAX_THROTTLE - DSHOT_3D_DEADBAND_HIGH) / 100.0f) * motorConfig->digitalIdleOffsetPercent); // TODO - Not working yet !! Mixer requires some throttle rescaling changes
|
||||
deadbandMotor3dHigh = DSHOT_3D_DEADBAND_HIGH + lrintf(((DSHOT_MAX_THROTTLE - DSHOT_3D_DEADBAND_HIGH) / 100.0f) * motorConfig()->digitalIdleOffsetPercent); // TODO - Not working yet !! Mixer requires some throttle rescaling changes
|
||||
deadbandMotor3dLow = DSHOT_3D_DEADBAND_LOW;
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
disarmMotorOutput = (feature(FEATURE_3D)) ? flight3DConfig->neutral3d : motorConfig->mincommand;
|
||||
motorOutputLow = motorConfig->minthrottle;
|
||||
motorOutputHigh = motorConfig->maxthrottle;
|
||||
deadbandMotor3dHigh = flight3DConfig->deadband3d_high;
|
||||
deadbandMotor3dLow = flight3DConfig->deadband3d_low;
|
||||
disarmMotorOutput = (feature(FEATURE_3D)) ? flight3DConfig()->neutral3d : motorConfig()->mincommand;
|
||||
motorOutputLow = motorConfig()->minthrottle;
|
||||
motorOutputHigh = motorConfig()->maxthrottle;
|
||||
deadbandMotor3dHigh = flight3DConfig()->deadband3d_high;
|
||||
deadbandMotor3dLow = flight3DConfig()->deadband3d_low;
|
||||
}
|
||||
|
||||
rcCommandThrottleRange = (PWM_RANGE_MAX - rxConfig->mincheck);
|
||||
rcCommandThrottleRange3dLow = rxConfig->midrc - rxConfig->mincheck - flight3DConfig->deadband3d_throttle;
|
||||
rcCommandThrottleRange3dHigh = PWM_RANGE_MAX - rxConfig->midrc - flight3DConfig->deadband3d_throttle;
|
||||
rcCommandThrottleRange = (PWM_RANGE_MAX - rxConfig()->mincheck);
|
||||
rcCommandThrottleRange3dLow = rxConfig()->midrc - rxConfig()->mincheck - flight3DConfig()->deadband3d_throttle;
|
||||
rcCommandThrottleRange3dHigh = PWM_RANGE_MAX - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
|
||||
}
|
||||
|
||||
void mixerUseConfigs(
|
||||
flight3DConfig_t *flight3DConfigToUse,
|
||||
motorConfig_t *motorConfigToUse,
|
||||
mixerConfig_t *mixerConfigToUse,
|
||||
airplaneConfig_t *airplaneConfigToUse,
|
||||
rxConfig_t *rxConfigToUse)
|
||||
{
|
||||
flight3DConfig = flight3DConfigToUse;
|
||||
motorConfig = motorConfigToUse;
|
||||
mixerConfig = mixerConfigToUse;
|
||||
airplaneConfig = airplaneConfigToUse;
|
||||
rxConfig = rxConfigToUse;
|
||||
}
|
||||
|
||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *initialCustomMixers)
|
||||
void mixerInit(mixerMode_e mixerMode)
|
||||
{
|
||||
currentMixerMode = mixerMode;
|
||||
|
||||
customMixers = initialCustomMixers;
|
||||
|
||||
initEscEndpoints();
|
||||
}
|
||||
|
||||
|
@ -328,9 +305,9 @@ void mixerConfigureOutput(void)
|
|||
// load custom mixer into currentMixer
|
||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
// check if done
|
||||
if (customMixers[i].throttle == 0.0f)
|
||||
if (customMotorMixer(i)->throttle == 0.0f)
|
||||
break;
|
||||
currentMixer[i] = customMixers[i];
|
||||
currentMixer[i] = *customMotorMixer(i);
|
||||
motorCount++;
|
||||
}
|
||||
} else {
|
||||
|
@ -441,25 +418,25 @@ void mixTable(pidProfile_t *pidProfile)
|
|||
|
||||
// Find min and max throttle based on condition.
|
||||
if (feature(FEATURE_3D)) {
|
||||
if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming.
|
||||
if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig()->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming.
|
||||
|
||||
if ((rcCommand[THROTTLE] <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Out of band handling
|
||||
if ((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) { // Out of band handling
|
||||
motorOutputMax = deadbandMotor3dLow;
|
||||
motorOutputMin = motorOutputLow;
|
||||
throttlePrevious = rcCommand[THROTTLE];
|
||||
throttle = rcCommand[THROTTLE] - rxConfig->mincheck;
|
||||
throttle = rcCommand[THROTTLE] - rxConfig()->mincheck;
|
||||
currentThrottleInputRange = rcCommandThrottleRange3dLow;
|
||||
if(isMotorProtocolDshot()) mixerInversion = true;
|
||||
} else if (rcCommand[THROTTLE] >= (rxConfig->midrc + flight3DConfig->deadband3d_throttle)) { // Positive handling
|
||||
} else if (rcCommand[THROTTLE] >= (rxConfig()->midrc + flight3DConfig()->deadband3d_throttle)) { // Positive handling
|
||||
motorOutputMax = motorOutputHigh;
|
||||
motorOutputMin = deadbandMotor3dHigh;
|
||||
throttlePrevious = rcCommand[THROTTLE];
|
||||
throttle = rcCommand[THROTTLE] - rxConfig->midrc - flight3DConfig->deadband3d_throttle;
|
||||
throttle = rcCommand[THROTTLE] - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
|
||||
currentThrottleInputRange = rcCommandThrottleRange3dHigh;
|
||||
} else if ((throttlePrevious <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Deadband handling from negative to positive
|
||||
} else if ((throttlePrevious <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) { // Deadband handling from negative to positive
|
||||
motorOutputMax = deadbandMotor3dLow;
|
||||
motorOutputMin = motorOutputLow;
|
||||
throttle = rxConfig->midrc - flight3DConfig->deadband3d_throttle;
|
||||
throttle = rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
|
||||
currentThrottleInputRange = rcCommandThrottleRange3dLow;
|
||||
if(isMotorProtocolDshot()) mixerInversion = true;
|
||||
} else { // Deadband handling from positive to negative
|
||||
|
@ -469,7 +446,7 @@ void mixTable(pidProfile_t *pidProfile)
|
|||
currentThrottleInputRange = rcCommandThrottleRange3dHigh;
|
||||
}
|
||||
} else {
|
||||
throttle = rcCommand[THROTTLE] - rxConfig->mincheck;
|
||||
throttle = rcCommand[THROTTLE] - rxConfig()->mincheck;
|
||||
currentThrottleInputRange = rcCommandThrottleRange;
|
||||
motorOutputMin = motorOutputLow;
|
||||
motorOutputMax = motorOutputHigh;
|
||||
|
@ -485,7 +462,7 @@ void mixTable(pidProfile_t *pidProfile)
|
|||
}
|
||||
|
||||
// Calculate voltage compensation
|
||||
const float vbatCompensationFactor = (batteryConfig && pidProfile->vbatPidCompensation) ? calculateVbatPidCompensation() : 1.0f;
|
||||
const float vbatCompensationFactor = pidProfile->vbatPidCompensation ? calculateVbatPidCompensation() : 1.0f;
|
||||
|
||||
// Find roll/pitch/yaw desired output
|
||||
float motorMix[MAX_SUPPORTED_MOTORS];
|
||||
|
@ -494,7 +471,7 @@ void mixTable(pidProfile_t *pidProfile)
|
|||
motorMix[i] =
|
||||
scaledAxisPIDf[PITCH] * currentMixer[i].pitch +
|
||||
scaledAxisPIDf[ROLL] * currentMixer[i].roll +
|
||||
scaledAxisPIDf[YAW] * currentMixer[i].yaw * (-mixerConfig->yaw_motor_direction);
|
||||
scaledAxisPIDf[YAW] * currentMixer[i].yaw * (-mixerConfig()->yaw_motor_direction);
|
||||
|
||||
if (vbatCompensationFactor > 1.0f) {
|
||||
motorMix[i] *= vbatCompensationFactor; // Add voltage compensation
|
||||
|
@ -542,7 +519,7 @@ void mixTable(pidProfile_t *pidProfile)
|
|||
|
||||
// Motor stop handling
|
||||
if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !isAirmodeActive()) {
|
||||
if (((rcData[THROTTLE]) < rxConfig->mincheck)) {
|
||||
if (((rcData[THROTTLE]) < rxConfig()->mincheck)) {
|
||||
motor[i] = disarmMotorOutput;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue