mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-22 07:45:29 +03:00
Merge remote-tracking branch 'upstream/master' into blackbox-flash
This commit is contained in:
commit
acd4745a4e
65 changed files with 982 additions and 485 deletions
|
@ -27,45 +27,46 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/compass.h"
|
||||
|
||||
#include "io/statusindicator.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "io/serial.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/statusindicator.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
|
@ -110,7 +111,7 @@ profile_t *currentProfile;
|
|||
static uint8_t currentControlRateProfileIndex = 0;
|
||||
controlRateConfig_t *currentControlRateProfile;
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 90;
|
||||
static const uint8_t EEPROM_CONF_VERSION = 91;
|
||||
|
||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||
{
|
||||
|
@ -121,6 +122,8 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
|||
|
||||
static void resetPidProfile(pidProfile_t *pidProfile)
|
||||
{
|
||||
pidProfile->pidController = 0;
|
||||
|
||||
pidProfile->P8[ROLL] = 40;
|
||||
pidProfile->I8[ROLL] = 30;
|
||||
pidProfile->D8[ROLL] = 23;
|
||||
|
@ -231,15 +234,26 @@ void resetBatteryConfig(batteryConfig_t *batteryConfig)
|
|||
batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
|
||||
}
|
||||
|
||||
#ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
|
||||
#define FIRST_PORT_INDEX 1
|
||||
#define SECOND_PORT_INDEX 0
|
||||
#else
|
||||
#define FIRST_PORT_INDEX 0
|
||||
#define SECOND_PORT_INDEX 1
|
||||
#endif
|
||||
|
||||
void resetSerialConfig(serialConfig_t *serialConfig)
|
||||
{
|
||||
#ifdef SWAP_SERIAL_PORT_1_AND_2_DEFAULTS
|
||||
serialConfig->serial_port_scenario[0] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
serialConfig->serial_port_scenario[1] = lookupScenarioIndex(SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH);
|
||||
serialConfig->serial_port_scenario[FIRST_PORT_INDEX] = lookupScenarioIndex(SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH);
|
||||
|
||||
#ifdef CC3D
|
||||
// Temporary workaround for CC3D non-functional VCP when using OpenPilot bootloader.
|
||||
// This allows MSP connection via USART so the board can be reconfigured.
|
||||
serialConfig->serial_port_scenario[SECOND_PORT_INDEX] = lookupScenarioIndex(SCENARIO_MSP_ONLY);
|
||||
#else
|
||||
serialConfig->serial_port_scenario[0] = lookupScenarioIndex(SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH);
|
||||
serialConfig->serial_port_scenario[1] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
serialConfig->serial_port_scenario[SECOND_PORT_INDEX] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
#endif
|
||||
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
serialConfig->serial_port_scenario[2] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
#if (SERIAL_PORT_COUNT > 3)
|
||||
|
@ -386,7 +400,6 @@ static void resetConf(void)
|
|||
masterConfig.looptime = 3500;
|
||||
masterConfig.emf_avoidance = 0;
|
||||
|
||||
currentProfile->pidController = 0;
|
||||
resetPidProfile(¤tProfile->pidProfile);
|
||||
|
||||
resetControlRateConfig(&masterConfig.controlRateProfiles[0]);
|
||||
|
@ -472,7 +485,7 @@ static void resetConf(void)
|
|||
masterConfig.escAndServoConfig.maxthrottle = 2000;
|
||||
masterConfig.motor_pwm_rate = 32000;
|
||||
masterConfig.looptime = 2000;
|
||||
currentProfile->pidController = 3;
|
||||
currentProfile->pidProfile.pidController = 3;
|
||||
currentProfile->pidProfile.P8[ROLL] = 36;
|
||||
currentProfile->pidProfile.P8[PITCH] = 36;
|
||||
currentProfile->failsafeConfig.failsafe_delay = 2;
|
||||
|
@ -604,7 +617,7 @@ void activateConfig(void)
|
|||
useTelemetryConfig(&masterConfig.telemetryConfig);
|
||||
#endif
|
||||
|
||||
setPIDController(currentProfile->pidController);
|
||||
setPIDController(currentProfile->pidProfile.pidController);
|
||||
|
||||
#ifdef GPS
|
||||
gpsUseProfile(¤tProfile->gpsProfile);
|
||||
|
@ -630,7 +643,7 @@ void activateConfig(void)
|
|||
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
|
||||
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
||||
|
||||
configureIMU(
|
||||
imuConfigure(
|
||||
&imuRuntimeConfig,
|
||||
¤tProfile->pidProfile,
|
||||
¤tProfile->accDeadband,
|
||||
|
@ -676,7 +689,9 @@ void validateAndFixConfig(void)
|
|||
// rssi adc needs the same ports
|
||||
featureClear(FEATURE_RSSI_ADC);
|
||||
// current meter needs the same ports
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
|
||||
|
@ -709,13 +724,13 @@ void validateAndFixConfig(void)
|
|||
#endif
|
||||
|
||||
#if defined(NAZE) && defined(SONAR)
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM) && feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER)) {
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM) && feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(OLIMEXINO) && defined(SONAR)
|
||||
if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER)) {
|
||||
if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue