Skip to content

Commit

Permalink
Added pinout image and README
Browse files Browse the repository at this point in the history
  • Loading branch information
tsubashchandar committed Feb 28, 2024
1 parent b0baac0 commit abf5817
Show file tree
Hide file tree
Showing 4 changed files with 151 additions and 7 deletions.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
146 changes: 139 additions & 7 deletions libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/README.md
Original file line number Diff line number Diff line change
@@ -1,40 +1,117 @@
# PixFlamingo-F767 Flight Controller

The PixFlamingo-F767 is a flight controller produced by Dheeran Labs
The PixFlamingo-F767 is a flight controller produced by Dheeran Labs.
Contact [email protected] for sales

## Features
Processor
STM32F767 32-bit processor
Onboard Flash: 2048Mbits
Sensors
ICM42670, MPU6500 Acc/Gyro
MS5611 / BMP280 barometer
LIS3MDL Compass
Two IMU : ICM42670, MPU6500/ICM20602 Acc/Gyro
One Baro : Internal MS5611/BMP280/DPS310 SPI barometer
Internal LIS3MDL Compass
Power
5v input voltage with voltage monitoring
Interfaces
10x PWM outputs
1x RC input
5x UARTs/serial for GPS and other peripherals
2x I2C ports for external compass, airspeed, etc.
microSD card slot port
Internal RGB LED
Safety switch port
Buzzer port
USB-C port

## Connectors

**POWER ADC**

| Pin | Signal | Volt |
| :--: | :-------------: | :---: |
| 1 | VCC_IN | +5V |
| 2 | VCC_IN | +5V |
| 3 | BAT_CRRENT_ADC | +3.3V |
| 4 | BAT_VOLTAGE_ADC | +3.3V |
| 5 | GND | GND |
| 6 | GND | GND |

**TELEM1**

| Pin | Signal | Volt |
| :--: | :-----: | :---: |
| 1 | VCC | +5V |
| 2 | UART_TX3 | +3.3V |
| 3 | UART_RX3 | +3.3V |
| 4 | CTS | +3.3V |
| 5 | RTS | +3.3V |
| 6 | GND | GND |

**TELEM2**

| Pin | Signal | Volt |
| :--: | :-----: | :---: |
| 1 | VCC | +5V |
| 2 | UART_TX6 | +3.3V |
| 3 | UART_RX6 | +3.3V |
| 4 | CTS | +3.3V |
| 5 | RTS | +3.3V |
| 6 | GND | GND |

**GPS1**

| Pin | Signal | Volt |
| :--: | :-----: | :---: |
| 1 | VCC | +5V |
| 2 | UART_TX1 | +3.3V |
| 3 | UART_RX1 | +3.3V |
| 4 | I2C2_SCL | +3.3V |
| 5 | I2C2_SDA | +3.3V |
| 6 | GND | GND |

**GPS2**

| Pin | Signal | Volt |
| :--: | :-----: | :---: |
| 1 | VCC | +5V |
| 2 | UART_TX1 | +3.3V |
| 3 | UART_RX1 | +3.3V |
| 4 | X | X |
| 5 | X | X |
| 6 | GND | GND |


**SAFETY**

| Pin | Signal | Volt |
| :--: | :-----------: | :---: |
| 1 | SAFETY_SW | +3.3V |
| 2 | SAFETY_SW_LED | +3.3V |
| 3 | 3V3_OUT | +3.3V |
| 4 | BUZZER+ | +3.3V |
| 5 | BUZZER- | GND |


## UART Mapping

The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
receive pin for UARTn. The Tn pin is the transmit pin for UARTn.

- SERIAL0 -> USB
- SERIAL0 -> USB (OTG1)
- SERIAL1 -> UART3 (TELEM1) with CTS/RTS DMA Enabled
- SERIAL2 -> UART6 (TELEM2) with CTS/RTS DMA Enabled
- SERIAL3 -> UART1 (GPS) DMA Enabled
- SERIAL3 -> UART1 (GPS1) DMA Enabled
- SERIAL4 -> EMPTY
- SERIAL5 -> UART7 (GPS2)
- SERIAL5 -> UART7 (GPS2) NODMA
- SERIAL6 -> USART2 (User) DMA Enabled

