Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions src/main/target/FLYDRAGONPRO/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
target_stm32f722xe(FLYDRAGONPRO)
82 changes: 82 additions & 0 deletions src/main/target/FLYDRAGONPRO/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
FlydragonRC Flydragon Pro
=========================

Flight controllers originally designed for helicopters using Rotorflight.
Two variants exist, one with ICM42688P IMU and one with MPU6000. Both share the same target in INAV.

Built-in periperals
-------------------

Both models contain
- STM32F722RET6 MCU
- SPL06-001 barometer
- W25N01GVZEIG 1GBit Blackbox
- ExpressLRS receiver using ESP8285 and SX1280 connected to UART1. ELRS target is "FD R24D 2.4GHz RX"
- large button connected to BOOT0
- large button is backlit by WS2812B RGB LED
- "GPS" expansion port with 5V, UART5, I2C and GND
- "DSM" expansion port with 3.3V, GND and UART3 RX
- "EXT" expansion port with BAT+, GND, BZZP and 5V.

Buzzer should be connected between 5V and BZZP.
The BAT+ pin measures voltage up to 62V. When measuring the flight battery it is recommended to connect BAT+ but not GND to prevent unintended current paths.

None of the external connections route to the receiver, they are all connected to the STM32F7 Flight Controller.
The receiver can be disabled using USER1, which controls a pinio on pin PA15.

Pin configuration
-----------------

The ESC, RPM, RX2 and TX2 pins are Servo/Motor outputs by default. However, when UART4 or UART2 are assigned a function in the ports tab, the pins will become a UART instead. See the table below.

**The RPM pin features a filtering circuit that limits UART4 RX to 115200 baud. This means CRSF won't work on UART4, while slower protocols like SBUS will.**

| Marking on the case | Both UART2 and UART4 unused | UART2 in use | UART4 in use | Both UART2 and UART4 in use |
|---------------------|-----------------------------|-------------------------|-------------------------|-----------------------------|
| TAIL | Output S1 | Output S1 | Output S1 | Output S1 |
| CH3 | Output S2 | Output S2 | Output S2 | Output S2 |
| CH2 | Output S3 | Output S3 | Output S3 | Output S3 |
| CH1 | Output S4 | Output S4 | Output S4 | Output S4 |
| ESC | Output S5 | Output S5 | UART4 TX | UART4 TX |
| RPM | Output S6 | Output S6 | UART4 RX | UART4 RX |
| RX2 | Output S7 | UART2 RX | Output S5 | UART2 RX |
| TX2 | Output S8 | UART2 TX | Output S6 | UART2 TX |
| AUX | Output S9 | Output S7 | Output S7 | Output S5 |
| GPS RX5 | UART5 RX | UART5 RX | UART5 RX | UART5 RX |
| GPS TX5 | UART5 TX | UART5 TX | UART5 TX | UART5 TX |
| GPS SCL | I2C SCL | I2C SCL | I2C SCL | I2C SCL |
| GPS SDA | I2C SDA | I2C SDA | I2C SDA | I2C SDA |
| DSM RX3 | UART3 RX | UART3 RX | UART3 RX | UART3 RX |
| EXT BAT+ | battery voltage max 62V | battery voltage max 62V | battery voltage max 62V | battery voltage max 62V |
| EXT BZZP | Buzzer positive pin | Buzzer positive pin | Buzzer positive pin | Buzzer positive pin |
| built-in ELRS | UART1 | UART1 | UART1 | UART1 |


Hardware layout
---------------


| Marking on the case | STM32 pin | Servo | UART | I2C |
|---------------------|-----------|------------------------------------------:|---------------------:|-------------------------------------------:|
| TAIL | PC9 | TIM3CH4<br>TIM8CH4 | n/a | I2C3 SDA |
| CH3 | PC8 | TIM3CH3<br>TIM8CH3 | n/a | n/a |
| CH2 | PC7 | TIM3CH2<br>TIM8CH2 | n/a | n/a |
| CH1 | PC6 | TIM3CH1<br>TIM8CH1 | n/a | n/a |
| ESC | PA0 | TIM2CH1<br>TIM5CH1 | UART4 TX | n/a |
| RPM | PA1 | TIM2CH2<br>TIM5CH2 | UART4 RX | n/a |
| RX2 | PA3 | TIM2CH4<br>TIM5CH4<br>TIM9CH2 | UART2 RX | n/a |
| TX2 | PA2 | TIM2CH3<br>TIM5CH3<br>TIM9CH1 | UART2 TX | n/a |
| AUX | PB9 | TIM4CH4<br>TIM11CH1 | n/a | I2C1 SDA |
| GPS RX5 | PD2 | n/a | UART5 RX | n/a |
| GPS TX5 | PC12 | n/a | UART5 TX | n/a |
| GPS SCL | PB6 | TIM4CH1 | UART1 TX | I2C1 SCL |
| GPS SDA | PB7 | TIM4CH2 | UART1 RX | I2C1 SDA |
| DSM RX3 | PC11 | n/a | UART3 RX<br>UART4 RX | n/a |
| EXT BAT+ | PC0 | n/a | n/a | n/a |
| EXT BZZP | PA8 | TIM1CH1<br>pin is behind a FET for buzzer | n/a | I2C3 SCL<br>pin is behind a FET for buzzer |
| RGB LED | PB8 | TIM4CH1 | UART1 TX | I2C1 SCL |
| BUTTON | BOOT0 | n/a | n/a | n/a |
| built-in ELRS | PA9/PA10 | n/a | UART1 | n/a |

PC1 is ADC for servo plug bank.
PC2 is ADC for the built-in BEC.
46 changes: 46 additions & 0 deletions src/main/target/FLYDRAGONPRO/config.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
/*
* 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/.
*/

#include <stdint.h>

#include "platform.h"

#include "drivers/pwm_mapping.h"

#include "fc/fc_msp_box.h"

#include "io/piniobox.h"
#include "io/serial.h"

#include "io/ledstrip.h"

void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;

// configure the built-in WS2812B led as makeshift indicator led
ledStripConfig_t *config = ledStripConfigMutable();
ledConfig_t *lc = config->ledConfigs;
DEFINE_LED(lc, 0, 0, COLOR_BLUE, 0, LED_FUNCTION_COLOR, LED_FLAG_OVERLAY(LED_OVERLAY_WARNING), 0);
}
45 changes: 45 additions & 0 deletions src/main/target/FLYDRAGONPRO/target.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*/

#include <stdint.h>

#include "platform.h"

#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "target.h"

timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TAIL"

DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "CH3"
DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "CH2"
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "CH1"

DEF_TIM(TIM2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "ESC", clashes with UART4 TX
DEF_TIM(TIM2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "RPM", clashes with UART4 RX

DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "RX2", clashes with UART2 RX
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TX2", clashes with UART2 TX

DEF_TIM(TIM11, CH1, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "AUX"

DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0), // WS2812B
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
164 changes: 164 additions & 0 deletions src/main/target/FLYDRAGONPRO/target.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,164 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*/


#pragma once

#define TARGET_BOARD_IDENTIFIER "RTFL"

#define USBD_PRODUCT_STRING "FLYDRAGONPRO"

// indicator led on this board is a single WS2812B LED
// no traditional indicator leds
#define LED0 NONE
#define LED1 NONE
#define USE_LED_STRIP
#define WS2811_PIN PB8

#define BEEPER PA8
#define BEEPER_INVERTED

#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7

// ICM42605 variant
#define USE_IMU_ICM42605 // is actually ICM42688P
#define IMU_ICM42605_ALIGN CW0_DEG
#define ICM42605_CS_PIN PB0
#define ICM42605_EXTI_PIN PB3
#define ICM42605_SPI_BUS BUS_SPI1

// MPU6000 variant
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW90_DEG
#define MPU6000_CS_PIN PB0
#define MPU6000_SPI_BUS BUS_SPI1


// *************** I2C /Baro/Mag *********************
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define DEFAULT_I2C BUS_I2C1

#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
#define I2C2_SDA PB11

#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_SPL06
#define SPL06_I2C_ADDR 118

#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C
#define USE_MAG_ALL

#define TEMPERATURE_I2C_BUS DEFAULT_I2C

#define PITOT_I2C_BUS DEFAULT_I2C

#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS DEFAULT_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 // internal ELRS receiver
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10

#define USE_UART2
#define UART2_TX_PIN PA2 // pin labelled as "TX2"
#define UART2_RX_PIN PA3 // pin labelled as "RX2"

#define USE_UART3
#define UART3_TX_PIN NONE
#define UART3_RX_PIN PC11 // pin labelled "RX3" on the "DSM" port

#define USE_UART4
#define UART4_TX_PIN PA0 // pin labelled "ESC"
#define UART4_RX_PIN PA1 // pin labelled "RPM"

#define USE_UART5
#define UART5_TX_PIN PC12 // pin labelled "TX5" on the "GPS" port
#define UART5_RX_PIN PD2 // pin labelled "RX5" on the "GPS" port

#define SERIAL_PORT_COUNT 6

#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_CRSF
#define SERIALRX_UART SERIAL_PORT_USART1
#define GPS_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 // pin labelled "BAT+" on the "EXT" port
//BEC ADC is ADC_CHN_2
//BUS ADC is ADC_CHN_1

#define VBAT_SCALE_DEFAULT 1898

// *************** PINIO ***************************
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PA15 // enable pin for internal ELRS receiver
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED // turn on by default

#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_LED_STRIP )

#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

#define USE_DSHOT_DMAR
#define TARGET_MOTOR_COUNT 8 // more than 8 DSHOT motors crashes the FC