Initial OpenPilot CC3D commit.
This commit is contained in:
parent
ae0f842266
commit
1fb75890d5
23
Makefile
23
Makefile
|
@ -32,7 +32,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0
|
|||
|
||||
FORKNAME = cleanflight
|
||||
|
||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3
|
||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D
|
||||
|
||||
# Working directories
|
||||
ROOT = $(dir $(lastword $(MAKEFILE_LIST)))
|
||||
|
@ -222,6 +222,27 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
|
|||
drivers/timer.c \
|
||||
$(COMMON_SRC)
|
||||
|
||||
CC3D_SRC = startup_stm32f10x_md_gcc.S \
|
||||
drivers/adc.c \
|
||||
drivers/adc_stm32f10x.c \
|
||||
drivers/bus_i2c_stm32f10x.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/light_led_stm32f10x.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
drivers/pwm_mapping.c \
|
||||
drivers/pwm_output.c \
|
||||
drivers/pwm_rssi.c \
|
||||
drivers/pwm_rx.c \
|
||||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/sound_beeper_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer.c \
|
||||
$(COMMON_SRC)
|
||||
|
||||
STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \
|
||||
drivers/adc.c \
|
||||
drivers/adc_stm32f30x.c \
|
||||
|
|
|
@ -70,6 +70,7 @@ enum {
|
|||
TYPE_S,
|
||||
};
|
||||
|
||||
#if USABLE_TIMER_CHANNEL_COUNT >= 14
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (TYPE_IP << 8), // PPM input
|
||||
PWM9 | (TYPE_M << 8), // Swap to servo if needed
|
||||
|
@ -135,6 +136,73 @@ static const uint16_t airPWM[] = {
|
|||
PWM14 | (TYPE_S << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
#endif
|
||||
|
||||
#if USABLE_TIMER_CHANNEL_COUNT == 12
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (TYPE_IP << 8), // PPM input
|
||||
PWM7 | (TYPE_M << 8), // Swap to servo if needed
|
||||
PWM8 | (TYPE_M << 8), // Swap to servo if needed
|
||||
PWM9 | (TYPE_M << 8),
|
||||
PWM10 | (TYPE_M << 8),
|
||||
PWM11 | (TYPE_M << 8),
|
||||
PWM12 | (TYPE_M << 8),
|
||||
PWM2 | (TYPE_M << 8), // Swap to servo if needed
|
||||
PWM3 | (TYPE_M << 8), // Swap to servo if needed
|
||||
PWM4 | (TYPE_M << 8), // Swap to servo if needed
|
||||
PWM5 | (TYPE_M << 8), // Swap to servo if needed
|
||||
PWM6 | (TYPE_M << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t multiPWM[] = {
|
||||
PWM1 | (TYPE_IW << 8), // input #1
|
||||
PWM2 | (TYPE_IW << 8),
|
||||
PWM3 | (TYPE_IW << 8),
|
||||
PWM4 | (TYPE_IW << 8),
|
||||
PWM5 | (TYPE_IW << 8),
|
||||
PWM6 | (TYPE_IW << 8), // input #6
|
||||
PWM7 | (TYPE_M << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (TYPE_M << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (TYPE_M << 8), // motor #1 or #3
|
||||
PWM10 | (TYPE_M << 8),
|
||||
PWM11 | (TYPE_M << 8),
|
||||
PWM12 | (TYPE_M << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPPM[] = {
|
||||
PWM1 | (TYPE_IP << 8), // PPM input
|
||||
PWM7 | (TYPE_M << 8),
|
||||
PWM8 | (TYPE_M << 8),
|
||||
PWM9 | (TYPE_S << 8),
|
||||
PWM10 | (TYPE_S << 8),
|
||||
PWM11 | (TYPE_S << 8),
|
||||
PWM12 | (TYPE_S << 8),
|
||||
PWM2 | (TYPE_S << 8),
|
||||
PWM3 | (TYPE_S << 8),
|
||||
PWM4 | (TYPE_S << 8),
|
||||
PWM5 | (TYPE_S << 8),
|
||||
PWM6 | (TYPE_S << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPWM[] = {
|
||||
PWM1 | (TYPE_IW << 8), // input #1
|
||||
PWM2 | (TYPE_IW << 8),
|
||||
PWM3 | (TYPE_IW << 8),
|
||||
PWM4 | (TYPE_IW << 8),
|
||||
PWM5 | (TYPE_IW << 8),
|
||||
PWM6 | (TYPE_IW << 8), // input #6
|
||||
PWM7 | (TYPE_M << 8), // motor #1
|
||||
PWM8 | (TYPE_M << 8), // motor #2
|
||||
PWM9 | (TYPE_S << 8), // servo #1
|
||||
PWM10 | (TYPE_S << 8), // servo #2
|
||||
PWM11 | (TYPE_S << 8), // servo #3
|
||||
PWM12 | (TYPE_S << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
#endif
|
||||
|
||||
static const uint16_t * const hardwareMaps[] = {
|
||||
multiPWM,
|
||||
|
|
|
@ -67,7 +67,7 @@
|
|||
TIM4 4 channels
|
||||
*/
|
||||
|
||||
#if defined(STM32F10X_MD) || defined(NAZE)
|
||||
#if (defined(STM32F10X_MD) || defined(NAZE)) && !defined(CC3D)
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // PWM1
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // PWM2
|
||||
|
@ -95,6 +95,33 @@ static const TIM_TypeDef *timers[MAX_TIMERS] = {
|
|||
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
|
||||
#endif
|
||||
|
||||
#if defined(CC3D)
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // S1_IN
|
||||
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // S2_IN - GPIO_PartialRemap_TIM3
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // S3_IN
|
||||
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD}, // S4_IN
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // S5_IN
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // S6_IN
|
||||
|
||||
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, GPIO_Mode_AF_PP}, // S1_OUT
|
||||
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, GPIO_Mode_AF_PP}, // S2_OUT
|
||||
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, GPIO_Mode_AF_PP}, // S3_OUT
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, GPIO_Mode_AF_PP}, // S4_OUT
|
||||
{ TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, GPIO_Mode_AF_PP}, // S5_OUT - GPIO_PartialRemap_TIM3
|
||||
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, GPIO_Mode_AF_PP}, // S6_OUT
|
||||
};
|
||||
|
||||
#define MAX_TIMERS 4 // TIM1..TIM4
|
||||
|
||||
static const TIM_TypeDef *timers[MAX_TIMERS] = {
|
||||
TIM1, TIM2, TIM3, TIM4
|
||||
};
|
||||
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
|
||||
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
|
||||
#endif
|
||||
|
||||
#if (defined(STM32F303xC) || defined(STM32F3DISCOVERY)) && !(defined(CHEBUZZF3) || defined(NAZE32PRO))
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP_PD}, // PWM1 - PA8
|
||||
|
@ -397,6 +424,10 @@ void timerInit(void)
|
|||
{
|
||||
memset(timerConfig, 0, sizeof (timerConfig));
|
||||
|
||||
#ifdef CC3D
|
||||
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
|
||||
#endif
|
||||
|
||||
#ifdef TIMER_APB1_PERIPHERALS
|
||||
RCC_APB1PeriphClockCmd(TIMER_APB1_PERIPHERALS, ENABLE);
|
||||
#endif
|
||||
|
@ -442,5 +473,4 @@ void timerInit(void)
|
|||
GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_2);
|
||||
GPIO_PinAFConfig(GPIOB, GPIO_PinSource9, GPIO_AF_2);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
|
|
@ -19,7 +19,13 @@
|
|||
|
||||
#ifdef CHEBUZZF3
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 18
|
||||
#else
|
||||
#endif
|
||||
|
||||
#ifdef CC3D
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||
#endif
|
||||
|
||||
#if !defined(USABLE_TIMER_CHANNEL_COUNT)
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#endif
|
||||
|
||||
|
|
|
@ -107,6 +107,20 @@
|
|||
#undef USE_ACC_MMA8452
|
||||
#endif
|
||||
|
||||
#ifdef CC3D
|
||||
#define USE_FAKE_GYRO
|
||||
#define USE_FAKE_ACC
|
||||
#undef USE_GYRO_L3GD20
|
||||
#undef USE_GYRO_L3G4200D
|
||||
#undef USE_GYRO_MPU6050
|
||||
#undef USE_GYRO_MPU3050
|
||||
#undef USE_ACC_LSM303DLHC
|
||||
#undef USE_ACC_ADXL345
|
||||
#undef USE_ACC_BMA280
|
||||
#undef USE_ACC_MPU6050
|
||||
#undef USE_ACC_MMA8452
|
||||
#endif
|
||||
|
||||
extern uint16_t batteryWarningVoltage;
|
||||
extern uint8_t batteryCellCount;
|
||||
extern float magneticDeclination;
|
||||
|
|
|
@ -0,0 +1,26 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3 // PB3 (LED)
|
||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define LED0
|
||||
|
||||
#define ACC
|
||||
#define GYRO
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_MAG)
|
Loading…
Reference in New Issue