Merge branch 'development' of https://github.com/borisbstyle/betaflight into development

This commit is contained in:
borisbstyle 2016-07-05 16:48:56 +02:00
commit a3ca1c59db
11 changed files with 413 additions and 51 deletions

View File

@ -89,6 +89,7 @@
#endif
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
void targetConfiguration(void);
#if !defined(FLASH_SIZE)
#error "Flash size not defined for target. (specify in KB)"
@ -652,41 +653,8 @@ static void resetConf(void)
}
#endif
// alternative defaults settings for COLIBRI RACE targets
#if defined(COLIBRI_RACE)
masterConfig.escAndServoConfig.minthrottle = 1025;
masterConfig.escAndServoConfig.maxthrottle = 1980;
masterConfig.batteryConfig.vbatmaxcellvoltage = 45;
masterConfig.batteryConfig.vbatmincellvoltage = 30;
#endif
#if defined(TARGET_CONFIG)
targetConfiguration(&masterConfig);
#endif
#if defined(ALIENFLIGHT)
featureClear(FEATURE_ONESHOT125);
#ifdef ALIENFLIGHTF3
masterConfig.mag_hardware = MAG_NONE; // disabled by default
#endif
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentControlRateProfile->rates[FD_PITCH] = 40;
currentControlRateProfile->rates[FD_ROLL] = 40;
currentControlRateProfile->rates[FD_YAW] = 40;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
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
targetConfiguration();
#endif
// copy first profile into remaining profile

View File

@ -117,13 +117,13 @@ void adcInit(drv_adc_config_t *init)
}
#endif
#ifdef CURRENT_METER_ADC_GPIO
#ifdef CURRENT_METER_ADC_PIN
if (init->enableCurrentMeter) {
adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN);
}
#endif
#ifdef EXTERNAL1_ADC_GPIO
#ifdef EXTERNAL1_ADC_PIN
if (init->enableExternal1) {
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN);
}

View File

@ -0,0 +1,100 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.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/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
featureClear(FEATURE_ONESHOT125);
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentControlRateProfile->rates[FD_PITCH] = 40;
currentControlRateProfile->rates[FD_ROLL] = 40;
currentControlRateProfile->rates[FD_YAW] = 40;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
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
}

View File

@ -18,7 +18,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
#define ALIENFLIGHT
#define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT

View File

@ -0,0 +1,100 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.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/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
featureClear(FEATURE_ONESHOT125);
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentControlRateProfile->rates[FD_PITCH] = 40;
currentControlRateProfile->rates[FD_ROLL] = 40;
currentControlRateProfile->rates[FD_YAW] = 40;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
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
}

View File

@ -17,6 +17,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF4"
#define TARGET_CONFIG
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
@ -153,9 +154,6 @@
//#define WS2811_DMA_CHANNEL DMA1_Channel3
//#define WS2811_IRQ DMA1_Channel3_IRQn
// alternative defaults for AlienFlight F4 target
#define ALIENFLIGHT
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3

View File

@ -0,0 +1,84 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.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/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(void) {
masterConfig.escAndServoConfig.minthrottle = 1025;
masterConfig.escAndServoConfig.maxthrottle = 1980;
masterConfig.batteryConfig.vbatmaxcellvoltage = 45;
masterConfig.batteryConfig.vbatmincellvoltage = 30;
}

View File

@ -20,6 +20,7 @@
#define TARGET_BOARD_IDENTIFIER "CLBR"
#define BST_DEVICE_NAME "COLIBRI RACE"
#define BST_DEVICE_NAME_LENGTH 12
#define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT

View File

@ -17,13 +17,10 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "FYF4" //Call it a revo for now so it connects to RFC for testing.
#define TARGET_BOARD_IDENTIFIER "FYF4"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
#define CONFIG_MSP_PORT 2
#define CONFIG_RX_SERIAL_PORT 1
#define USBD_PRODUCT_STRING "FURYF4"
#define USBD_PRODUCT_STRING "FuryF4"
#define LED0 PB5
#define LED1 PB4
@ -67,8 +64,8 @@
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PB3
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12
/*
#define SDCARD_DETECT_PIN PD2
@ -86,11 +83,18 @@
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
//#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
//#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
//#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
//#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB3
@ -149,10 +153,18 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SPEKTRUM_BIND
// USART3 Rx, PB11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9))

View File

@ -0,0 +1,99 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.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/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
featureClear(FEATURE_ONESHOT125);
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentControlRateProfile->rates[FD_PITCH] = 40;
currentControlRateProfile->rates[FD_ROLL] = 40;
currentControlRateProfile->rates[FD_YAW] = 40;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
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
}

View File

@ -172,7 +172,7 @@
// alternative defaults for AlienFlight F1 target
#undef TARGET_BOARD_IDENTIFIER
#define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1.
#define ALIENFLIGHT
#define TARGET_CONFIG
#undef BOARD_HAS_VOLTAGE_DIVIDER
#undef USE_SERIAL_4WAY_BLHELI_INTERFACE