From 1e68552a0c7365c80f28402f8e6f7376f7619251 Mon Sep 17 00:00:00 2001 From: kc10kevin Date: Sun, 5 Jun 2016 05:53:27 -0500 Subject: [PATCH 1/6] Initial FURYF3 Target --- Makefile | 37 ++- fake_travis_build.sh | 3 +- src/main/config/config.c | 9 +- src/main/drivers/bus_i2c_stm32f30x.c | 2 + src/main/drivers/pwm_mapping.c | 48 +++ src/main/drivers/system.c | 2 +- src/main/drivers/timer.c | 23 ++ src/main/io/serial_msp.c | 2 +- src/main/main.c | 5 + src/main/sensors/initialisation.c | 13 + src/main/sensors/sonar.c | 2 +- src/main/target/FURYF3/system_stm32f30x.c | 371 ++++++++++++++++++++++ src/main/target/FURYF3/system_stm32f30x.h | 76 +++++ src/main/target/FURYF3/target.h | 221 +++++++++++++ top_makefile | 2 + 15 files changed, 808 insertions(+), 8 deletions(-) create mode 100644 src/main/target/FURYF3/system_stm32f30x.c create mode 100644 src/main/target/FURYF3/system_stm32f30x.h create mode 100644 src/main/target/FURYF3/target.h diff --git a/Makefile b/Makefile index e5a4916594..fe5283d572 100644 --- a/Makefile +++ b/Makefile @@ -46,7 +46,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 SPRACINGF3EVO DOGE SINGULARITY +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 DOGE SINGULARITY FURYF3 # Valid targets for OP VCP support VCP_VALID_TARGETS = $(CC3D_TARGETS) @@ -56,9 +56,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 SPRACINGF3EVO DOGE SINGULARITY +256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY FURYF3 -F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY FURYF3 # note that there is no hardfault debugging startup file assembly handler for other platforms ifeq ($(DEBUG_HARDFAULTS),F3) @@ -150,6 +150,13 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ VPATH := $(VPATH):$(FATFS_DIR) endif +ifeq ($(TARGET),FURY) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(FATFS_DIR) \ + +VPATH := $(VPATH):$(FATFS_DIR) +endif + LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion @@ -810,6 +817,30 @@ SINGULARITY_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) +FURYF3_SRC = \ + $(STM32F30x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/display_ug2864hsweg01.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_usb_vcp.c \ + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + drivers/flash_m25p16.c \ + drivers/sonar_hcsr04.c \ + drivers/serial_softserial.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c \ + io/flashfs.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCP_SRC) + # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 7749d64354..4babddd212 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -17,7 +17,8 @@ targets=("PUBLISHMETA=True" \ "TARGET=ALIENFLIGHTF1" \ "TARGET=ALIENFLIGHTF3" \ "TARGET=DOGE" \ - "TARGET=SINGULARITY") + "TARGET=SINGULARITY" \ + "TARGET=FURYF3") #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) diff --git a/src/main/config/config.c b/src/main/config/config.c index 46fcd292a0..6f0b952755 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -385,7 +385,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(DOGE) || defined(SINGULARITY) +#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) || defined(SINGULARITY) || defined(FURYF3) featureSet(FEATURE_RX_PPM); #endif @@ -596,6 +596,13 @@ static void resetConf(void) masterConfig.blackbox_rate_denom = 1; #endif +#if defined(FURYF3) + featureSet(FEATURE_BLACKBOX); + masterConfig.blackbox_device = 2; + masterConfig.blackbox_rate_num = 1; + masterConfig.blackbox_rate_denom = 1; +#endif + // alternative defaults settings for COLIBRI RACE targets #if defined(COLIBRI_RACE) masterConfig.escAndServoConfig.minthrottle = 1025; diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 8b33e7e461..b45f6bd6bb 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -30,6 +30,7 @@ #ifndef SOFT_I2C +#if !defined(I2C1_SCL_GPIO) #define I2C1_SCL_GPIO GPIOB #define I2C1_SCL_GPIO_AF GPIO_AF_4 #define I2C1_SCL_PIN GPIO_Pin_6 @@ -40,6 +41,7 @@ #define I2C1_SDA_PIN GPIO_Pin_7 #define I2C1_SDA_PIN_SOURCE GPIO_PinSource7 #define I2C1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB +#endif #if !defined(I2C2_SCL_GPIO) #define I2C2_SCL_GPIO GPIOF diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index b786ba0cee..d6b523f8c8 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -748,6 +748,54 @@ static const uint16_t airPWM[] = { }; #endif +#ifdef FURYF3 +static const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM2 | (MAP_TO_SERVO_OUTPUT << 8), + PWM3 | (MAP_TO_SERVO_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t airPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; +#endif + static const uint16_t * const hardwareMaps[] = { multiPWM, multiPPM, diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index 1cc192121f..af25ef0c99 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -83,7 +83,7 @@ void EXTI15_10_IRQHandler(void) extiHandler(EXTI15_10_IRQn); } -#if defined(CC3D) +#if defined(CC3D) || defined(FURYF3) void EXTI3_IRQHandler(void) { extiHandler(EXTI3_IRQn); diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index bc52c6e3cc..659236602a 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -416,6 +416,29 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { #endif +#ifdef FURYF3 +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, GPIOB, Pin_3, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1}, // PPM IN + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + + { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2}, // PWM4 - S1 + { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM5 - S2 + { TIM17, GPIOB, Pin_5, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_10}, // PWM6 - S3 + { TIM16, GPIOB, Pin_4, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_1}, // PWM7 - S4 + + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO TIMER - LED_STRIP + +}; + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17)) + +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) +#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB) + +#endif + #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS) #define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4 diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index a827db5d40..dcae1a0ef1 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -125,7 +125,7 @@ void setGyroSamplingSpeed(uint16_t looptime) { masterConfig.mag_hardware = 1; masterConfig.pid_process_denom = 2; } else if (looptime < 375) { -#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3) || defined(SPRACINGF3EVO) || defined(DOGE) +#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3) || defined(SPRACINGF3EVO) || defined(DOGE) || defined(FURYF3) masterConfig.acc_hardware = 0; #else masterConfig.acc_hardware = 1; diff --git a/src/main/main.c b/src/main/main.c index d89bb44923..e05eefb0ca 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -426,6 +426,11 @@ void init(void) } #endif +#if defined(FURYF3) && defined(SONAR) && defined(USE_SOFTSERIAL1) + if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) { + serialRemovePort(SERIAL_PORT_SOFTSERIAL1); + } +#endif #ifdef USE_I2C #if defined(NAZE) diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index ab9b27c898..a27ca0663d 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -223,6 +223,19 @@ const extiConfig_t *selectMPUIntExtiConfig(void) } #endif +#if defined(FURYF3) + static const extiConfig_t FURYF3MPUIntExtiConfig = { + .gpioAHBPeripherals = RCC_AHBPeriph_GPIOA, + .gpioPort = GPIOA, + .gpioPin = Pin_3, + .exti_port_source = EXTI_PortSourceGPIOA, + .exti_pin_source = EXTI_PinSource3, + .exti_line = EXTI_Line3, + .exti_irqn = EXTI3_IRQn + }; + return &FURYF3MPUIntExtiConfig; +#endif + return NULL; } diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index 4e0b2bea52..93104d0cd7 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -101,7 +101,7 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon .exti_irqn = EXTI0_IRQn }; return &sonarHardware; -#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) +#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(FURYF3) UNUSED(batteryConfig); static const sonarHardware_t const sonarHardware = { .trigger_pin = Pin_0, // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) diff --git a/src/main/target/FURYF3/system_stm32f30x.c b/src/main/target/FURYF3/system_stm32f30x.c new file mode 100644 index 0000000000..de8a873131 --- /dev/null +++ b/src/main/target/FURYF3/system_stm32f30x.c @@ -0,0 +1,371 @@ +/** + ****************************************************************************** + * @file system_stm32f30x.c + * @author MCD Application Team + * @version V1.1.1 + * @date 28-March-2014 + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. + * This file contains the system clock configuration for STM32F30x devices, + * and is generated by the clock configuration tool + * stm32f30x_Clock_Configuration_V1.0.0.xls + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier + * and Divider factors, AHB/APBx prescalers and Flash settings), + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f30x.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (8 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f30x.s" file, to + * configure the system clock before to branch to main program. + * + * 3. If the system clock source selected by user fails to startup, the SystemInit() + * function will do nothing and HSI still used as system clock source. User can + * add some code to deal with this issue inside the SetSysClock() function. + * + * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define + * in "stm32f30x.h" file. When HSE is used as system clock source, directly or + * through PLL, and you are using different crystal you have to adapt the HSE + * value to your own configuration. + * + * 5. This file configures the system clock as follows: + *============================================================================= + * Supported STM32F30x device + *----------------------------------------------------------------------------- + * System Clock source | PLL (HSE) + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 72000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 72000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 2 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 2 + *----------------------------------------------------------------------------- + * HSE Frequency(Hz) | 8000000 + *---------------------------------------------------------------------------- + * PLLMUL | 9 + *----------------------------------------------------------------------------- + * PREDIV | 1 + *----------------------------------------------------------------------------- + * USB Clock | ENABLE + *----------------------------------------------------------------------------- + * Flash Latency(WS) | 2 + *----------------------------------------------------------------------------- + * Prefetch Buffer | ON + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2014 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f30x_system + * @{ + */ + +/** @addtogroup STM32F30x_System_Private_Includes + * @{ + */ + +#include "stm32f30x.h" + +uint32_t hse_value = HSE_VALUE; + +/** + * @} + */ + +/* Private typedef -----------------------------------------------------------*/ + +/** @addtogroup STM32F30x_System_Private_Defines + * @{ + */ +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ + +/** @addtogroup STM32F30x_System_Private_Variables + * @{ + */ + + uint32_t SystemCoreClock = 72000000; + + __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + +/** + * @} + */ + +/** @addtogroup STM32F30x_System_Private_FunctionPrototypes + * @{ + */ + +void SetSysClock(void); + +/** + * @} + */ + +/** @addtogroup STM32F30x_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemFrequency variable. + * @param None + * @retval None + */ +void SystemInit(void) +{ + /* FPU settings ------------------------------------------------------------*/ + #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ + #endif + + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset CFGR register */ + RCC->CFGR &= 0xF87FC00C; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + + /* Reset PREDIV1[3:0] bits */ + RCC->CFGR2 &= (uint32_t)0xFFFFFFF0; + + /* Reset USARTSW[1:0], I2CSW and TIMs bits */ + RCC->CFGR3 &= (uint32_t)0xFF00FCCC; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; + + /* Configure the System clock source, PLL Multiplier and Divider factors, + AHB/APBx prescalers and Flash settings ----------------------------------*/ + //SetSysClock(); // called from main() + +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value + * 8 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value + * 8 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param None + * @retval None + */ +void SystemCoreClockUpdate (void) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock */ + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } + else + { + prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; + /* HSE oscillator clock selected as PREDIV1 clock entry */ + SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; + } + break; + default: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + } + /* Compute HCLK clock frequency ----------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +/** + * @brief Configures the System clock source, PLL Multiplier and Divider factors, + * AHB/APBx prescalers and Flash settings + * @note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ +void SetSysClock(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + +/******************************************************************************/ +/* PLL (clocked by HSE) used as System clock source */ +/******************************************************************************/ + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer and set Flash Latency */ + FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1; + + /* HCLK = SYSCLK / 1 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK / 1 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK / 2 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + + /* PLL configuration */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9); + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ \ No newline at end of file diff --git a/src/main/target/FURYF3/system_stm32f30x.h b/src/main/target/FURYF3/system_stm32f30x.h new file mode 100644 index 0000000000..57e5e05d74 --- /dev/null +++ b/src/main/target/FURYF3/system_stm32f30x.h @@ -0,0 +1,76 @@ +/** + ****************************************************************************** + * @file system_stm32f30x.h + * @author MCD Application Team + * @version V1.1.1 + * @date 28-March-2014 + * @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2014 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f30x_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F30X_H +#define __SYSTEM_STM32F30X_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/** @addtogroup STM32F30x_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F30X_H */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ \ No newline at end of file diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h new file mode 100644 index 0000000000..0fbe17c57b --- /dev/null +++ b/src/main/target/FURYF3/target.h @@ -0,0 +1,221 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "FURY" + +#define LED0 + +#define LED0_GPIO GPIOC +#define LED0_PIN Pin_14 +#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOC + +#define BEEPER +#define BEEP_GPIO GPIOC +#define BEEP_PIN Pin_15 +#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC +#define BEEPER_INVERTED + +#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU INT, SDCardDetect + +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define GYRO +#define ACC + +#define MPU6000_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA +#define MPU6000_CS_GPIO GPIOA +#define MPU6000_CS_PIN GPIO_Pin_4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA +#define MPU6500_CS_GPIO GPIOA +#define MPU6500_CS_PIN GPIO_Pin_4 +#define MPU6500_SPI_INSTANCE SPI1 + +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG // changedkb 270 +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG // changedkb 270 + +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define GYRO_MPU6500_ALIGN CW90_DEG // changedkb 270 +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define ACC_MPU6500_ALIGN CW90_DEG // changedkb 270 + +#define BARO +#define USE_BARO_MS5611 +#define USE_BARO_BMP280 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 + +#define SPI2_GPIO GPIOB +#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB +#define SPI2_NSS_PIN Pin_12 +#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12 +#define SPI2_SCK_PIN Pin_13 +#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13 +#define SPI2_MISO_PIN Pin_14 +#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14 +#define SPI2_MOSI_PIN Pin_15 +#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15 + +//#define USE_FLASHFS +//#define USE_FLASH_M25P16 +//#define M25P16_CS_GPIO GPIOB +//#define M25P16_CS_PIN GPIO_Pin_12 +//#define M25P16_SPI_INSTANCE SPI2 + +#define USE_SDCARD +#define USE_SDCARD_SPI2 + +#define SDCARD_DETECT_INVERTED + +#define SDCARD_DETECT_PIN GPIO_Pin_2 +#define SDCARD_DETECT_EXTI_LINE EXTI_Line2 +#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2 +#define SDCARD_DETECT_GPIO_PORT GPIOB +#define SDCARD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOB +#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB +#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn + +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_SPI_CS_GPIO SPI2_GPIO +#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN + +// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128 +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 + +// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 + +// Performance logging for SD card operations: +// #define AFATFS_USE_INTROSPECTIVE_LOGGING + +#define USABLE_TIMER_CHANNEL_COUNT 8 + +#define USB_IO + +#define USE_VCP +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define USE_SOFTSERIAL1 +#define SERIAL_PORT_COUNT 5 + +#ifndef UART1_GPIO +#define UART1_TX_PIN GPIO_Pin_9 // PA9 +#define UART1_RX_PIN GPIO_Pin_10 // PA10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 +#endif + +#define UART2_TX_PIN GPIO_Pin_14 // PA14 +#define UART2_RX_PIN GPIO_Pin_15 // PA15 +#define UART2_GPIO GPIOA +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource14 +#define UART2_RX_PINSOURCE GPIO_PinSource15 + +#ifndef UART3_GPIO +#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) +#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 +#endif + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 1 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 2 + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4) + +#define I2C1_SCL_GPIO GPIOB +#define I2C1_SCL_GPIO_AF GPIO_AF_4 +#define I2C1_SCL_PIN GPIO_Pin_8 +#define I2C1_SCL_PIN_SOURCE GPIO_PinSource8 +#define I2C1_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOB +#define I2C1_SDA_GPIO GPIOB +#define I2C1_SDA_GPIO_AF GPIO_AF_4 +#define I2C1_SDA_PIN GPIO_Pin_9 +#define I2C1_SDA_PIN_SOURCE GPIO_PinSource9 +#define I2C1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER + +#define ADC_INSTANCE ADC1 +#define ADC_DMA_CHANNEL DMA1_Channel1 +#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 + +#define VBAT_ADC_GPIO GPIOA +#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 +#define VBAT_ADC_CHANNEL ADC_Channel_1 + +#define RSSI_ADC_GPIO GPIOA +#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 +#define RSSI_ADC_CHANNEL ADC_Channel_2 + +#define CURRENT_METER_ADC_GPIO GPIOA +#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2 +#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3 + +#define LED_STRIP +#define LED_STRIP_TIMER TIM1 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL2 +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_GPIO_AF GPIO_AF_6 +#define WS2811_PIN GPIO_Pin_8 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM1 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define WS2811_DMA_CHANNEL DMA1_Channel2 +#define WS2811_IRQ DMA1_Channel2_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define BLACKBOX +#define DISPLAY +#define GPS +#define SERIAL_RX +#define TELEMETRY +#define USE_SERVOS +#define USE_CLI +#define SONAR + +#define SPEKTRUM_BIND +// USART3, +#define BIND_PORT GPIOB +#define BIND_PIN Pin_11 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE \ No newline at end of file diff --git a/top_makefile b/top_makefile index 4b1bb90e78..bbc1f43f14 100644 --- a/top_makefile +++ b/top_makefile @@ -15,6 +15,7 @@ ALL_TARGETS += ircfusionf3 ALL_TARGETS += afromini ALL_TARGETS += doge ALL_TARGETS += singularity +ALL_TARGETS += furyf3 CLEAN_TARGETS := $(addprefix clean_, $(ALL_TARGETS)) @@ -35,6 +36,7 @@ clean_ircfusionf3 ircfusionf3 : opts := TARGET=IRCFUSIONF3 clean_afromini afromini : opts := TARGET=AFROMINI clean_doge doge : opts := TARGET=DOGE clean_singularity singularity : opts := TARGET=SINGULARITY +clean_furyf3 furyf3 : opts := TARGET=FURYF3 .PHONY: all clean From 047d962e6588e14f71470e0d6596b7c5360b7dc3 Mon Sep 17 00:00:00 2001 From: Gary Keeble Date: Mon, 6 Jun 2016 18:22:52 +0100 Subject: [PATCH 2/6] Blackbox Coding Simplification Simplified header record writing using macros to outnumber the case statements --- src/main/blackbox/blackbox.c | 288 +++++++++++------------------------ 1 file changed, 91 insertions(+), 197 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 40fa2e2306..80df3ba141 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1118,6 +1118,15 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v return xmitState.headerIndex < headerCount; } +#ifndef BLACKBOX_PRINT_HEADER_LINE +#define BLACKBOX_PRINT_HEADER_LINE(x, ...) case __COUNTER__: \ + blackboxPrintfHeaderLine(x, __VA_ARGS__); \ + break; +#define BLACKBOX_PRINT_HEADER_LINE_CUSTOM(...) case __COUNTER__: \ + {__VA_ARGS__}; \ + break; +#endif + /** * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns * true iff transmission is complete, otherwise call again later to continue transmission. @@ -1130,212 +1139,97 @@ static bool blackboxWriteSysinfo() } switch (xmitState.headerIndex) { - case 0: - blackboxPrintfHeaderLine("Firmware type:Cleanflight"); - break; - case 1: - blackboxPrintfHeaderLine("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName); - break; - case 2: - blackboxPrintfHeaderLine("Firmware date:%s %s", buildDate, buildTime); - break; - case 3: - blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); - break; - case 4: - blackboxPrintfHeaderLine("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcRate8); - break; - case 5: - blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle); - break; - case 6: - blackboxPrintfHeaderLine("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle); - break; - case 7: - blackboxPrintfHeaderLine("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale)); - break; - case 8: - blackboxPrintfHeaderLine("acc_1G:%u", acc_1G); - break; - case 9: + BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight"); + BLACKBOX_PRINT_HEADER_LINE("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName); + BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime); + BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); + BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle); + BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle); + BLACKBOX_PRINT_HEADER_LINE("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale)); + BLACKBOX_PRINT_HEADER_LINE("acc_1G:%u", acc_1G); + + BLACKBOX_PRINT_HEADER_LINE_CUSTOM( if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) { blackboxPrintfHeaderLine("vbatscale:%u", masterConfig.batteryConfig.vbatscale); } else { xmitState.headerIndex += 2; // Skip the next two vbat fields too } - break; - case 10: - blackboxPrintfHeaderLine("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage, - masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage); - break; - case 11: - blackboxPrintfHeaderLine("vbatref:%u", vbatReference); - break; - case 12: + ); + + BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage, + masterConfig.batteryConfig.vbatwarningcellvoltage, + masterConfig.batteryConfig.vbatmaxcellvoltage); + BLACKBOX_PRINT_HEADER_LINE("vbatref:%u", vbatReference); + + BLACKBOX_PRINT_HEADER_LINE_CUSTOM( //Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too: if (feature(FEATURE_CURRENT_METER)) { blackboxPrintfHeaderLine("currentMeter:%d,%d", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale); } - break; - case 13: - blackboxPrintfHeaderLine("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8); - break; - case 14: - blackboxPrintfHeaderLine("rcYawRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawRate8); - break; - case 15: - blackboxPrintfHeaderLine("rcYawExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawExpo8); - break; - case 16: - blackboxPrintfHeaderLine("thrMid:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrMid8); - break; - case 17: - blackboxPrintfHeaderLine("thrExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrExpo8); - break; - case 18: - blackboxPrintfHeaderLine("dynThrPID:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].dynThrPID); - break; - case 19: - blackboxPrintfHeaderLine("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); - break; - case 20: - blackboxPrintfHeaderLine("rates:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[ROLL], - masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[PITCH], - masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[YAW]); - break; - case 21: - blackboxPrintfHeaderLine("looptime:%d", targetLooptime); - break; - case 22: - blackboxPrintfHeaderLine("pidController:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidController); - break; - case 23: - blackboxPrintfHeaderLine("rollPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[ROLL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[ROLL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[ROLL]); - break; - case 24: - blackboxPrintfHeaderLine("pitchPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PITCH], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PITCH], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PITCH]); - break; - case 25: - blackboxPrintfHeaderLine("yawPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[YAW], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[YAW], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[YAW]); - break; - case 26: - blackboxPrintfHeaderLine("altPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDALT], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDALT], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDALT]); - break; - case 27: - blackboxPrintfHeaderLine("posPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOS], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOS], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOS]); - break; - case 28: - blackboxPrintfHeaderLine("posrPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOSR], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOSR], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOSR]); - break; - case 29: - blackboxPrintfHeaderLine("navrPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDNAVR], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDNAVR], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDNAVR]); - break; - case 30: - blackboxPrintfHeaderLine("levelPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL]); - break; - case 31: - blackboxPrintfHeaderLine("magPID:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDMAG]); - break; - case 32: - blackboxPrintfHeaderLine("velPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]); - break; - case 33: - blackboxPrintfHeaderLine("yaw_p_limit:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit); - break; - case 34: - blackboxPrintfHeaderLine("yaw_lpf_hz:%d", - (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f)); - break; - case 35: - blackboxPrintfHeaderLine("dterm_average_count:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); - break; - case 36: - blackboxPrintfHeaderLine("dynamic_pid:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid); - break; - case 37: - blackboxPrintfHeaderLine("rollPitchItermResetRate:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate); - break; - case 38: - blackboxPrintfHeaderLine("yawItermResetRate:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate); - break; - case 39: - blackboxPrintfHeaderLine("dterm_lpf_hz:%d", - (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); - break; - case 40: - blackboxPrintfHeaderLine("airmode_activate_throttle:%d", - masterConfig.rxConfig.airModeActivateThreshold); - break; - case 41: - blackboxPrintfHeaderLine("deadband:%d", masterConfig.rcControlsConfig.deadband); - break; - case 42: - blackboxPrintfHeaderLine("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); - break; - case 43: - blackboxPrintfHeaderLine("gyro_lpf:%d", masterConfig.gyro_lpf); - break; - case 44: - blackboxPrintfHeaderLine("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); - break; - case 45: - blackboxPrintfHeaderLine("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f)); - break; - case 46: - blackboxPrintfHeaderLine("acc_hardware:%d", masterConfig.acc_hardware); - break; - case 47: - blackboxPrintfHeaderLine("baro_hardware:%d", masterConfig.baro_hardware); - break; - case 48: - blackboxPrintfHeaderLine("mag_hardware:%d", masterConfig.mag_hardware); - break; - case 49: - blackboxPrintfHeaderLine("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm); - break; - case 50: - blackboxPrintfHeaderLine("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation); - break; - case 51: - blackboxPrintfHeaderLine("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); - break; - case 52: - blackboxPrintfHeaderLine("features:%d", masterConfig.enabledFeatures); - break; + ); + + BLACKBOX_PRINT_HEADER_LINE("looptime:%d", targetLooptime); + BLACKBOX_PRINT_HEADER_LINE("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcRate8); + BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8); + BLACKBOX_PRINT_HEADER_LINE("rcYawRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawRate8); + BLACKBOX_PRINT_HEADER_LINE("rcYawExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawExpo8); + BLACKBOX_PRINT_HEADER_LINE("thrMid:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrMid8); + BLACKBOX_PRINT_HEADER_LINE("thrExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrExpo8); + BLACKBOX_PRINT_HEADER_LINE("dynThrPID:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].dynThrPID); + BLACKBOX_PRINT_HEADER_LINE("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); + BLACKBOX_PRINT_HEADER_LINE("rates:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[ROLL], + masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[PITCH], + masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[YAW]); + BLACKBOX_PRINT_HEADER_LINE("pidController:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidController); + BLACKBOX_PRINT_HEADER_LINE("rollPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[ROLL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[ROLL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[ROLL]); + BLACKBOX_PRINT_HEADER_LINE("pitchPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PITCH], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PITCH], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PITCH]); + BLACKBOX_PRINT_HEADER_LINE("yawPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[YAW], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[YAW], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[YAW]); + BLACKBOX_PRINT_HEADER_LINE("altPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDALT], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDALT], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDALT]); + BLACKBOX_PRINT_HEADER_LINE("posPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOS], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOS], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOS]); + BLACKBOX_PRINT_HEADER_LINE("posrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOSR], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOSR], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOSR]); + BLACKBOX_PRINT_HEADER_LINE("navrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDNAVR], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDNAVR], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDNAVR]); + BLACKBOX_PRINT_HEADER_LINE("levelPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL]); + BLACKBOX_PRINT_HEADER_LINE("magPID:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDMAG]); + BLACKBOX_PRINT_HEADER_LINE("velPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]); + BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit); + BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); + BLACKBOX_PRINT_HEADER_LINE("dynamic_pid:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid); + BLACKBOX_PRINT_HEADER_LINE("rollPitchItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate); + BLACKBOX_PRINT_HEADER_LINE("yawItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate); + BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("deadband:%d", masterConfig.rcControlsConfig.deadband); + BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); + BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyro_lpf); + BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.acc_hardware); + BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware); + BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.mag_hardware); + BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm); + BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation); + BLACKBOX_PRINT_HEADER_LINE("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); + BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold); + BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures); + default: return true; } From 6e228eacf5e53c38e2c69569e9d846a3e2e96a55 Mon Sep 17 00:00:00 2001 From: mikeller Date: Tue, 7 Jun 2016 11:39:37 +1200 Subject: [PATCH 3/6] Fixed rateprofile dump / restore --- src/main/io/serial_cli.c | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index d077b96148..4cad900d68 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -2051,24 +2051,27 @@ static void cliDump(char *cmdline) if (dumpMask & DUMP_ALL) { uint8_t activeProfile = masterConfig.current_profile_index; - uint8_t currentRateIndex = currentProfile->activeRateProfile; uint8_t profileCount; - uint8_t rateCount; for (profileCount=0; profileCountactiveRateProfile; + uint8_t rateCount; for (rateCount=0; rateCount Date: Tue, 7 Jun 2016 20:16:06 +0100 Subject: [PATCH 4/6] Added default features and default rx that can be set in the target.h file. --- src/main/config/config.c | 35 +++++++------------------ src/main/target/ALIENFLIGHTF3/target.h | 1 + src/main/target/CC3D/target.h | 1 + src/main/target/CJMCU/target.h | 1 + src/main/target/COLIBRI_RACE/target.h | 1 + src/main/target/DOGE/target.h | 1 + src/main/target/FURYF3/target.h | 2 ++ src/main/target/LUX_RACE/target.h | 1 + src/main/target/MOTOLAB/target.h | 1 + src/main/target/SINGULARITY/target.h | 2 ++ src/main/target/SPARKY/target.h | 1 + src/main/target/SPRACINGF3/target.h | 3 +++ src/main/target/SPRACINGF3EVO/target.h | 5 ++-- src/main/target/SPRACINGF3MINI/target.h | 2 +- 14 files changed, 29 insertions(+), 28 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 6f0b952755..46f0f669bb 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -73,6 +73,10 @@ #include "config/config_profile.h" #include "config/config_master.h" +#ifndef DEFAULT_RX_FEATURE +#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM +#endif + #define BRUSHED_MOTORS_PWM_RATE 16000 #define BRUSHLESS_MOTORS_PWM_RATE 400 @@ -382,25 +386,20 @@ static void resetConf(void) memset(&masterConfig, 0, sizeof(master_t)); setProfile(0); - 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(DOGE) || defined(SINGULARITY) || defined(FURYF3) - featureSet(FEATURE_RX_PPM); + featureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES); +#ifdef DEFAULT_FEATURES + featureSet(DEFAULT_FEATURES); #endif -//#if defined(SPRACINGF3MINI) -// featureSet(FEATURE_DISPLAY); -//#endif - #ifdef BOARD_HAS_VOLTAGE_DIVIDER // only enable the VBAT feature by default if the board has a voltage divider otherwise // the user may see incorrect readings and unexpected issues with pin mappings may occur. featureSet(FEATURE_VBAT); #endif - featureSet(FEATURE_FAILSAFE); - featureSet(FEATURE_SUPEREXPO_RATES); + masterConfig.version = EEPROM_CONF_VERSION; + masterConfig.mixerMode = MIXER_QUADX; // global settings masterConfig.current_profile_index = 0; // default profile @@ -574,7 +573,6 @@ static void resetConf(void) #endif #ifdef SPRACINGF3 - featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = 1; #ifdef TRANSPONDER static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware @@ -597,7 +595,6 @@ static void resetConf(void) #endif #if defined(FURYF3) - featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = 2; masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; @@ -609,16 +606,6 @@ static void resetConf(void) masterConfig.escAndServoConfig.maxthrottle = 1980; masterConfig.batteryConfig.vbatmaxcellvoltage = 45; masterConfig.batteryConfig.vbatmincellvoltage = 30; - - featureSet(FEATURE_VBAT); - 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 @@ -699,14 +686,12 @@ static void resetConf(void) // alternative defaults settings for SINGULARITY target #if defined(SINGULARITY) - featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = 1; masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; masterConfig.batteryConfig.vbatscale = 77; - featureSet(FEATURE_RX_SERIAL); masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; #endif @@ -823,7 +808,7 @@ void activateConfig(void) void validateAndFixConfig(void) { if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) { - featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM + featureSet(FEATURE_RX_PARALLEL_PWM); } if (featureConfigured(FEATURE_RX_PPM)) { diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 79365c62e5..144ba1f7dd 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -157,6 +157,7 @@ //#define DISPLAY #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // USART2, PA3 diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index ca94199b8f..3f6b753b52 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -128,6 +128,7 @@ #define SERIAL_RX #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SONAR //#define GPS diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index cf32393b42..cd9cb19123 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -60,6 +60,7 @@ #define SERIAL_RX //#define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // USART2, PA3 diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 92edd4fea2..d95a9cc48a 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -192,5 +192,6 @@ #define SERIAL_RX #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 008557d335..fa18385a83 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -190,6 +190,7 @@ #define SERIAL_RX #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // Use UART3 for speksat diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 0fbe17c57b..99d7340d79 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -212,6 +212,8 @@ #define USE_SERVOS #define USE_CLI #define SONAR +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define SPEKTRUM_BIND // USART3, diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index a3b370df7a..2d04a2fee6 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -154,6 +154,7 @@ #define TELEMETRY #define SERIAL_RX +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 9f168587fd..23e54ab3b8 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -121,6 +121,7 @@ #define TELEMETRY #define BLACKBOX #define SERIAL_RX +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM //#define GPS //#define GTUNE #define DISPLAY diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 54d1824444..fbc58bae34 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -127,6 +127,8 @@ #define GPS #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL) #define SPEKTRUM_BIND // USART2, PA15 diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 8ff56c86ca..5e69ef1089 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -126,6 +126,7 @@ #define TELEMETRY #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define LED_STRIP #if 1 diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index c5a0e5265d..0e0ede72ce 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -158,6 +158,9 @@ #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX + #define SPEKTRUM_BIND // USART3, #define BIND_PORT GPIOB diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 4586dbc2d1..73ea225dca 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -206,8 +206,6 @@ #define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2 #define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM - #define GPS #define BLACKBOX #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT @@ -217,6 +215,9 @@ #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) + #define SPEKTRUM_BIND // USART3, #define BIND_PORT GPIOB diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 5459d4f9a2..6151d35492 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -212,10 +212,10 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define TELEMETRY #define SERIAL_RX -#define AUTOTUNE #define DISPLAY #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define BUTTONS #define BUTTON_A_PORT GPIOB From dd06a5d29ba5c5b4e77378ec8191d1bdc6eb20de Mon Sep 17 00:00:00 2001 From: Michael Keller Date: Mon, 13 Jun 2016 09:36:39 +1200 Subject: [PATCH 5/6] Added targets for listing and building all valid target platforms to Makefile. --- Makefile | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/Makefile b/Makefile index fe5283d572..20d6bd130f 100644 --- a/Makefile +++ b/Makefile @@ -968,6 +968,16 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.S ## all : default task; compile C code, build firmware all: binary +## all_targets : build all valid target platforms +all_targets: + for build_target in $(VALID_TARGETS); do \ + echo "Building $$build_target" && \ + make clean && \ + make -j TARGET=$$build_target || \ + break; \ + echo "Building $$build_target succeeded."; \ + done + ## clean : clean up all temporary / machine-generated files clean: rm -f $(CLEAN_ARTIFACTS) @@ -1017,6 +1027,10 @@ help: Makefile @echo "" @sed -n 's/^## //p' $< +## targets : print a list of all valid target platforms (for consumption by scripts) +targets: + @echo $(VALID_TARGETS) + ## test : run the cleanflight test suite test: cd src/test && $(MAKE) test || true From e024e451a7800b2b88f9ce07cdf820f2a258a00c Mon Sep 17 00:00:00 2001 From: Albert Kravcov Date: Tue, 14 Jun 2016 19:12:09 +0200 Subject: [PATCH 6/6] Update README.md Logo change --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 0239f59611..28d9c66a13 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # Betaflight -![Betaflight](https://dl.dropboxusercontent.com/u/31537757/betaflight%20logo.jpg) +![Betaflight](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088900-228-bf_logo.jpg) Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft.