libraries/AP_HAL_ChibiOS/hwdef/YARIV6X/README.md
The YARI V6X autopilot is based on the FMUV6X and Pixhawk Autopilot Bus open source specifications. The Pixhawk Autopilot Bus (PAB) form factor enables the YARI V6X to be used on any PAB carrier board.
YARI V6X autopilots are produced and sold by YARI Robotics.
Autopilot Module
Carrier Board
| Serial# | Port | UART |
|---|---|---|
| SERIAL0 | OTG1 | USB |
| SERIAL1 | Telem1 | UART7 (RTC/CTS) |
| SERIAL2 | Telem2 | UART5 (RTS/CTS) |
| SERIAL3 | GPS1 | USART1 |
| SERIAL4 | GPS2 | UART8 |
| SERIAL5 | Telem3 | USART2 (RTS/CTS) |
| SERIAL6 | UART4, I2C | UART4 |
| SERIAL7 | Debug Console | USART3 |
| SERIAL8 | IO/RC | USART6 |
All UARTs have DMA capability
The YARI V6X supports up to 16 PWM outputs (M1-8 and A1-8). All 16 outputs support all normal PWM output formats. All outputs support DShot and BiDir DShot, except A7 and A8 which only support PWM.
The 8 FMU PWM outputs (A1-8) are in 4 groups:
FMU outputs within the same group need to use the same output rate and protocol. If any output in a group uses DShot then all channels in that group need to use DShot.
The PPM pin, which by default is mapped to a timer input, can be used for all ArduPilot supported unidirectional receiver protocols,. Half-Duplex and bi-directional protocols, such as CRSF/ELRS, Fport, and SRXL2) require a true UART connection (see below). FPort when connected to PPM will only provide RC without telemetry.
To allow CRSF and embedded telemetry available in Fport, CRSF, and SRXL2 receivers, a full UART, such as SERIAL6 (UART4) would need to be used for receiver connections. Below are setups using SERIAL6.
SERIAL6_PROTOCOL<SERIAL6_PROTOCOL> should be set to “23”.SERIAL6_OPTIONS<SERIAL6_OPTIONS> be set to “15”.SERIAL6_OPTIONS<SERIAL6_OPTIONS> be set to “0”.SERIAL6_OPTIONS<SERIAL6_OPTIONS> be set to “4” and connects only the TX pin.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.
The default battery parameters for use with a digital power module (with INA2xx) connected to Power1 port:
BATT_I2C_BUS<BATT_I2C_BUS> = 1BATT_I2C_ADDR<BATT_I2C_ADDR> = 0BATT_MONITOR<BATT_MONITOR> = 21For use with Power2 port update :ref:BATT_I2C_BUS<BATT_I2C_BUS> = 2
The YARI V6X autopilot has a built-in compass. Due to potential interference, the autopilot is usually used with an external I2C compass as part of a GPS/Compass combination.
The 8 FMU outputs can be used as GPIOs (relays, buttons, RPM etc). To use them you need to set the output’s SERVOx_FUNCTION to -1. See GPIOs page for more information.
The numbering of the GPIOs for PIN variables in ArduPilot is:
Additional GPIOs:
The YARI V6X has 2 analog inputs, one 6V tolerant and one 3.3V tolerant
RSSI_TYPE<RSSI_TYPE> = 1 and :ref:RSSI_ANA_PIN<RSSI_ANA_PIN> = 103.The board comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of xxxxxx.apj firmware files with any ArduPilot compatible ground station.
Firmware for YARI V6X can be found here in sub-folders labeled “YARIV6X”.
Subsequently, you can update firmware with Mission Planner or QGroundcontrol.