## RC Input

Supports I-Bus/S-bus

Any UART can be used for RC system connections in ArduPilot also, and is compatible with all protocols except PPM. See Radio Control Systems for details.

## PWM Output

The PixFlaminog-F767 supports up to 10 PWM outputs.
Expand All @@ -46,3 +123,58 @@ The PWM is in 5 groups:
- PWM 9 in group3
- PWM 10 in group4

## GPIOs

All 10 PWM channels can be used for GPIO functions (relays, buttons, RPM etc).

The pin numbers for these PWM channels in ArduPilot are shown below:

| PWM Channels | Pin | PWM Channels | Pin |
| ------------ | ---- | ------------ | ---- |
| PWM1 | 50 | PWM8 | 57 |
| PWM2 | 51 | PWM9 | 58 |
| PWM3 | 52 | PWM10 | 59 |
| PWM4 | 53 | | |
| PWM5 | 54 | | |
| PWM6 | 55 | | |
| PWM7 | 56 | | |

## Analog inputs

The PixFlamingo-F767 flight controller has 4 analog inputs

- ADC Pin10 -> Battery Current
- ADC Pin11 -> Battery Voltage
- ADC Pin14 -> ADC 3V3 Sense
- ADC Pin15 -> ADC 6V6 Sense

## Battery Monitor Configuration

The board has voltage and current sensor inputs on the POWER_ADC connector.

The correct battery setting parameters are:

Enable Battery monitor.

BATT_MONITOR =4

Then reboot.

BATT_VOLT_PIN 11

BATT_CURR_PIN 10

BATT_VOLT_MULT 10.1 (may need adjustment if supplied monitor is not used)

BATT_AMP_PERVLT 17.0 (may need adjustment if supplied monitor is not used)

## Build the FC

./waf configure --board=PixFlamingo-F767
./waf copter

The compiled firmware is located in folder **"build/PixFlamingo-F767/bin/arducopter.apj"**.

## Loading Firmware

The PixFlamingo-F767 flight controller comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station.
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
RC2_REVERSED 1
MOT_SAFE_DISARM 1
BARO_ALTERR_MAX 6000
BRD_HEAT_TARG -1
11 changes: 11 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,9 @@ PB12 VDD_BRICK_VALID INPUT PULLDOWN
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2

PA8 CAN3_RX CAN3
PA15 CAN3_TX CAN3

# SPI2 is for sensors
PD3 SPI2_SCK SPI2
PC2 SPI2_MISO SPI2
Expand Down Expand Up @@ -122,6 +125,10 @@ PE4 MAG_DRDY INPUT

PC13 VDD_SENSORS_EN OUTPUT HIGH

# GPIOs
PE3 HEATER_EN OUTPUT LOW GPIO(80)
define HAL_HEATER_GPIO_PIN 80
define HAL_HAVE_IMU_HEATER 1

PD12 TIM4_CH1 TIM4 GPIO(32) ALARM
PB9 EXTERN_GPIO1 OUTPUT GPIO(4)
Expand All @@ -145,6 +152,7 @@ SPIDEV mpu6500 SPI2 DEVID2 MPU6500_CS MODE3 1*MHZ 4*MHZ
SPIDEV ms5611_int SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
SPIDEV lis3mdl SPI2 DEVID5 MAG_CS MODE3 500*KHZ 500*KHZ
SPIDEV bmp280 SPI1 DEVID3 BARO_CS MODE3 1*MHZ 8*MHZ
SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ

# enable FAT filesystem
define HAL_OS_FATFS_IO 1
Expand Down Expand Up @@ -196,4 +204,7 @@ define STM32_I2C_USE_DMA FALSE
# one barometer
BARO MS56XX SPI:ms5611_int
BARO BMP280 SPI:bmp280
BARO DPS310 SPI:dps310
define HAL_BARO_ALLOW_INIT_NO_BARO
define HAL_COMPASS_AUTO_ROT_DEFAULT 2

0 comments on commit abf5817

Please sign in to comment.