diff --git a/src/main/target/VANTAC_RF007/CMakeLists.txt b/src/main/target/VANTAC_RF007/CMakeLists.txt new file mode 100644 index 00000000000..3ad19278f00 --- /dev/null +++ b/src/main/target/VANTAC_RF007/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(VANTAC_RF007) diff --git a/src/main/target/VANTAC_RF007/README.md b/src/main/target/VANTAC_RF007/README.md new file mode 100644 index 00000000000..e5d3b4a0739 --- /dev/null +++ b/src/main/target/VANTAC_RF007/README.md @@ -0,0 +1,73 @@ +FrSky/Rotorflight VANTAC RF007 +============================== + +Family of flight controllers originally designed for helicopters using Rotorflight. +There are three versions available, the only difference is the type of integrated FrSky receiver. +All versions share the same target in INAV. + +Rotorflight's site: https://www.rotorflight.org/docs/controllers/frsky-007 + +FrSky's manual: https://www.frsky-rc.com/wp-content/uploads/Downloads/Amanual/VANTAC%20RF007%20Manual.pdf + +Built-in receiver +------------------- + +The built-in receiver is connected to UART5 and uses FrSky FBUS. +Only the RxUG update port is connected to the receiver directly. +All other pins are connected to the STM32F7 running INAV. + +The receiver has a bind button labelled "Rx". +To bind the Archer+ version, the button needs to be held while power gets connected. +The Archer+ version will bind to Multiprotocol Module FrSky X2 D16 mode, among other options. +For more information, see the manufacturer's manual. + +Pin configuration +----------------- + +The RPM, TLM, AUX and SBUS pins are Servo/Motor outputs by default. +However, when UART1 or UART2 are assigned a function in the ports tab, the pins will become a UART instead. +See the table below. + +| Marking on the case | Both UART1 and UART2 unused | UART1 in use | UART2 in use | Both UART1 and UART2 in use | +|---------------------|------------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------| +| S1 | Output S1 | Output S1 | Output S1 | Output S1 | +| S2 | Output S2 | Output S2 | Output S2 | Output S2 | +| S3 | Output S3 | Output S3 | Output S3 | Output S3 | +| TAIL | Output S4 | Output S4 | Output S4 | Output S4 | +| ESC | Output S5 | Output S5 | Output S5 | Output S5 | +| RPM | Output S6 | Output S6 | UART2 TX | UART2 TX | +| TLM | Output S7 | Output S7 | UART2 RX | UART2 RX | +| AUX | Output S8 | UART1 TX | Output S6 | UART1 TX | +| SBUS | Output S9 | UART1 RX | Output S7 | UART1 RX | +| A | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | +| C | I2C
pin order:
**SDA, SCL, 5V, GND**
or
UART3
pin order:
**RX, TX, 5V, GND** | I2C
pin order:
**SDA, SCL, 5V, GND**
or
UART3
pin order:
**RX, TX, 5V, GND** | I2C
pin order:
**SDA, SCL, 5V, GND**
or
UART3
pin order:
**RX, TX, 5V, GND** | I2C
pin order:
**SDA, SCL, 5V, GND**
or
UART3
pin order:
**RX, TX, 5V, GND** | +| EXT-V | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | +| built-in receiver | UART5 | UART5 | UART5 | UART5 | + +All pin orders are from left to right, when looking at the connector on the flight controller. + +**Port "C" has the data pins swapped. The manufacturers documentation is incorrect.** +Port "A" is wired correctly. + +Hardware layout +--------------- + + +| Marking on the case | STM32 pin | Servo | UART | I2C | +|---------------------|-----------|------------------------------:|---------------:|---------:| +| S1 | PB4 | TIM3CH1 | n/a | n/a | +| S2 | PB5 | TIM3CH2 | n/a | n/a | +| S3 | PB0 | TIM3CH3 | n/a | n/a | +| TAIL | PA15 | TIM2CH1 | n/a | n/a | +| ESC | PA9 | TIM1CH2 | UART1 TX | n/a | +| RPM | PA2 | TIM2CH3
TIM5CH3
TIM9CH1 | UART2 TX | n/a | +| TLM | PA3 | TIM2CH4
TIM5CH4
TIM9CH2 | UART2 RX | n/a | +| AUX | PB6 | TIM4CH1 | UART1 TX | I2C1 SCL | +| SBUS | PB7 | TIM4CH2 | UART1 RX | I2C1 SDA | +| A | PA0/PA1 | TIM1
TIM5 | UART2
UART4 | n/a | +| C | PB10/PB11 | TIM2 | UART3 | I2C2 | +| EXT-V | PC0 | n/a | n/a | n/a | +| built-in receiver | PC12/PD2 | n/a | UART5 | n/a | + +The pinout is extremely similar to the F7B5 reference design from Rotorflight. +https://github.com/rotorflight/rotorflight-ref-design/blob/master/Reference-Design-F7B.md \ No newline at end of file diff --git a/src/main/target/VANTAC_RF007/config.c b/src/main/target/VANTAC_RF007/config.c new file mode 100644 index 00000000000..c3c3f3d6295 --- /dev/null +++ b/src/main/target/VANTAC_RF007/config.c @@ -0,0 +1,28 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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 file 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 program. If not, see http://www.gnu.org/licenses/. + */ + +void targetConfiguration(void) +{ + +} diff --git a/src/main/target/VANTAC_RF007/target.c b/src/main/target/VANTAC_RF007/target.c new file mode 100644 index 00000000000..3589a56c224 --- /dev/null +++ b/src/main/target/VANTAC_RF007/target.c @@ -0,0 +1,43 @@ +/* + * This file is part of INAV. + * + * INAV 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. + * + * INAV 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 INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "target.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "S1" + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "S2" + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "S3" + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TAIL" + + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "ESC" + + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "RPM", clashes with UART2 TX + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TLM", clashes with UART2 RX + + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "AUX", clashes with UART1 TX and I2C1 SCL + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "SBUS", clashes with UART1 RX and I2C1 SDA +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/VANTAC_RF007/target.h b/src/main/target/VANTAC_RF007/target.h new file mode 100644 index 00000000000..3f54ef4cf37 --- /dev/null +++ b/src/main/target/VANTAC_RF007/target.h @@ -0,0 +1,143 @@ +/* + * This file is part of INAV. + * + * INAV 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. + * + * INAV 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 INAV. If not, see . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "F7B5" + +#define USBD_PRODUCT_STRING "VANTAC_RF007" + +#define LED0 PC14 +#define LED1 PC15 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_ICM42605 // is actually ICM42688P +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_CS_PIN PA4 +#define ICM42605_EXTI_PIN PB2 +#define ICM42605_SPI_BUS BUS_SPI1 + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 +// alternate pin assignment +// clashes with UART1 +// also won't allow the built-in barometer to be used +//#define I2C1_SCL PB6 +//#define I2C1_SDA PB7 + +#define USE_I2C_DEVICE_2 // clashes with UART3 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 +#define EXTERNAL_I2C BUS_I2C2 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_SPL06 +#define SPL06_I2C_ADDR 119 + +#define TEMPERATURE_I2C_BUS EXTERNAL_I2C + +#define PITOT_I2C_BUS EXTERNAL_I2C + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS EXTERNAL_I2C + +// *************** SPI2 Blackbox ******************* +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_FLASHFS +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI2 +#define W25N01G_CS_PIN PB12 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 // clashes with I2C1 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 // pin labelled "SBUS" + +#define USE_UART2 +#define UART2_TX_PIN PA2 // pin labelled as "RPM" +#define UART2_RX_PIN PA3 // pin labelled as "TLM" + +#define USE_UART3 // clashes with I2C2 +// port labelled "C" +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +// port labelled "A" +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +// port internal receiver +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_FBUS +#define SERIALRX_UART SERIAL_PORT_USART5 + +#define SENSORS_SET (SENSOR_ACC|SENSOR_BARO) + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC0 + +#define VBAT_ADC_CHANNEL ADC_CHN_3 // port labelled "EXT-V" +//BEC ADC is ADC_CHN_2 +//BUS ADC is ADC_CHN_1 + +#define VBAT_SCALE_DEFAULT 2464 + +#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_TX_PROF_SEL) + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 9 + +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR +#define USE_SMARTPORT_MASTER // no internal current sensor, enable SMARTPORT_MASTER so external ones can be used