Skip to content

Commit

Permalink
Merge Betaflight 2.6.1
Browse files Browse the repository at this point in the history
  • Loading branch information
kc10kevin committed Apr 25, 2016
2 parents 372b7e2 + 8e744e8 commit 1d8e3c7
Show file tree
Hide file tree
Showing 84 changed files with 4,473 additions and 1,243 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
*.dep
*.bak
*.uvgui.*
*.swp
*.save
.project
.settings
.cproject
Expand Down
50 changes: 44 additions & 6 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ FORKNAME = betaflight

CC3D_TARGETS = CC3D CC3D_OPBL

VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI KBCC3DF3
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO KBCC3DF3 DOGE

# Valid targets for OP VCP support
VCP_VALID_TARGETS = $(CC3D_TARGETS)
Expand All @@ -52,10 +52,9 @@ OPBL_VALID_TARGETS = CC3D_OPBL

64K_TARGETS = CJMCU
128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI KBCC3DF3

F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI KBCC3DF3
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO KBCC3DF3 DOGE

F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO KBCC3DF3 DOGE

# Configure default flash sizes for the targets
ifeq ($(FLASH_SIZE),)
Expand Down Expand Up @@ -303,7 +302,9 @@ COMMON_SRC = build_config.c \
io/rc_controls.c \
io/rc_curves.c \
io/serial.c \
io/serial_1wire.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
io/serial_4way_stk500v2.c \
io/serial_cli.c \
io/serial_msp.c \
io/statusindicator.c \
Expand Down Expand Up @@ -352,7 +353,8 @@ VCP_SRC = \
vcp/usb_istr.c \
vcp/usb_prop.c \
vcp/usb_pwr.c \
drivers/serial_usb_vcp.c
drivers/serial_usb_vcp.c \
drivers/usb_io.c

NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/accgyro_adxl345.c \
Expand Down Expand Up @@ -621,6 +623,20 @@ LUX_RACE_SRC = \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCP_SRC)

DOGE_SRC = \
$(STM32F30x_COMMON_SRC) \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_bmp280.c \
drivers/barometer_spi_bmp280.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_usb_vcp.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCP_SRC)

SPARKY_SRC = \
$(STM32F30x_COMMON_SRC) \
Expand Down Expand Up @@ -705,6 +721,28 @@ IRCFUSIONF3_SRC = \
$(HIGHEND_SRC) \
$(COMMON_SRC)

SPRACINGF3EVO_SRC = \
$(STM32F30x_COMMON_SRC) \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_bmp280.c \
drivers/compass_ak8963.c \
drivers/display_ug2864hsweg01.h \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_usb_vcp.c \
drivers/sdcard.c \
drivers/sdcard_standard.c \
drivers/transponder_ir.c \
drivers/transponder_ir_stm32f30x.c \
io/asyncfatfs/asyncfatfs.c \
io/asyncfatfs/fat_standard.c \
io/transponder_ir.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCP_SRC)

MOTOLAB_SRC = \
$(STM32F30x_COMMON_SRC) \
drivers/accgyro_mpu.c \
Expand Down
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ Cleanflight also has additional features not found in baseflight.
* Graupner HoTT telemetry.
* Multiple simultaneous telemetry providers.
* Configurable serial ports for Serial RX, Telemetry, MSP, GPS - Use most devices on any port, softserial too.
* Optional lost buzzer on port 6 for CC3D (set enable_buzzer_p6 = ON)
* And many more minor bug fixes.

For a list of features, changes and some discussion please review the thread on MultiWii forums and consult the documentation.
Expand Down
4 changes: 3 additions & 1 deletion fake_travis_build.sh
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ targets=("PUBLISHMETA=True" \
"TARGET=COLIBRI_RACE" \
"TARGET=LUX_RACE" \
"TARGET=SPRACINGF3" \
"TARGET=SPRACINGF3EVO" \
"TARGET=SPRACINGF3MINI" \
"TARGET=NAZE" \
"TARGET=AFROMINI" \
Expand All @@ -14,7 +15,8 @@ targets=("PUBLISHMETA=True" \
"TARGET=MOTOLAB" \
"TARGET=IRCFUSIONF3" \
"TARGET=ALIENFLIGHTF1" \
"TARGET=ALIENFLIGHTF3")
"TARGET=ALIENFLIGHTF3" \
"TARGET=DOGE")

#fake a travis build environment
export TRAVIS_BUILD_NUMBER=$(date +%s)
Expand Down
6 changes: 1 addition & 5 deletions src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -401,11 +401,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {
return currentProfile->pidProfile.D_f[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
} else {
return currentProfile->pidProfile.D8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
}
return currentProfile->pidProfile.D8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;

case FLIGHT_LOG_FIELD_CONDITION_MAG:
#ifdef MAG
Expand Down
23 changes: 23 additions & 0 deletions src/main/common/filter.c
Original file line number Diff line number Diff line change
Expand Up @@ -96,3 +96,26 @@ float applyBiQuadFilter(float sample, biquad_t *state)

return result;
}

int32_t filterApplyAverage(int32_t input, uint8_t averageCount, int32_t averageState[DELTA_MAX_SAMPLES]) {
int count;
int32_t averageSum = 0;

for (count = averageCount-1; count > 0; count--) averageState[count] = averageState[count-1];
averageState[0] = input;
for (count = 0; count < averageCount; count++) averageSum += averageState[count];

return averageSum / averageCount;
}

float filterApplyAveragef(float input, uint8_t averageCount, float averageState[DELTA_MAX_SAMPLES]) {
int count;
float averageSum = 0.0f;

for (count = averageCount-1; count > 0; count--) averageState[count] = averageState[count-1];
averageState[0] = input;
for (count = 0; count < averageCount; count++) averageSum += averageState[count];

return averageSum / averageCount;
}

4 changes: 4 additions & 0 deletions src/main/common/filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/

#define DELTA_MAX_SAMPLES 12

typedef struct filterStatePt1_s {
float state;
float RC;
Expand All @@ -29,4 +31,6 @@ typedef struct biquad_s {

float applyBiQuadFilter(float sample, biquad_t *state);
float filterApplyPt1(float input, filterStatePt1_t *filter, float f_cut, float dt);
int32_t filterApplyAverage(int32_t input, uint8_t averageCount, int32_t averageState[DELTA_MAX_SAMPLES]);
float filterApplyAveragef(float input, uint8_t averageCount, float averageState[DELTA_MAX_SAMPLES]);
void BiQuadNewLpf(float filterCutFreq, biquad_t *newState, uint32_t refreshRate);
63 changes: 31 additions & 32 deletions src/main/config/config.c
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ static uint32_t activeFeaturesLatch = 0;
static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile;

static const uint8_t EEPROM_CONF_VERSION = 129;
static const uint8_t EEPROM_CONF_VERSION = 131;

static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
{
Expand All @@ -147,14 +147,14 @@ static void resetPidProfile(pidProfile_t *pidProfile)
{
pidProfile->pidController = 1;

pidProfile->P8[ROLL] = 42;
pidProfile->I8[ROLL] = 40;
pidProfile->P8[ROLL] = 45;
pidProfile->I8[ROLL] = 30;
pidProfile->D8[ROLL] = 18;
pidProfile->P8[PITCH] = 54;
pidProfile->I8[PITCH] = 40;
pidProfile->D8[PITCH] = 22;
pidProfile->P8[PITCH] = 45;
pidProfile->I8[PITCH] = 30;
pidProfile->D8[PITCH] = 18;
pidProfile->P8[YAW] = 90;
pidProfile->I8[YAW] = 50;
pidProfile->I8[YAW] = 40;
pidProfile->D8[YAW] = 0;
pidProfile->P8[PIDALT] = 50;
pidProfile->I8[PIDALT] = 0;
Expand All @@ -168,31 +168,23 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
pidProfile->P8[PIDLEVEL] = 30;
pidProfile->I8[PIDLEVEL] = 30;
pidProfile->P8[PIDLEVEL] = 50;
pidProfile->I8[PIDLEVEL] = 50;
pidProfile->D8[PIDLEVEL] = 100;
pidProfile->P8[PIDMAG] = 40;
pidProfile->P8[PIDVEL] = 120;
pidProfile->I8[PIDVEL] = 45;
pidProfile->D8[PIDVEL] = 1;
pidProfile->P8[PIDVEL] = 55;
pidProfile->I8[PIDVEL] = 55;
pidProfile->D8[PIDVEL] = 75;

pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->yaw_lpf_hz = 70.0f;
pidProfile->dterm_average_count = 4;
pidProfile->dterm_lpf_hz = 0; // filtering ON by default
pidProfile->rollPitchItermResetRate = 200;
pidProfile->yawItermResetRate = 50;
pidProfile->dterm_lpf_hz = 70.0f; // filtering ON by default
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;

pidProfile->P_f[ROLL] = 1.1f;
pidProfile->I_f[ROLL] = 0.4f;
pidProfile->D_f[ROLL] = 0.01f;
pidProfile->P_f[PITCH] = 1.4f;
pidProfile->I_f[PITCH] = 0.4f;
pidProfile->D_f[PITCH] = 0.01f;
pidProfile->P_f[YAW] = 4.0f;
pidProfile->I_f[YAW] = 0.4f;
pidProfile->D_f[YAW] = 0.00f;
pidProfile->A_level = 4.0f;
pidProfile->H_level = 4.0f;
pidProfile->H_sensitivity = 75;
pidProfile->H_sensitivity = 75; // TODO - Cleanup during next EEPROM changes

#ifdef GTUNE
pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
Expand Down Expand Up @@ -272,6 +264,7 @@ void resetBatteryConfig(batteryConfig_t *batteryConfig)
batteryConfig->vbatmaxcellvoltage = 43;
batteryConfig->vbatmincellvoltage = 33;
batteryConfig->vbatwarningcellvoltage = 35;
batteryConfig->vbathysteresis = 1;
batteryConfig->vbatPidCompensation = 0;
batteryConfig->currentMeterOffset = 0;
batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
Expand Down Expand Up @@ -312,15 +305,15 @@ void resetSerialConfig(serialConfig_t *serialConfig)

static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcExpo8 = 70;
controlRateConfig->rcExpo8 = 60;
controlRateConfig->thrMid8 = 50;
controlRateConfig->thrExpo8 = 0;
controlRateConfig->dynThrPID = 0;
controlRateConfig->rcYawExpo8 = 20;
controlRateConfig->tpa_breakpoint = 1500;

for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
controlRateConfig->rates[axis] = 0;
controlRateConfig->rates[axis] = 50;
}

}
Expand Down Expand Up @@ -387,7 +380,7 @@ static void resetConf(void)
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerMode = MIXER_QUADX;
featureClearAll();
#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(KBCC3DF3)
#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(KBCC3DF3) || defined(DOGE)
featureSet(FEATURE_RX_PPM);
#endif

Expand All @@ -410,7 +403,7 @@ static void resetConf(void)
masterConfig.dcm_ki = 0; // 0.003 * 10000
masterConfig.gyro_lpf = 0; // 256HZ default
masterConfig.gyro_sync_denom = 8;
masterConfig.gyro_soft_lpf_hz = 60;
masterConfig.gyro_soft_lpf_hz = 80.0f;

masterConfig.pid_process_denom = 1;

Expand Down Expand Up @@ -459,14 +452,13 @@ static void resetConf(void)
masterConfig.rxConfig.rcSmoothing = 0;
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
masterConfig.rxConfig.max_aux_channel = 6;
masterConfig.rxConfig.acroPlusFactor = 30;
masterConfig.rxConfig.acroPlusOffset = 40;
masterConfig.rxConfig.superExpoFactor = 30;

resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);

masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;

masterConfig.retarded_arm = 0; // TODO - Cleanup retarded arm support
masterConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
masterConfig.disarm_kill_switch = 1;
masterConfig.auto_disarm_delay = 5;
masterConfig.small_angle = 25;
Expand Down Expand Up @@ -601,6 +593,13 @@ static void resetConf(void)
featureSet(FEATURE_FAILSAFE);
#endif

#ifdef SPRACINGF3EVO
featureSet(FEATURE_TRANSPONDER);
featureSet(FEATURE_RSSI_ADC);
featureSet(FEATURE_CURRENT_METER);
featureSet(FEATURE_TELEMETRY);
#endif

// alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
#ifdef ALIENFLIGHT
featureSet(FEATURE_RX_SERIAL);
Expand Down
2 changes: 1 addition & 1 deletion src/main/config/config_master.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ typedef struct master_t {
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.


uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
uint8_t gyro_cal_on_first_arm; // allow disarm/arm on throttle down + roll left/right
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
uint8_t small_angle;
Expand Down
3 changes: 2 additions & 1 deletion src/main/config/runtime_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,8 @@
typedef enum {
OK_TO_ARM = (1 << 0),
PREVENT_ARMING = (1 << 1),
ARMED = (1 << 2)
ARMED = (1 << 2),
WAS_EVER_ARMED = (1 << 3)
} armingFlag_e;

extern uint8_t armingFlags;
Expand Down
1 change: 1 addition & 0 deletions src/main/drivers/accgyro_mpu6500.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#define MPU6500_WHO_AM_I_CONST (0x70)
#define MPU9250_WHO_AM_I_CONST (0x71)
#define ICM20608G_WHO_AM_I_CONST (0xAF)

#define MPU6500_BIT_RESET (0x80)

Expand Down
2 changes: 2 additions & 0 deletions src/main/drivers/accgyro_spi_mpu6000.c
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,8 @@ void mpu6000SpiGyroInit(uint8_t lpf)
mpu6000WriteRegister(MPU6000_CONFIG, lpf);
delayMicroseconds(1);

spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock

int16_t data[3];
mpuGyroRead(data);

Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/accgyro_spi_mpu6500.c
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ bool mpu6500SpiDetect(void)

mpu6500ReadRegister(MPU_RA_WHO_AM_I, 1, &tmp);

if (tmp == MPU6500_WHO_AM_I_CONST || tmp == MPU9250_WHO_AM_I_CONST) {
if (tmp == MPU6500_WHO_AM_I_CONST || tmp == MPU9250_WHO_AM_I_CONST || tmp == ICM20608G_WHO_AM_I_CONST) {
return true;
}

Expand Down
Loading

0 comments on commit 1d8e3c7

Please sign in to comment.