mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 23:35:34 +03:00
Merge branch 'master' into patch_v3.1.4
This commit is contained in:
commit
ecb104b1f1
150 changed files with 3461 additions and 2167 deletions
|
@ -29,12 +29,18 @@
|
|||
|
||||
#include "cms/cms.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/color.h"
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/io.h"
|
||||
|
@ -45,6 +51,7 @@
|
|||
#include "drivers/rx_pwm.h"
|
||||
#include "drivers/rx_spi.h"
|
||||
#include "drivers/sdcard.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
#include "drivers/system.h"
|
||||
|
@ -56,42 +63,37 @@
|
|||
#include "fc/fc_rc.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/motors.h"
|
||||
#include "io/servos.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/motors.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/servos.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#ifndef DEFAULT_RX_FEATURE
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
|
||||
#endif
|
||||
|
@ -544,7 +546,7 @@ uint8_t getCurrentProfile(void)
|
|||
return masterConfig.current_profile_index;
|
||||
}
|
||||
|
||||
void setProfile(uint8_t profileIndex)
|
||||
static void setProfile(uint8_t profileIndex)
|
||||
{
|
||||
currentProfile = &masterConfig.profile[profileIndex];
|
||||
currentControlRateProfileIndex = currentProfile->activeRateProfile;
|
||||
|
@ -866,11 +868,14 @@ void createDefaultConfig(master_t *config)
|
|||
}
|
||||
}
|
||||
|
||||
static void resetConf(void)
|
||||
void resetConfigs(void)
|
||||
{
|
||||
createDefaultConfig(&masterConfig);
|
||||
pgResetAll(MAX_PROFILE_COUNT);
|
||||
pgActivateProfile(0);
|
||||
|
||||
setProfile(0);
|
||||
setControlRateProfile(0);
|
||||
|
||||
#ifdef LED_STRIP
|
||||
reevaluateLedConfig();
|
||||
|
@ -883,32 +888,19 @@ void activateConfig(void)
|
|||
|
||||
resetAdjustmentStates();
|
||||
|
||||
useRcControlsConfig(
|
||||
modeActivationProfile()->modeActivationConditions,
|
||||
&masterConfig.motorConfig,
|
||||
¤tProfile->pidProfile
|
||||
);
|
||||
|
||||
#ifdef TELEMETRY
|
||||
telemetryUseConfig(&masterConfig.telemetryConfig);
|
||||
#endif
|
||||
useRcControlsConfig(modeActivationProfile()->modeActivationConditions, ¤tProfile->pidProfile);
|
||||
useAdjustmentConfig(¤tProfile->pidProfile);
|
||||
|
||||
#ifdef GPS
|
||||
gpsUseProfile(&masterConfig.gpsProfile);
|
||||
gpsUsePIDs(¤tProfile->pidProfile);
|
||||
#endif
|
||||
|
||||
useFailsafeConfig(&masterConfig.failsafeConfig);
|
||||
setAccelerationTrims(&accelerometerConfig()->accZero);
|
||||
failsafeReset();
|
||||
setAccelerationTrims(&accelerometerConfigMutable()->accZero);
|
||||
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
|
||||
|
||||
mixerUseConfigs(
|
||||
&masterConfig.flight3DConfig,
|
||||
&masterConfig.motorConfig,
|
||||
&masterConfig.mixerConfig,
|
||||
&masterConfig.airplaneConfig,
|
||||
&masterConfig.rxConfig
|
||||
);
|
||||
mixerUseConfigs(&masterConfig.airplaneConfig);
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoProfile.servoConf, &masterConfig.gimbalConfig);
|
||||
|
@ -921,22 +913,13 @@ void activateConfig(void)
|
|||
throttleCorrectionConfig()->throttle_correction_angle
|
||||
);
|
||||
|
||||
configureAltitudeHold(
|
||||
¤tProfile->pidProfile,
|
||||
&masterConfig.barometerConfig,
|
||||
&masterConfig.rcControlsConfig,
|
||||
&masterConfig.motorConfig
|
||||
);
|
||||
|
||||
#ifdef BARO
|
||||
useBarometerConfig(&masterConfig.barometerConfig);
|
||||
#endif
|
||||
configureAltitudeHold(¤tProfile->pidProfile);
|
||||
}
|
||||
|
||||
void validateAndFixConfig(void)
|
||||
{
|
||||
if ((motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)) {
|
||||
motorConfig()->mincommand = 1000;
|
||||
if((motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)){
|
||||
motorConfigMutable()->mincommand = 1000;
|
||||
}
|
||||
|
||||
if ((motorConfig()->motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
|
||||
|
@ -1053,18 +1036,18 @@ void validateAndFixGyroConfig(void)
|
|||
{
|
||||
// Prevent invalid notch cutoff
|
||||
if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
|
||||
gyroConfig()->gyro_soft_notch_hz_1 = 0;
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
|
||||
}
|
||||
if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
|
||||
gyroConfig()->gyro_soft_notch_hz_2 = 0;
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
|
||||
}
|
||||
|
||||
float samplingTime = 0.000125f;
|
||||
|
||||
if (gyroConfig()->gyro_lpf != GYRO_LPF_256HZ && gyroConfig()->gyro_lpf != GYRO_LPF_NONE) {
|
||||
pidConfig()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
|
||||
gyroConfig()->gyro_sync_denom = 1;
|
||||
gyroConfig()->gyro_use_32khz = false;
|
||||
pidConfigMutable()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
|
||||
gyroConfigMutable()->gyro_sync_denom = 1;
|
||||
gyroConfigMutable()->gyro_use_32khz = false;
|
||||
samplingTime = 0.001f;
|
||||
}
|
||||
|
||||
|
@ -1072,18 +1055,18 @@ void validateAndFixGyroConfig(void)
|
|||
samplingTime = 0.00003125;
|
||||
// F1 and F3 can't handle high sample speed.
|
||||
#if defined(STM32F1)
|
||||
gyroConfig()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
|
||||
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
|
||||
#elif defined(STM32F3)
|
||||
gyroConfig()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
|
||||
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
|
||||
#endif
|
||||
} else {
|
||||
#if defined(STM32F1)
|
||||
gyroConfig()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
|
||||
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if !defined(GYRO_USES_SPI) || !defined(USE_MPU_DATA_READY_SIGNAL)
|
||||
gyroConfig()->gyro_isr_update = false;
|
||||
gyroConfigMutable()->gyro_isr_update = false;
|
||||
#endif
|
||||
|
||||
// check for looptime restrictions based on motor protocol. Motor times have safety margin
|
||||
|
@ -1113,7 +1096,7 @@ void validateAndFixGyroConfig(void)
|
|||
|
||||
if (pidLooptime < motorUpdateRestriction) {
|
||||
const uint8_t maxPidProcessDenom = constrain(motorUpdateRestriction / (samplingTime * gyroConfig()->gyro_sync_denom), 1, MAX_PID_PROCESS_DENOM);
|
||||
pidConfig()->pid_process_denom = MIN(pidConfig()->pid_process_denom, maxPidProcessDenom);
|
||||
pidConfigMutable()->pid_process_denom = MIN(pidConfigMutable()->pid_process_denom, maxPidProcessDenom);
|
||||
}
|
||||
|
||||
// Prevent overriding the max rate of motors
|
||||
|
@ -1121,25 +1104,57 @@ void validateAndFixGyroConfig(void)
|
|||
uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
|
||||
|
||||
if(motorConfig()->motorPwmRate > maxEscRate)
|
||||
motorConfig()->motorPwmRate = maxEscRate;
|
||||
motorConfigMutable()->motorPwmRate = maxEscRate;
|
||||
}
|
||||
}
|
||||
|
||||
void readEEPROM(void)
|
||||
{
|
||||
suspendRxSignal();
|
||||
|
||||
// Sanity check, read flash
|
||||
if (!loadEEPROM()) {
|
||||
failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
|
||||
}
|
||||
|
||||
// pgActivateProfile(getCurrentProfile());
|
||||
// setControlRateProfile(rateProfileSelection()->defaultRateProfileIndex);
|
||||
|
||||
if (masterConfig.current_profile_index > MAX_PROFILE_COUNT - 1) {// sanity check
|
||||
masterConfig.current_profile_index = 0;
|
||||
}
|
||||
|
||||
setProfile(masterConfig.current_profile_index);
|
||||
|
||||
validateAndFixConfig();
|
||||
activateConfig();
|
||||
|
||||
resumeRxSignal();
|
||||
}
|
||||
|
||||
void writeEEPROM(void)
|
||||
{
|
||||
suspendRxSignal();
|
||||
|
||||
writeConfigToEEPROM();
|
||||
|
||||
resumeRxSignal();
|
||||
}
|
||||
|
||||
void resetEEPROM(void)
|
||||
{
|
||||
resetConfigs();
|
||||
writeEEPROM();
|
||||
}
|
||||
|
||||
void ensureEEPROMContainsValidData(void)
|
||||
{
|
||||
if (isEEPROMContentValid()) {
|
||||
return;
|
||||
}
|
||||
|
||||
resetEEPROM();
|
||||
}
|
||||
|
||||
void resetEEPROM(void)
|
||||
{
|
||||
resetConf();
|
||||
writeEEPROM();
|
||||
}
|
||||
|
||||
void saveConfigAndNotify(void)
|
||||
{
|
||||
writeEEPROM();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue