From 66dfcd4b3a32001010ad186e38bd0a8ae0b04893 Mon Sep 17 00:00:00 2001 From: Freek van Tienen Date: Sat, 26 Nov 2016 23:13:41 +0100 Subject: [PATCH] New target ELLE0 --- src/main/target/ELLE0/target.c | 51 ++++++++++++++++ src/main/target/ELLE0/target.h | 105 ++++++++++++++++++++++++++++++++ src/main/target/ELLE0/target.mk | 9 +++ 3 files changed, 165 insertions(+) create mode 100644 src/main/target/ELLE0/target.c create mode 100644 src/main/target/ELLE0/target.h create mode 100644 src/main/target/ELLE0/target.mk diff --git a/src/main/target/ELLE0/target.c b/src/main/target/ELLE0/target.c new file mode 100644 index 000000000..b350ddf36 --- /dev/null +++ b/src/main/target/ELLE0/target.c @@ -0,0 +1,51 @@ +/* + * 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 . + */ + +#include + +#include +#include "drivers/io.h" + +#include "drivers/timer.h" +#include "drivers/timer_def.h" +#include "drivers/dma.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN DMA1_ST1 (shared with RX1) + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // SERVO1 DMA2_ST2 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // SERVO2 DMA2_ST3 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1 ), // SERVO3 DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // SERVO4 DMA2_ST7 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // SERVO5 DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // SERVO6 DMA1_ST4 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // SERVO7 DMA1_ST7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // SERVO8 DMA1_ST3 +}; + +// Telemetry +//UART1 RX: DMA2_ST5 +//UART1 TX: DMA2_ST7 + +// RX1 +//UART2 RX: DMA1_ST5 +//UART2 TX: DMA1_ST6 + +// I2C +//UART3 RX: DMA1_ST1 +//UART3 TX: DMA1_ST3 + + diff --git a/src/main/target/ELLE0/target.h b/src/main/target/ELLE0/target.h new file mode 100644 index 000000000..cbe277a93 --- /dev/null +++ b/src/main/target/ELLE0/target.h @@ -0,0 +1,105 @@ +/* + * 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 "ELL0" + +#define CONFIG_START_FLASH_ADDRESS 0x08080000 //0x08080000 to 0x080A0000 (FLASH_Sector_8) +#define TARGET_XTAL_MHZ 25 + +#define USBD_PRODUCT_STRING "Elle0" + +#define LED0 PA8 +#define LED1 PB4 +#define LED2 PC2 + +// MPU9250 interrupt +#define USE_EXTI +#define MPU_INT_EXTI PB5 +//#define DEBUG_MPU_DATA_READY_INTERRUPT +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define MPU6500_CS_PIN PB12 +#define MPU6500_SPI_INSTANCE SPI2 + +// Using MPU6050 for the moment. +#define GYRO +#define USE_GYRO_SPI_MPU6500 +#define GYRO_MPU6500_ALIGN CW270_DEG + +#define ACC +#define USE_ACC_SPI_MPU6500 +#define ACC_MPU6500_ALIGN CW270_DEG + +//#define BARO +//#define USE_BARO_MS5611 + +#define MAG +#define USE_MAG_AK8963 +#define MAG_AK8963_ALIGN CW0_DEG_FLIP + +#define USE_VCP + +/* Telemetry (Overlaps with DMA from motors) */ +//#define USE_UART1 +//#define UART1_RX_PIN PA10 +//#define UART1_TX_PIN PA9 +//#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 + +/* RX1 */ +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +/* I2C */ +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +/* RX2 */ +//#define USE_UART5 +//#define UART5_RX_PIN PD2 +//#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 3 + +#define USE_SPI + +#define USE_SPI_DEVICE_2 //MPU9250 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_ADC +#define VBAT_ADC_PIN PC4 +#define CURRENT_METER_ADC_PIN PC5 + +#define DEFAULT_FEATURES (FEATURE_VBAT) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 +#define SERIALRX_UART SERIAL_PORT_USART2 +#define RX_CHANNELS_TAER + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define USABLE_TIMER_CHANNEL_COUNT 9 +#define USED_TIMERS (TIM_N(2) | TIM_N(4) | TIM_N(5) | TIM_N(8)) diff --git a/src/main/target/ELLE0/target.mk b/src/main/target/ELLE0/target.mk new file mode 100644 index 000000000..b044290a7 --- /dev/null +++ b/src/main/target/ELLE0/target.mk @@ -0,0 +1,9 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP +HSE_VALUE = 25000000 + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/compass_ak8963.c