1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +03:00

merge upstream into sirinfpv-dev branch

This commit is contained in:
Evgeny Sychov 2016-06-13 09:41:19 -07:00
commit 21b5dce0e9
416 changed files with 156557 additions and 11350 deletions

View file

@ -37,6 +37,7 @@
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/gyro_sync.h"
#include "drivers/pwm_output.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
@ -79,7 +80,11 @@
#endif
#define BRUSHED_MOTORS_PWM_RATE 16000
#ifdef STM32F4
#define BRUSHLESS_MOTORS_PWM_RATE 2000
#else
#define BRUSHLESS_MOTORS_PWM_RATE 400
#endif
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
@ -100,6 +105,15 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#ifdef STM32F10X_HD
#define FLASH_PAGE_SIZE ((uint16_t)0x800)
#endif
#if defined(STM32F40_41xxx)
#define FLASH_PAGE_SIZE ((uint32_t)0x20000)
#endif
#if defined (STM32F411xE)
#define FLASH_PAGE_SIZE ((uint32_t)0x20000)
#endif
#endif
#if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT)
@ -113,8 +127,14 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#endif
#if defined(FLASH_SIZE)
#if defined(STM32F40_41xxx)
#define FLASH_PAGE_COUNT 4 // just to make calculations work
#elif defined (STM32F411xE)
#define FLASH_PAGE_COUNT 4 // just to make calculations work
#else
#define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
#endif
#endif
#if !defined(FLASH_PAGE_SIZE)
#error "Flash page size not defined for target."
@ -136,8 +156,10 @@ size_t custom_flash_memory_address = 0;
#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
#else
// use the last flash pages for storage
#ifndef CONFIG_START_FLASH_ADDRESS
#define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
#endif
#endif
master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile;
@ -313,7 +335,8 @@ void resetSerialConfig(serialConfig_t *serialConfig)
serialConfig->reboot_character = 'R';
}
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
{
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcYawRate8 = 100;
controlRateConfig->rcExpo8 = 10;
@ -329,14 +352,16 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
}
void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) {
void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
{
rcControlsConfig->deadband = 0;
rcControlsConfig->yaw_deadband = 0;
rcControlsConfig->alt_hold_deadband = 40;
rcControlsConfig->alt_hold_fast_change = 1;
}
void resetMixerConfig(mixerConfig_t *mixerConfig) {
void resetMixerConfig(mixerConfig_t *mixerConfig)
{
mixerConfig->yaw_motor_direction = 1;
#ifdef USE_SERVOS
mixerConfig->tri_unarmed_servo = 1;
@ -362,14 +387,15 @@ uint8_t getCurrentControlRateProfile(void)
return currentControlRateProfileIndex;
}
static void setControlRateProfile(uint8_t profileIndex) {
static void setControlRateProfile(uint8_t profileIndex)
{
currentControlRateProfileIndex = profileIndex;
masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
}
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) {
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex)
{
return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
}
@ -400,6 +426,9 @@ static void resetConf(void)
//masterConfig.batteryConfig.vbatscale = 20;
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS;
masterConfig.blackbox_device = 1;
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
#endif
#ifdef OSD
@ -483,7 +512,11 @@ static void resetConf(void)
masterConfig.rxConfig.rssi_ppm_invert = 0;
masterConfig.rxConfig.rcSmoothing = 0;
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
#ifdef STM32F4
masterConfig.rxConfig.max_aux_channel = 99;
#else
masterConfig.rxConfig.max_aux_channel = 6;
#endif
masterConfig.rxConfig.airModeActivateThreshold = 1350;
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
@ -505,12 +538,13 @@ static void resetConf(void)
#ifdef BRUSHED_MOTORS
masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
masterConfig.motor_pwm_protocol = PWM_TYPE_BRUSHED;
#else
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125;
#endif
masterConfig.servo_pwm_rate = 50;
masterConfig.fast_pwm_protocol = 1;
masterConfig.use_unsyncedPwm = 0;
#ifdef CC3D
masterConfig.use_buzzer_p6 = 0;
#endif
@ -632,10 +666,11 @@ static void resetConf(void)
masterConfig.batteryConfig.vbatmincellvoltage = 30;
#endif
// alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
#ifdef ALIENFLIGHT
featureSet(FEATURE_RX_SERIAL);
featureSet(FEATURE_MOTOR_STOP);
#if defined(TARGET_CONFIG)
targetConfiguration(&masterConfig);
#endif
#if defined(ALIENFLIGHT)
featureClear(FEATURE_ONESHOT125);
#ifdef ALIENFLIGHTF3
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
@ -650,6 +685,7 @@ static void resetConf(void)
masterConfig.escAndServoConfig.minthrottle = 1000;
masterConfig.escAndServoConfig.maxthrottle = 2000;
masterConfig.motor_pwm_rate = 32000;
masterConfig.motor_pwm_protocol = PWM_TYPE_BRUSHED;
currentProfile->pidProfile.pidController = 2;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
@ -659,57 +695,18 @@ static void resetConf(void)
currentControlRateProfile->rates[FD_YAW] = 20;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
// { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R
masterConfig.customMotorMixer[0].throttle = 1.0f;
masterConfig.customMotorMixer[0].roll = -0.414178f;
masterConfig.customMotorMixer[0].pitch = 1.0f;
masterConfig.customMotorMixer[0].yaw = -1.0f;
// { 1.0f, -0.414178f, -1.0f, 1.0f }, // FRONT_R
masterConfig.customMotorMixer[1].throttle = 1.0f;
masterConfig.customMotorMixer[1].roll = -0.414178f;
masterConfig.customMotorMixer[1].pitch = -1.0f;
masterConfig.customMotorMixer[1].yaw = 1.0f;
// { 1.0f, 0.414178f, 1.0f, 1.0f }, // REAR_L
masterConfig.customMotorMixer[2].throttle = 1.0f;
masterConfig.customMotorMixer[2].roll = 0.414178f;
masterConfig.customMotorMixer[2].pitch = 1.0f;
masterConfig.customMotorMixer[2].yaw = 1.0f;
// { 1.0f, 0.414178f, -1.0f, -1.0f }, // FRONT_L
masterConfig.customMotorMixer[3].throttle = 1.0f;
masterConfig.customMotorMixer[3].roll = 0.414178f;
masterConfig.customMotorMixer[3].pitch = -1.0f;
masterConfig.customMotorMixer[3].yaw = -1.0f;
// { 1.0f, -1.0f, -0.414178f, -1.0f }, // MIDFRONT_R
masterConfig.customMotorMixer[4].throttle = 1.0f;
masterConfig.customMotorMixer[4].roll = -1.0f;
masterConfig.customMotorMixer[4].pitch = -0.414178f;
masterConfig.customMotorMixer[4].yaw = -1.0f;
// { 1.0f, 1.0f, -0.414178f, 1.0f }, // MIDFRONT_L
masterConfig.customMotorMixer[5].throttle = 1.0f;
masterConfig.customMotorMixer[5].roll = 1.0f;
masterConfig.customMotorMixer[5].pitch = -0.414178f;
masterConfig.customMotorMixer[5].yaw = 1.0f;
// { 1.0f, -1.0f, 0.414178f, 1.0f }, // MIDREAR_R
masterConfig.customMotorMixer[6].throttle = 1.0f;
masterConfig.customMotorMixer[6].roll = -1.0f;
masterConfig.customMotorMixer[6].pitch = 0.414178f;
masterConfig.customMotorMixer[6].yaw = 1.0f;
// { 1.0f, 1.0f, 0.414178f, -1.0f }, // MIDREAR_L
masterConfig.customMotorMixer[7].throttle = 1.0f;
masterConfig.customMotorMixer[7].roll = 1.0f;
masterConfig.customMotorMixer[7].pitch = 0.414178f;
masterConfig.customMotorMixer[7].yaw = -1.0f;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
#endif
// alternative defaults settings for SINGULARITY target
#if defined(SINGULARITY)
// alternative defaults settings for SINGULARITY target
masterConfig.blackbox_device = 1;
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
@ -1002,15 +999,22 @@ void writeEEPROM(void)
// write it
FLASH_Unlock();
while (attemptsRemaining--) {
#ifdef STM32F303
#if defined(STM32F4)
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
#elif defined(STM32F303)
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
#endif
#ifdef STM32F10X
#elif defined(STM32F10X)
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
#endif
for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
if (wordOffset % FLASH_PAGE_SIZE == 0) {
status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
#if defined(STM32F40_41xxx)
status = FLASH_EraseSector(FLASH_Sector_8, VoltageRange_3); //0x08080000 to 0x080A0000
#elif defined (STM32F411xE)
status = FLASH_EraseSector(FLASH_Sector_7, VoltageRange_3); //0x08060000 to 0x08080000
#else
status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
#endif
if (status != FLASH_COMPLETE) {
break;
}