Merge branch 'master' into development

This commit is contained in:
borisbstyle 2016-08-15 22:00:22 +02:00
commit 534b77554b
23 changed files with 382 additions and 133 deletions

View File

@ -343,6 +343,10 @@ ifneq ($(FLASH_SIZE),)
DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
endif
ifneq ($(HSE_VALUE),)
DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)
endif
TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET)
TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))

View File

@ -93,7 +93,7 @@
#endif
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
void targetConfiguration(void);
void targetConfiguration(master_t *config);
master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile;
@ -618,12 +618,7 @@ void createDefaultConfig(master_t *config)
#endif
#if defined(TARGET_CONFIG)
// Don't look at target specific config settings when getting default
// values for a CLI diff. This is suboptimal, but it doesn't break the
// public API
if (config == &masterConfig) {
targetConfiguration();
}
targetConfiguration(config);
#endif

View File

@ -53,19 +53,23 @@ static void i2cUnstick(IO_t scl, IO_t sda);
#ifndef I2C1_SDA
#define I2C1_SDA PB9
#endif
#else
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz)
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#endif
@ -398,8 +402,8 @@ void i2cInit(I2CDevice device)
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C);
#else
IOConfigGPIO(scl, IOCFG_AF_OD);
IOConfigGPIO(sda, IOCFG_AF_OD);
IOConfigGPIO(scl, IOCFG_I2C);
IOConfigGPIO(sda, IOCFG_I2C);
#endif
I2C_DeInit(i2c->dev);

View File

@ -30,9 +30,9 @@
#ifndef SOFT_I2C
#if defined(USE_I2C_PULLUP)
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP)
#else
#define IOCFG_I2C IOCFG_AF_OD
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#endif
#define I2C_HIGHSPEED_TIMING 0x00500E30 // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.

View File

@ -204,10 +204,10 @@ void scaleRcCommandToFpvCamAngle(void) {
sinFactor = sin_approx(masterConfig.rxConfig.fpvCamAngleDegrees * RAD);
}
int16_t roll = setpointRate[ROLL];
int16_t yaw = setpointRate[YAW];
setpointRate[ROLL] = constrain(roll * cosFactor - yaw * sinFactor, -500, 500);
setpointRate[YAW] = constrain(yaw * cosFactor + roll * sinFactor, -500, 500);
int16_t roll = rcCommand[ROLL];
int16_t yaw = rcCommand[YAW];
rcCommand[ROLL] = constrain(roll * cosFactor - yaw * sinFactor, -500, 500);
rcCommand[YAW] = constrain(yaw * cosFactor + roll * sinFactor, -500, 500);
}
void processRcCommand(void)
@ -264,13 +264,13 @@ void processRcCommand(void)
}
if (readyToCalculateRate || isRXDataNew) {
for (int axis = 0; axis < 3; axis++) setpointRate[axis] = calculateSetpointRate(axis, rcCommand[axis]);
isRXDataNew = false;
// Scaling of AngleRate to camera angle (Mixing Roll and Yaw)
if (masterConfig.rxConfig.fpvCamAngleDegrees && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && !FLIGHT_MODE(HEADFREE_MODE))
scaleRcCommandToFpvCamAngle();
for (int axis = 0; axis < 3; axis++) setpointRate[axis] = calculateSetpointRate(axis, rcCommand[axis]);
isRXDataNew = false;
}
}

View File

