From 1722f20a34ad0e058574059761cff2356b68b05f Mon Sep 17 00:00:00 2001 From: Amir Guindehi Date: Mon, 15 Jan 2018 11:45:22 +0100 Subject: [PATCH 1/6] Added UAVP-NG HW-0.30-mini target called UAVPNG030MINI. --- src/main/target/UAVPNG030MINI/target.c | 39 ++++++ src/main/target/UAVPNG030MINI/target.h | 157 ++++++++++++++++++++++++ src/main/target/UAVPNG030MINI/target.mk | 6 + 3 files changed, 202 insertions(+) create mode 100644 src/main/target/UAVPNG030MINI/target.c create mode 100644 src/main/target/UAVPNG030MINI/target.h create mode 100644 src/main/target/UAVPNG030MINI/target.mk diff --git a/src/main/target/UAVPNG030MINI/target.c b/src/main/target/UAVPNG030MINI/target.c new file mode 100644 index 000000000..929914ff2 --- /dev/null +++ b/src/main/target/UAVPNG030MINI/target.c @@ -0,0 +1,39 @@ +/* + * 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/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM3, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM_IN_A + DEF_TIM(TIM3, CH1, PA3, TIM_USE_PPM, 0, 0), // PPM_IN_B + + DEF_TIM(TIM3, CH3, PA8, TIM_USE_MOTOR, 0, 0), // PPM_OUT_A + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR, 0, 0), // PPM_OUT_B + DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR, 0, 0), // PPM_OUT_C + DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR, 0, 0), // PPM_OUT_D + DEF_TIM(TIM3, CH3, PB5, TIM_USE_MOTOR, 0, 0), // PPM_OUT_E + DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR, 0, 0), // PPM_OUT_F + DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR, 0, 0), // PPM_OUT_G + DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR, 0, 0), // PPM_OUT_H +}; diff --git a/src/main/target/UAVPNG030MINI/target.h b/src/main/target/UAVPNG030MINI/target.h new file mode 100644 index 000000000..ef46a99b6 --- /dev/null +++ b/src/main/target/UAVPNG030MINI/target.h @@ -0,0 +1,157 @@ +/* + * This 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. + * + * This software 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 this software. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "UAVP" + +#define USBD_PRODUCT_STRING "UAVP-NG HW-0.30-mini" + +#define LED0_PIN PE5 +#define LED1_PIN PE7 +#define LED2_PIN PE6 +#define LED3_PIN PE8 + +#define BEEPER PB0 +#define BEEPER_INVERTED + +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define ACC +#define USE_ACC_SPI_MPU6000 + +#define GYRO +#define USE_GYRO_SPI_MPU6000 + +// TODO +#define GYRO_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG + +// MPU6000 interrupts +#define USE_EXTI +#define MPU_INT_EXTI PE0 +#define USE_MPU_DATA_READY_SIGNAL + +#define MAG +#define USE_MAG_HMC5883 +#define MAG_HMC5883_ALIGN CW90_DEG +#define MAG_I2C_INSTANCE I2CDEV_2 +#define HMC5883_I2C_INSTANCE I2CDEV_2 +#define MAG_INT_EXTI PE12 +#define USE_MAG_DATA_READY_SIGNAL + +#define BARO +#define USE_BARO_MS5611 +#define USE_BARO_SPI_MS5611 +#define MS5611_CS_PIN PE1 +#define MS5611_SPI_INSTANCE SPI1 + +#if 0 // TODO: Enable SDCard and blackbox logging +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#define USE_SDCARD +#define USE_SDCARD_SPI2 +#define SDCARD_DETECT_INVERTED +#define SDCARD_DETECT_PIN PE2 +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN +// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz + +#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4 +#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 +#define SDCARD_DMA_CHANNEL DMA_Channel_0 +#elif defined(LUXF4OSD) +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#endif + +#define USE_VCP +//#define VBUS_SENSING_PIN PC5 + +#define USE_UART1 +#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 +//#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 + +#define USE_UART2 +#define UART2_RX_PIN PD6 +#define UART2_TX_PIN PD5 + +#define USE_UART3 +#define UART3_RX_PIN PD9 +#define UART3_TX_PIN PD8 + +#define USE_UART6 +#define UART6_RX_PIN PC6 +#define UART6_TX_PIN PC7 + +#define SERIAL_PORT_COUNT 5 //VCP, USART1, USART2, USART3, USART6 + +// TODO +#define USE_ESCSERIAL +#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +/// I2C Configuration +#define USE_I2C +#define USE_I2C_PULLUP +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define I2C_DEVICE (I2CDEV_2) + +#define USE_ADC +#define VBAT_ADC_PIN PC1 +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC + +//#define TRANSPONDER + +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART1 + +#define USE_SERIALRX_SBUS +#define USE_SERIALRX_SPEKTRUM + +#define DEFAULT_FEATURES 0 +#define AVOID_UART1_FOR_PWM_PPM +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA (0xffff & ~(BIT(0)|BIT(1)|BIT(10)|BIT(13)|BIT(14)|BIT(15))) +#define TARGET_IO_PORTB (0xffff & ~(BIT(2)|BIT(3)|BIT(4))) +#define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)|BIT(13))) +#define TARGET_IO_PORTD (0xffff & ~(BIT(0)|BIT(1))) +#define TARGET_IO_PORTE (0xffff & ~(BIT(15))) + +#define USABLE_TIMER_CHANNEL_COUNT 10 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) diff --git a/src/main/target/UAVPNG030MINI/target.mk b/src/main/target/UAVPNG030MINI/target.mk new file mode 100644 index 000000000..3ecb836a8 --- /dev/null +++ b/src/main/target/UAVPNG030MINI/target.mk @@ -0,0 +1,6 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP +TARGET_SRC = \ + drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/barometer/barometer_ms5611.c \ + drivers/compass/compass_hmc5883l.c From 54111b62d65ad2fad67cf6ba8bae73a0a6a81a51 Mon Sep 17 00:00:00 2001 From: Amir Guindehi Date: Mon, 17 Sep 2018 15:51:06 +0200 Subject: [PATCH 2/6] Fixed missing defines in UAVPNG030MINI target. It seems MPU6000_CS_PIN + MPU6000_SPI_INSTANCE got renamed to GYRO_1_CS_PIN + GYRO_1_SPI_INSTANCE. --- src/main/target/UAVPNG030MINI/target.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/target/UAVPNG030MINI/target.h b/src/main/target/UAVPNG030MINI/target.h index ef46a99b6..3e2006cba 100644 --- a/src/main/target/UAVPNG030MINI/target.h +++ b/src/main/target/UAVPNG030MINI/target.h @@ -27,15 +27,15 @@ #define BEEPER PB0 #define BEEPER_INVERTED -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 - #define ACC #define USE_ACC_SPI_MPU6000 #define GYRO #define USE_GYRO_SPI_MPU6000 +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_SPI_INSTANCE SPI1 + // TODO #define GYRO_MPU6000_ALIGN CW180_DEG #define ACC_MPU6000_ALIGN CW180_DEG From aaff54cca14106ed8f13ce5c966049e8c6a561eb Mon Sep 17 00:00:00 2001 From: Amir Guindehi Date: Mon, 17 Sep 2018 17:36:23 +0200 Subject: [PATCH 3/6] Removed unneeded target definitions in target UAVPNG030MINI. --- src/main/target/UAVPNG030MINI/target.h | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/main/target/UAVPNG030MINI/target.h b/src/main/target/UAVPNG030MINI/target.h index 3e2006cba..f16b42f01 100644 --- a/src/main/target/UAVPNG030MINI/target.h +++ b/src/main/target/UAVPNG030MINI/target.h @@ -134,16 +134,8 @@ #define VBAT_ADC_PIN PC1 #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -//#define TRANSPONDER - #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_USART1 -#define USE_SERIALRX_SBUS -#define USE_SERIALRX_SPEKTRUM - -#define DEFAULT_FEATURES 0 #define AVOID_UART1_FOR_PWM_PPM #define USE_SERIAL_4WAY_BLHELI_INTERFACE From 9e838e1451b41ce4cca748bdffe13ab43e0a4e2f Mon Sep 17 00:00:00 2001 From: Amir Guindehi Date: Mon, 17 Sep 2018 20:45:42 +0200 Subject: [PATCH 4/6] Corrected USED_TIMERS in the UAVPNG030MINI target. --- src/main/target/UAVPNG030MINI/target.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/target/UAVPNG030MINI/target.h b/src/main/target/UAVPNG030MINI/target.h index f16b42f01..5958f37cb 100644 --- a/src/main/target/UAVPNG030MINI/target.h +++ b/src/main/target/UAVPNG030MINI/target.h @@ -146,4 +146,8 @@ #define TARGET_IO_PORTE (0xffff & ~(BIT(15))) #define USABLE_TIMER_CHANNEL_COUNT 10 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) + +// Used Timers +//#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) | TIM_N(12)) +// Defined Timers in timer.c +#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4)) From cf8c1d7e0b4d1fdf4a784063468cff0b1bb39439 Mon Sep 17 00:00:00 2001 From: Amir Guindehi Date: Tue, 18 Sep 2018 08:40:15 +0200 Subject: [PATCH 5/6] Removed AVOID_UART1_FOR_PWM_PPM from UAVPNG030MINI target. As we do not share PPM/PWM pads and serial input this is unneeded. --- src/main/target/UAVPNG030MINI/target.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/target/UAVPNG030MINI/target.h b/src/main/target/UAVPNG030MINI/target.h index 5958f37cb..a0bb3f5b9 100644 --- a/src/main/target/UAVPNG030MINI/target.h +++ b/src/main/target/UAVPNG030MINI/target.h @@ -135,8 +135,6 @@ #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL - -#define AVOID_UART1_FOR_PWM_PPM #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA (0xffff & ~(BIT(0)|BIT(1)|BIT(10)|BIT(13)|BIT(14)|BIT(15))) From 566ad49a10cf557ddbb4998397aad328ee4629be Mon Sep 17 00:00:00 2001 From: Amir Guindehi Date: Tue, 18 Sep 2018 08:47:04 +0200 Subject: [PATCH 6/6] Changed PPM_IN_B from TIM_USE_PPM to TIM_USE_ANY and added a comment that this is a secondary PPM_IN which can be assigned if a user wants to use it. --- src/main/target/UAVPNG030MINI/target.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/UAVPNG030MINI/target.c b/src/main/target/UAVPNG030MINI/target.c index 929914ff2..5ac94896a 100644 --- a/src/main/target/UAVPNG030MINI/target.c +++ b/src/main/target/UAVPNG030MINI/target.c @@ -26,7 +26,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM3, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM_IN_A - DEF_TIM(TIM3, CH1, PA3, TIM_USE_PPM, 0, 0), // PPM_IN_B + DEF_TIM(TIM3, CH1, PA3, TIM_USE_ANY, 0, 0), // Secondary PPM input PPM_IN_B (user can assign this as he wants) DEF_TIM(TIM3, CH3, PA8, TIM_USE_MOTOR, 0, 0), // PPM_OUT_A DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR, 0, 0), // PPM_OUT_B