From 5b8b9781da1acb9b0d91ca84135dad4a30ad5b47 Mon Sep 17 00:00:00 2001 From: lkaino Date: Thu, 18 Aug 2016 14:05:44 +0300 Subject: [PATCH] New target: RCEXPLORERF3 (#439) New target: RCEXPLORERF3 F3FC board from RCExplorer.se. Supports both tricopter integrated and standalone boards. --- .travis.yml | 3 +- fake_travis_build.sh | 4 +- src/main/drivers/pwm_mapping.c | 7 ++ src/main/target/RCEXPLORERF3/target.c | 71 ++++++++++++++++ src/main/target/RCEXPLORERF3/target.h | 148 +++++++++++++++++++++++++++++++++ src/main/target/RCEXPLORERF3/target.mk | 17 ++++ 6 files changed, 247 insertions(+), 3 deletions(-) create mode 100644 src/main/target/RCEXPLORERF3/target.c create mode 100644 src/main/target/RCEXPLORERF3/target.h create mode 100644 src/main/target/RCEXPLORERF3/target.mk diff --git a/.travis.yml b/.travis.yml index c0a2702ae..3d6e7ab8c 100755 --- a/.travis.yml +++ b/.travis.yml @@ -7,7 +7,8 @@ env: - TARGET=SPARKY - TARGET=FURYF3 - TARGET=FURYF3_SPIFLASH - + - TARGET=RCEXPLORERF3 + # use new docker environment sudo: false diff --git a/fake_travis_build.sh b/fake_travis_build.sh index d0369dd92..b2a3b8278 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -19,8 +19,8 @@ targets=("PUBLISHMETA=True" \ "TARGET=SPARKY" \ "TARGET=STM32F3DISCOVERY" \ "TARGET=ALIENWIIF1" \ - "TARGET=ALIENWIIF3") - + "TARGET=ALIENWIIF3"\ + "TARGET=RCEXPLORERF3" ) #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) export BUILDNAME=${BUILDNAME:=fake_travis} diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 17afcd679..2cfc3fb90 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -235,6 +235,13 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init) type = MAP_TO_SERVO_OUTPUT; #endif +#if defined(RCEXPLORERF3) + if (timerIndex == PWM2) + { + type = MAP_TO_SERVO_OUTPUT; + } +#endif + #if (defined(STM32F3DISCOVERY) && !defined(CHEBUZZF3)) // remap PWM 5+6 or 9+10 as servos - softserial pin pairs require timer ports that use the same timer if (init->useSoftSerial) { diff --git a/src/main/target/RCEXPLORERF3/target.c b/src/main/target/RCEXPLORERF3/target.c new file mode 100644 index 000000000..758cf0ad3 --- /dev/null +++ b/src/main/target/RCEXPLORERF3/target.c @@ -0,0 +1,71 @@ +/* + * 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 +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +const uint16_t multiPPM[] = { + PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM17 - can be switched to servo + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM1 + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM17 - can be switched to servo + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM1 + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + 0xFFFF +}; + +const uint16_t airPPM[] = { + PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM17 - can be switched to servo + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM1 + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM17 - can be switched to servo + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM1 + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM1 - PA4 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM2 - PA7 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // PWM3 - PA8 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM4 - PB0 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - PB1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM6 - PPM +}; diff --git a/src/main/target/RCEXPLORERF3/target.h b/src/main/target/RCEXPLORERF3/target.h new file mode 100644 index 000000000..78910b76a --- /dev/null +++ b/src/main/target/RCEXPLORERF3/target.h @@ -0,0 +1,148 @@ +/* + * 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 "REF3" + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE + +#define LED0 PB4 +#define LED1 PB5 + +#define BEEPER PA0 +#define BEEPER_INVERTED + +#define USABLE_TIMER_CHANNEL_COUNT 6 + + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL +#define MPU_INT_EXTI PA15 +#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready + +#define GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 + +#define MPU6000_CS_PIN PB12 +#define MPU6000_SPI_INSTANCE SPI2 + +#define ACC + +#define ACC_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG + +#define BARO +#define USE_BARO_MS5611 + +#define MAG +#define USE_MPU9250_MAG // Enables bypass configuration +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 // External + +#define MAG_AK8975_ALIGN CW180_DEG + +#define SONAR +#define SONAR_TRIGGER_PIN PA6 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) +#define SONAR_ECHO_PIN PB1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor ) + +#define USB_IO + +#define USE_VCP +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define SERIAL_PORT_COUNT 4 + +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 + +#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 USE_I2C +#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) + +#define I2C2_SCL PA9 +#define I2C2_SDA PA10 + +#define USE_SPI +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG) + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER + +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA5 +#define CURRENT_METER_ADC_PIN PB2 +#define RSSI_ADC_PIN PA6 + +#define LED_STRIP // LED strip configuration using PWM motor output pin 5. + +#define USE_LED_STRIP_ON_DMA1_CHANNEL3 +#define WS2811_PIN PB8 // TIM16_CH1 +#define WS2811_TIMER TIM16 +#define WS2811_DMA_CHANNEL DMA1_Channel3 +#define WS2811_IRQ DMA1_Channel3_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER + +#define DEFAULT_FEATURES FEATURE_VBAT +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +#define NAV +#define NAV_AUTO_MAG_DECLINATION +#define NAV_GPS_GLITCH_DETECTION +#define NAV_MAX_WAYPOINTS 60 +#define GPS +#define BLACKBOX +#define TELEMETRY +#define SERIAL_RX +#define AUTOTUNE +#define DISPLAY +#define USE_SERVOS +#define USE_CLI + +#define SPEKTRUM_BIND +// USART3, +#define BIND_PIN PA3 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// Number of available PWM outputs +#define MAX_PWM_OUTPUT_PORTS 6 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) + +#define USABLE_TIMER_CHANNEL_COUNT 6 +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(17)) diff --git a/src/main/target/RCEXPLORERF3/target.mk b/src/main/target/RCEXPLORERF3/target.mk new file mode 100644 index 000000000..cc8ecd0c5 --- /dev/null +++ b/src/main/target/RCEXPLORERF3/target.mk @@ -0,0 +1,17 @@ +F3_TARGETS += $(TARGET) +FEATURES = VCP + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c \ + drivers/compass_ak8975.c \ + drivers/compass_mag3110.c \ + drivers/display_ug2864hsweg01.c \ + drivers/serial_usb_vcp.c \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/sonar_hcsr04.c \ + drivers/sonar_srf10.c -- 2.11.4.GIT