1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Initial support for CJMCU target (work-in-progress, compiles but doesn't link yet)

This commit is contained in:
Dominic Clifton 2014-07-31 14:01:01 +01:00
parent 3d65e4ff96
commit 8f473f9b20
4 changed files with 121 additions and 13 deletions

View file

@ -32,7 +32,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0
FORKNAME = cleanflight
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU
# Working directories
ROOT = $(dir $(lastword $(MAKEFILE_LIST)))
@ -138,9 +138,6 @@ COMMON_SRC = build_config.c \
drivers/sound_beeper.c \
drivers/system.c \
io/beeper.c \
io/gps.c \
io/gps_conversion.c \
io/ledstrip.c \
io/rc_controls.c \
io/rc_curves.c \
io/serial.c \
@ -148,25 +145,29 @@ COMMON_SRC = build_config.c \
io/serial_msp.c \
io/statusindicator.c \
rx/rx.c \
rx/msp.c \
rx/pwm.c \
rx/sbus.c \
rx/sumd.c \
rx/spektrum.c \
sensors/battery.c \
sensors/boardalignment.c \
sensors/acceleration.c \
sensors/barometer.c \
sensors/compass.c \
sensors/gyro.c \
sensors/initialisation.c \
sensors/sonar.c \
$(CMSIS_SRC) \
$(DEVICE_STDPERIPH_SRC)
HIGHEND_SRC = io/gps.c \
io/gps_conversion.c \
io/ledstrip.c \
rx/msp.c \
rx/sbus.c \
rx/sumd.c \
rx/spektrum.c \
telemetry/telemetry.c \
telemetry/frsky.c \
telemetry/hott.c \
telemetry/msp.c \
$(CMSIS_SRC) \
$(DEVICE_STDPERIPH_SRC)
sensors/sonar.c \
sensors/barometer.c \
sensors/compass.c
NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/accgyro_adxl345.c \
@ -196,6 +197,7 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
$(HIGHEND_SRC) \
$(COMMON_SRC)
OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
@ -220,6 +222,24 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
$(HIGHEND_SRC) \
$(COMMON_SRC)
CJMCU_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/pwm_mapping.c \
drivers/pwm_output.c \
drivers/pwm_rssi.c \
drivers/pwm_rx.c \
drivers/serial_uart.c \
drivers/serial_uart_stm32f10x.c \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
$(COMMON_SRC)
CC3D_SRC = startup_stm32f10x_md_gcc.S \
@ -242,6 +262,7 @@ CC3D_SRC = startup_stm32f10x_md_gcc.S \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
$(HIGHEND_SRC) \
$(COMMON_SRC)
STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \
@ -273,6 +294,7 @@ STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \
vcp/usb_pwr.c
NAZE32PRO_SRC = $(STM32F30x_COMMON_SRC) \
$(HIGHEND_SRC) \
$(COMMON_SRC)
STM32F3DISCOVERY_COMMON_SRC = $(STM32F30x_COMMON_SRC) \
@ -287,9 +309,11 @@ STM32F3DISCOVERY_SRC = $(STM32F3DISCOVERY_COMMON_SRC) \
drivers/accgyro_mpu3050.c \
drivers/accgyro_mpu6050.c \
drivers/accgyro_l3g4200d.c \
$(HIGHEND_SRC) \
$(COMMON_SRC)
CHEBUZZF3_SRC = $(STM32F3DISCOVERY_SRC) \
$(HIGHEND_SRC) \
$(COMMON_SRC)
# Search path and source files for the ST stdperiph library

View file

@ -203,6 +203,35 @@ static const uint16_t airPWM[] = {
};
#endif
#ifdef CJMCU
static const uint16_t multiPPM[] = {
PWM1 | (TYPE_IP << 8), // PPM input
PWM2 | (TYPE_M << 8),
PWM3 | (TYPE_M << 8),
PWM4 | (TYPE_M << 8),
PWM5 | (TYPE_M << 8),
0xFF
};
static const uint16_t multiPWM[] = {
PWM1 | (TYPE_IP << 8), // PPM input
PWM2 | (TYPE_M << 8),
PWM3 | (TYPE_M << 8),
PWM4 | (TYPE_M << 8),
PWM5 | (TYPE_M << 8),
0xFF
};
static const uint16_t airPPM[] = {
0xFF
};
static const uint16_t airPWM[] = {
0xFF
};
#endif
static const uint16_t * const hardwareMaps[] = {
multiPWM,
multiPPM,

View file

@ -138,6 +138,18 @@
#undef USE_ACC_MMA8452
#endif
#ifdef CJMCU
#undef USE_GYRO_SPI_MPU6000
#undef USE_GYRO_L3GD20
#undef USE_GYRO_L3G4200D
#undef USE_GYRO_MPU3050
#undef USE_ACC_LSM303DLHC
#undef USE_ACC_SPI_MPU6000
#undef USE_ACC_ADXL345
#undef USE_ACC_BMA280
#undef USE_ACC_MMA8452
#endif
extern uint16_t batteryWarningVoltage;
extern uint8_t batteryCellCount;
extern float magneticDeclination;

View file

@ -0,0 +1,43 @@
/*
* 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 LED0_GPIO GPIOC
#define LED0_PIN Pin_13 // PC13 (LED)
#define LED0
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED1_GPIO GPIOC
#define LED1_PIN Pin_14 // PC14 (LED)
#define LED1
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED2_GPIO GPIOC
#define LED2_PIN Pin_15 // PC15 (LED)
#define LED2
#define LED2_PERIPHERAL RCC_APB2Periph_GPIOC
#define ACC
#define GYRO
#define MOTOR_PWM_RATE 16000
#define I2C_DEVICE (I2CDEV_1)
// #define SOFT_I2C // enable to test software i2c
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
// #define SOFT_I2C_PB67
#define SENSORS_SET (SENSOR_ACC | SENSOR_MAG)