@ -0,0 +1,106 @@
/*
* 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 "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM4 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
0xFFFF
};
const uint16_t airPPM[] = {
PWM4 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_11}, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2} // PWM14 - OUT6
};

View File

@ -0,0 +1,114 @@
/*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "AIR3"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define CONFIG_PREFER_ACC_ON
#define LED0 PB3
#define LED1 PB4
#define BEEPER PA12
#define BEEPER_INVERTED
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU INT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_SPI
#define USE_SPI_DEVICE_2
#define MPU6500_CS_PIN PB12
#define MPU6500_SPI_INSTANCE SPI2
#define GYRO
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW0_DEG
#define ACC
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW0_DEG
#define BARO
#define USE_BARO_SPI_BMP280
#define BMP280_SPI_INSTANCE SPI2
#define BMP280_CS_PIN PB5
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
#define SOFTSERIAL_2_TIMER TIM3
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define CURRENT_METER_ADC_PIN PB1
#define VBAT_ADC_PIN PA4
#define RSSI_ADC_PIN PA1
#define LED_STRIP
#define WS2811_TIMER TIM3
#define WS2811_PIN PA6
#define WS2811_DMA_CHANNEL DMA1_Channel6
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
#define GPS
#define DEFAULT_FEATURES FEATURE_VBAT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
#define RX_CHANNELS_TAER
#define SPEKTRUM_BIND
// USART3,
#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_PORTF (BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View File

@ -0,0 +1,12 @@
F3_TARGETS += $(TARGET)
HSE_VALUE = 12000000
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_spi_bmp280.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/sonar_hcsr04.c \
drivers/serial_softserial.c

View File

@ -71,26 +71,26 @@
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void)
void targetConfiguration(master_t *config)
{
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;
masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motor_pwm_rate = 32000;
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60;
config->profile[0].pidProfile.P8[PITCH] = 90;
config->profile[0].pidProfile.I8[PITCH] = 44;
config->profile[0].pidProfile.D8[PITCH] = 60;
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
config->customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
config->customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
config->customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
config->customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
config->customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
config->customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
config->customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
}

View File

@ -77,28 +77,28 @@
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
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;
masterConfig.gyro_sync_denom = 2;
masterConfig.pid_process_denom = 1;
masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
void targetConfiguration(master_t *config) {
config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motor_pwm_rate = 32000;
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->gyro_sync_denom = 2;
config->pid_process_denom = 1;
config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60;
config->profile[0].pidProfile.P8[PITCH] = 90;
config->profile[0].pidProfile.I8[PITCH] = 44;
config->profile[0].pidProfile.D8[PITCH] = 60;
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
config->customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
config->customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
config->customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
config->customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
config->customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
config->customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
config->customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
}

View File

@ -77,28 +77,28 @@
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
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;
masterConfig.gyro_sync_denom = 1;
masterConfig.pid_process_denom = 1;
masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
void targetConfiguration(master_t *config) {
config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motor_pwm_rate = 32000;
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->gyro_sync_denom = 1;
config->pid_process_denom = 1;
config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60;
config->profile[0].pidProfile.P8[PITCH] = 90;
config->profile[0].pidProfile.I8[PITCH] = 44;
config->profile[0].pidProfile.D8[PITCH] = 60;
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
config->customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
config->customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
config->customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
config->customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
config->customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
config->customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
config->customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
}

View File

@ -79,10 +79,10 @@
#include "hardware_revision.h"
// alternative defaults settings for BlueJayF4 targets
void targetConfiguration(void)
void targetConfiguration(master_t *config)
{
if (hardwareRevision == BJF4_REV1 || hardwareRevision == BJF4_REV2) {
masterConfig.sensorAlignmentConfig.gyro_align = CW180_DEG;
masterConfig.sensorAlignmentConfig.acc_align = CW180_DEG;
config->sensorAlignmentConfig.gyro_align = CW180_DEG;
config->sensorAlignmentConfig.acc_align = CW180_DEG;
}
}

View File

View File

@ -79,21 +79,20 @@
#include "config/config_master.h"
// alternative defaults settings for Colibri/Gemini targets
void targetConfiguration(void)
void targetConfiguration(master_t *config)
{
masterConfig.mixerMode = MIXER_HEX6X;
masterConfig.rxConfig.serialrx_provider = 2;
featureSet(FEATURE_RX_SERIAL);
config->mixerMode = MIXER_HEX6X;
config->rxConfig.serialrx_provider = 2;
masterConfig.escAndServoConfig.minthrottle = 1070;
masterConfig.escAndServoConfig.maxthrottle = 2000;
config->escAndServoConfig.minthrottle = 1070;
config->escAndServoConfig.maxthrottle = 2000;
masterConfig.boardAlignment.pitchDegrees = 10;
//masterConfig.rcControlsConfig.deadband = 10;
//masterConfig.rcControlsConfig.yaw_deadband = 10;
masterConfig.mag_hardware = 1;
config->boardAlignment.pitchDegrees = 10;
//config->rcControlsConfig.deadband = 10;
//config->rcControlsConfig.yaw_deadband = 10;
config->mag_hardware = 1;
masterConfig.profile[0].controlRateProfile[0].dynThrPID = 45;
masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint = 1700;
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
config->profile[0].controlRateProfile[0].dynThrPID = 45;
config->profile[0].controlRateProfile[0].tpa_breakpoint = 1700;
config->serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
}

View File

@ -104,22 +104,21 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM1 }, // S1_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // S2_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // S3_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // S4_IN
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM2 }, // S5_IN
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM2 }, // S6_IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM5 }, // S7_IN
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM5 }, // S8_IN
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S1_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S2_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S3_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_IN
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S5_IN
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S6_IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S7_IN
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S8_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S3_OUT
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12 }, // S4_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S5_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12 }, // S6_OUT
{ TIM10, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM10 }, // S7_OUT
{ TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM11 }, // S8_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S3_OUT
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S4_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S6_OUT
{ TIM10, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM10 }, // S7_OUT
{ TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM11 }, // S8_OUT
};

View File

@ -135,7 +135,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL)
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -77,9 +77,9 @@
#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;
void targetConfiguration(master_t *config) {
config->escAndServoConfig.minthrottle = 1025;
config->escAndServoConfig.maxthrottle = 1980;
config->batteryConfig.vbatmaxcellvoltage = 45;
config->batteryConfig.vbatmincellvoltage = 30;
}

View File

@ -152,6 +152,15 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define LED_STRIP
#define WS2811_PIN PA0
#define WS2811_TIMER TIM5
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream2
#define WS2811_DMA_IT DMA_IT_TCIF2
#define WS2811_DMA_CHANNEL DMA_Channel_6
#define WS2811_TIMER_CHANNEL TIM_Channel_1
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SPEKTRUM_BIND

View File

@ -5,5 +5,7 @@ TARGET_SRC = \
drivers/accgyro_spi_mpu6000.c \
drivers/accgyro_spi_mpu6500.c \
drivers/accgyro_mpu6500.c \
drivers/barometer_ms5611.c
drivers/barometer_ms5611.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f4xx.c

View File

@ -77,7 +77,7 @@
#include "config/config_master.h"
// Motolab target supports 2 different type of boards Tornado / Cyclone.
void targetConfiguration(void) {
masterConfig.gyro_sync_denom = 4;
masterConfig.pid_process_denom = 1;
void targetConfiguration(master_t *config) {
config->gyro_sync_denom = 4;
config->pid_process_denom = 1;
}

View File

@ -53,8 +53,8 @@ void detectHardwareRevision(void)
#ifdef USE_SPI
#define DISABLE_SPI_CS IOLo(nazeSpiCsPin)
#define ENABLE_SPI_CS IOHi(nazeSpiCsPin)
#define DISABLE_SPI_CS IOHi(nazeSpiCsPin)
#define ENABLE_SPI_CS IOLo(nazeSpiCsPin)
#define SPI_DEVICE_NONE (0)
#define SPI_DEVICE_FLASH (1)

View File

@ -74,9 +74,8 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define CURRENT_METER_ADC_PIN PA2
#define CURRENT_METER_ADC_PIN PB2
#define VBAT_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#if 1

View File

@ -331,7 +331,13 @@ void SetSysClock(void)
/* 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);
if (HSE_VALUE == 12000000) {
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL6);
}
else {
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
}
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;