Omnibus F4 SD

The Omnibus F4 SD is a controller board designed for racers. In contrast to a typical racer board it has some additional features, such as an SD card and a faster CPU.

These are the main differences compared to a Pixracer:

  • Lower price
  • Fewer IO ports (though it's still possible to attach a GPS or a Flow sensor for example)
  • Requires external pull up resistor on the I2C bus for external GPS, see I2C below.
  • Less RAM (192 KB vs. 256 KB) and FLASH (1 MB vs. 2 MB)
  • Same board dimensions as a Pixracer, but slightly smaller form factor (because it has less connectors)
  • Integrated OSD (not yet implemented in software)

All the usual PX4 features can still be used for your racer!

Key Features

  • Main System-on-Chip: STM32F405RGT6
    • CPU: 168 MHz ARM Cortex M4 with single-precision FPU
    • RAM: 192 KB SRAM
    • FLASH: 1 MB
  • Standard racer form factor: 36x36 mm with standard 30.5 mm hole pattern
  • MPU6000 Accel / Gyro
  • BMP280 Baro (not all boards have it mounted)
  • microSD (logging and parameters)
  • Futaba S.BUS and S.BUS2 / Spektrum DSM2 and DSMX / Graupner SUMD / PPM input / Yuneec ST24
  • OneShot PWM out (configurable)
  • built-in current sensor
  • built-in OSD chip (AB7456 via SPI, not supported yet)

Where to Buy

The board is produced by different vendors, with some variations (e.g. with or without a barometer).

PX4 is compatible with boards that support the Betaflight OMNIBUSF4SD target (if OMNIBUSF4SD is present on the product page the board should work with PX4).

Any Omnibus F4 labeled derivative (e.g. clone) should work as well. However, power distribution on these boards is of varying quality.

These are the boards tested and known to work:

Accessories include:

  • ESP8266 WiFi Module for MAVLink telemetry. You need to connect these pins: GND, RX, TX, VCC and CH-PD (CH-PD to 3.3V). The baud rate is 921600.

Connectors

Boards from different vendors (based on this design) can have significantly different layout. Layouts/Silkscreens for various versions are shown below.

Airbot Omnibus F4 SD

Below are silkscreens for the Airbot Omnibus F4 SD (V1), showing both top and bottom.

Omnibus F4 SD v1 Silkscreen Top Omnibus F4 SD v1 Silkscreen Bottom

Hobbywing XRotor Flight Controller F4

Below are silkscreens for the Hobbywing XRotor Flight Controller F4.

Hobbywing XRotor Flight Controller F4 Silkscreen

Pinouts

Radio Control

RC is connected to one of the following ports:

  • UART1
  • SBUS/PPM port (via inverter, internally goes to UART1)

Some Omnibus F4 boards have a jumper connecting either or both the MCU SBUS and PPM to a single pin header. Set your jumper or solder bridge to the appropriate MCU pin before use.

UARTs

  • UART6: GPS port

    • TX: MCU pin PC6
    • RX: MCU pin PC7

    • Airbot Omnibus F4 SD Pinout is on Port J10 (TX6/RX6):

    Omnibus F4 SD UART6

  • UART4

    • TX: MCU pin PA0
    • RX: MCU pin PA1
    • 57600 baud
    • This can be configured as the TELEM 2 port.
    • Airbot Omnibus F4 SD Pinout:
      • TX: RSSI pin
      • RX: PWM out 5

    Omnibus F4 SD UART4

    Omnibus F4 SD UART4 Top

I2C

There is one I2C port available via:

  • SCL: MCU pin PB10 (might be labeled as TX3)
  • SDA: MCU pin PB11 (might be labeled as RX3)

You will need external pullups on both signals (clock and data). You can use 2.2k pullups for example to attach an external mag.

  • Airbot Omnibus F4 SD Pinout is on Port J10 (SCL [clock] / SCA [data]):

Here is an example implementation. I used a Spektrum plug to get 3.3v from the DSM port, connecting only 3.3v + to each line via 2.2k resistor.

Omnibus F4 SD Pullup

Omnibus F4 SD Pullup Implementation

RC Telemetry

The Omnibus supports telemetry to the RC Transmitter using FrSky Telemetry or CRSF Crossfire Telemetry.

CRSF Crossfire Telemetry

TBS CRSF Crossfire telemetry is used to send telemetry data from the flight controller (the vehicle's attitude, battery, flight mode and GPS data) to the RC transmitter (Taranis).

Benefits over FrSky telemetry include:

  • Only a single UART is needed for RC and telemetry.
  • The CRSF protocol is optimized for low latency.
  • 150 Hz RC update rate.
  • The signals are uninverted and thus no (external) inverter logic is required.

For Omnibus we recommend the TBS Crossfire Nano RX, since it is specifically designed for small Quads.

On the handheld controller (e.g. Taranis) you will also need a Transmitter Module. This can be plugged into the back of the RC controller.

The referenced links above contains the documentation for the TX/RX modules.

Setup

Connect the Nano RX and Omnibus pins as shown:

Omnibus UART1 Nano RX
TX Ch2
RX Ch1

Nothing else needs to be configured on PX4 flight controller side - the RC protocol is auto-detected.

Next update the TX/RX modules to use the CRSF protocol and set up telemetry. Instructions for this are provided in the TBS Crossfire Manual (search for 'Setting up radio for CRSF').

Schematics

The schematics are provided by Airbot: OmnibusF4-Pro-Sch.pdf.

PX4 Bootloader Update

The board comes pre-installed with Betaflight. Before PX4 firmware can be installed, the PX4 bootloader must be flashed.

There are two options for flashing the bootloader: via Betaflight Configurator (easier), or building from source (guaranteed to work).

Bootloader Update using Betaflight Configurator

To install the PX4 bootloader using the Betaflight Configurator:

  1. Download the pre-built bootloader binary: omnibusf4sd_bl.hex.
  2. Download the Betaflight Configurator for your platform.

    If using the Chrome web browser, a simple cross-platform alternative is to install the configurator as an extension from here.

  3. Connect the board to your PC and start the Configurator.
  4. Press the Load Firmware [Local] button Betaflight Configurator - Local Firmware
  5. Select the bootloader binary from the file system and then flash the board.

You should now be able to install PX4 firmware on the board.

Bootloader Update using Source

Download Bootloader Source

Download and build the Bootloader via:

git clone --recursive  https://github.com/PX4/Bootloader.git
cd Bootloader
make omnibusf4sd_bl

Flash Bootloader

You can flash the PX4 bootloader using the dfu-util or the graphical dfuse tool on windows.

Don't be afraid to try flashing using any of the below methods. The STM32 MCU cannot be bricked. DFU cannot be overwritten by flashing and will always allow you to install a new firmware, even if flashing fails.

Enter DFU mode

Both methods require the board to be in DFU mode. To enter DFU mode, hold the boot button down while connecting the USB cable to your computer. The button can be released after the board is powered up.

dfu-util
dfu-util -a 0 --dfuse-address 0x08000000 -D  build/omnibusf4sd_bl/omnibusf4sd_bl.bin

Reboot the flight controller and it let it boot without holding the boot button.

dfuse

See the dfuse manual is here: https://www.st.com/resource/en/user_manual/cd00155676.pdf

Flash the omnibusf4sd_bl.bin file.

Building Firmware

To build PX4 for this target:

make omnibus_f4sd_default

Installing PX4 Firmware

The firmware can be installed in any of the normal ways:

  • Build and upload the source
    make omnibus_f4sd_default upload
    
  • Load the firmware using QGroundControl. You can use either pre-built firmware or your own custom firmware.

Configuration

In addition to the basic configuration, the following parameters are important:

Parameter Setting
SYS_HAS_MAG This should be disabled since the board does not have an internal mag. You can enable it if you attach an external mag.
SYS_HAS_BARO Disable this if your board does not have a barometer.
MOT_ORDERING If you use a 4-in-1 ESC with Betaflight/Cleanflight motor assignment, this parameter can be set accordingly.

Reinstall Betaflight

In order to switch back to Betaflight:

  • Backup the PX4 parameters, e.g. by exporting them to an SD card
  • Keep the bootloader button pressed while attaching the USB cable
  • Then flash Betaflight as usual with the Betaflight-configurator

Further Info

A review with further information of the board can be found here.

This page also provides a nice overview with pinouts and setup instructions.

© PX4 Dev Team. License: CC BY 4.0            Updated: 2020-10-28 22:06:47

results matching ""

    No results matching ""