Skip to content

Commit

Permalink
hwdef:add MUPilot autopilot
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Sep 24, 2024
1 parent dc0984c commit a09cc55
Show file tree
Hide file tree
Showing 5 changed files with 186 additions and 0 deletions.
Binary file added Tools/bootloaders/MUPilot_bl.bin
Binary file not shown.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
124 changes: 124 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/MUPilot/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
# CUAVv5 Flight Controller

The CUAVv5 flight controller is sold by [MUGIN UAV](http://https://www.muginuav.com/)

## Features

- STM32F765 microcontroller
- Three IMUs: ICM20689, MPU6000 and BMI055
- internal vibration isolation for IMUs
- Two MS5611 SPI barometers
- builtin I2C IST8310 magnetometer
- microSD card slot
- 6 UARTs plus USB
- 14 PWM outputs with selectable 5V or 3.3V output voltage
- Four I2C and two CAN ports
- External Buzzer
- builtin RGB LED
- external safety Switch
- voltage monitoring for servo rail and Vcc
- two dedicated power input ports for external power bricks

## Pinout

![MUPilot Board](MUPILOT-pinout.jpg "MUPilot")

## UART Mapping

- SERIAL0 -> USB
- SERIAL1 -> UART2 (Telem1)
- SERIAL2 -> UART3 (Telem2)
- SERIAL3 -> UART1 (GPS)
- SERIAL4 -> UART4 (GPS2)
- SERIAL5 -> UART6 (spare)
- SERIAL6 -> UART7 (spare, debug)

The Telem1 and Telem2 ports have RTS/CTS pins, the other UARTs do not
have RTS/CTS.

The UART7 connector is labelled debug, but is available as a general
purpose UART with ArduPilot.

## RC Input

RC input is configured on the PPM pin, at one end of the servo rail,
marked RC in the above diagram. This pin supports all unidirectional RC protocols including PPM. For CRSF/ELRS/etc. protocols
a full UART will need to be used with its SERIALx_PROTOCOL set to "23".

## PWM Output

The CUAVv5 supports up to 14 PWM outputs. First first 8 outputs (labelled
"M1 to M8") are controlled by a dedicated STM32F100 IO controller. These 8
outputs support all PWM output formats, but not DShot.

The remaining 6 outputs (labelled A1 to A6) are the "auxiliary"
outputs. These are directly attached to the STM32F765 and support all
PWM protocols as well as DShot.

All 14 PWM outputs have GND on the top row, 5V on the middle row and
signal on the bottom row.

The 8 main PWM outputs are in 3 groups:

- PWM 1 and 2 in group1
- PWM 3 and 4 in group2
- PWM 5, 6, 7 and 8 in group3

The 6 auxiliary PWM outputs are in 2 groups:

- PWM 1, 2, 3 and 4 in group1
- PWM 5 and 6 in group2

Channels within the same group need to use the same output rate. If
any channel in a group uses DShot then all channels in the group need
to use DShot.

## Battery Monitoring

The board has two dedicated power monitor ports on 6 pin
connectors. The correct battery setting parameters are dependent on
the type of power brick which is connected.

## Compass

The CUAVv5 has a builtin IST8310 compass. Due to potential
interference the board is usually used with an external I2C compass as
part of a GPS/Compass combination.

## GPIOs

The 6 PWM ports can be used as GPIOs (relays, buttons, RPM etc). To
use them you need to limit the number of these pins that is used for
PWM by setting the BRD_PWM_COUNT to a number less than 6. For example
if you set BRD_PWM_COUNT to 4 then PWM5 and PWM6 will be available for
use as GPIOs.

The numbering of the GPIOs for PIN variables in ArduPilot is:

- AUX1 50
- AUX2 51
- AUX3 52
- AUX4 53
- AUX5 54
- AUX6 55

## Analog inputs

The CUAVv5 has 7 analog inputs

- ADC Pin0 -> Battery Voltage
- ADC Pin1 -> Battery Current Sensor
- ADC Pin2 -> Battery Voltage 2
- ADC Pin3 -> Battery Current Sensor 2
- ADC Pin4 -> ADC port pin 2
- ADC Pin14 -> ADC port pin 3
- ADC Pin10 -> ADC 5V Sense
- ADC Pin11 -> ADC 3.3V Sense
- ADC Pin103 -> RSSI voltage monitoring

## Loading Firmware

The board comes pre-installed with an ArduPilot compatible bootloader,
allowing the loading of *.apj firmware files with any ArduPilot
compatible ground station.

7 changes: 7 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/MUPilot/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# hw definition file for processing by chibios_hwdef.py
# for MUPilot bootloader

include ../fmuv5/hwdef-bl.dat

undef APJ_BOARD_ID
APJ_BOARD_ID AP_HW_MUPilot
55 changes: 55 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/MUPilot/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
# hw definition file for processing by chibios_hwdef.py
# for MUPilot hardware.

include ../fmuv5/hwdef.dat

undef APJ_BOARD_ID
APJ_BOARD_ID AP_HW_MUPilot

# extra LEDs, active low, used using the pixracer LED scheme
PH10 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0)
PH11 LED_G1 OUTPUT OPENDRAIN HIGH GPIO(1)
PH12 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2)

undef AP_NOTIFY_GPIO_LED_RGB_RED_PIN
undef AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN

define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0
define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1
define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2

define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1

#heaters
define HAL_HAVE_IMU_HEATER 1
define HAL_IMU_TEMP_DEFAULT 45
define HAL_IMUHEAT_P_DEFAULT 50
define HAL_IMUHEAT_I_DEFAULT 0.07

undef PI6
PI6 MS5611_BOARD_CS CS

#SPI6 for extra BARO
PG13 SPI6_SCK SPI6
PG12 SPI6_MISO SPI6
PB5 SPI6_MOSI SPI6

SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ

undef BARO
BARO MS56XX SPI:ms5611
BARO MS56XX SPI:ms561_board


undef IMU
undef PF11

PF11 ICM42688_CS CS SPEED_VERYLOW

SPIDEV icm42688 SPI1 DEVID2 ICM42688_CS MODE3 2*MHZ 8*MHZ

IMU Invensense SPI:icm20689 ROTATION_NONE
IMU Invensense SPI:icm20602 ROTATION_NONE
IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270
IMU BMI055 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90
IMU BMI088 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90

0 comments on commit a09cc55

Please sign in to comment.