PX4 BeagleBone® Blue-based quadcopter

This article shows how to build a PX4 BeagleBone® Blue-based quadcopter

Hardware

  • Radiomaster Pocket Radio Controller (M2)

  • Radiomaster RP3 V2 ExpressLRS 2.4ghz Nano Receiver

  • Radiomaster Ranger Nano 2.4GHZ ELRS Module

  • Matek Systems GNSS & Compass, M10Q-5883

  • BeagleBone® Blue

  • 4x BLHeli Series 12A ESC

  • 2x MT2205II 2300KV Brushless Motor CW

  • 2x MT2205II 2300KV Brushless Motor CCW

  • FT VersaCopter v2.0

Software

Configuration

TX, RX, and backpack

The Radiomaster Pocket Radio Controller (M2) and RP3 V2 ExpressLRS 2.4ghz Nano Receiver must be updated to ExpressLRS 3.5.2 TX/RX firmware (the latest at the time of writing this article). Similarly, the Ranger Nano 2.4GHZ ELRS module must be updated to ExpressLRS 1.5.0 backpack firmware (the latest at the time of writing this article).

Hardware -> Internal RF -> Type - CSRF -> Baudrate - 400k Hardware -> ADC filter - Off Tools -> 01 Express LRS -> Packet Rate - D250 -> Telem Ratio - 1:2 (19921bps) -> Switch Mode - Hybrid -> Link Mode - MAVLink -> Mode Match - Off Tools -> 01 Express LRS -> Backpack -> Backpack - On -> DVR Rec - Off -> DVR Srt Dly - 0s -> DVR Stp Dly - 0s -> HT Enable - Off -> HT Start Chan - AUX 1 -> Telemetry - WiFi In the model setup, set Internal RF -> Mode - Off and set External RF -> Mode - CRSF. Note that the receiver's serial protocol must be set to MAVLink.

BeagleBone® Blue

  • Balena Etcher must be used to flash the bone-Debian-10.3-console-armhf-2020-04-06-1gb.img.xz to a microSD card.

  • The microSD card must be inserted into the microSD card slot of the BeagleBone Blue board

  • The microSD card button must be pressed while the BeagleBone Blue board is powered. The button should be released 1-2 seconds after powering on the board. This will instruct the BeagleBone Blue board to boot from the microSD card.

  • After the board boots from the microSD card use a SSH client (e.g. PuTTY) to connect to the board. Note that the default username is debian and the default password is temppwd.

  • Once connected to the board the /boot/uEnv.txt file must be modified by uncommenting the last line in the file (invoking a generic flasher).

  • Power cycle the BeagleBone blue board.

  • Wait until the flashing is complete (the microSD card contents will be flashed onto the EMMC.

PX4

Using Windows Subsystem for Linux (WSL), the latest stable PX4 release must be cloned (v1.15.0 at the time of writing this article). Before compiling, the default.px4board file in boards/beaglebone/blue folder must be modified to include the following lines:

CONFIG_BOARD_TESTING=n
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS5"
CONFIG_DRIVERS_MAGNETOMETER_AKM_AK8963=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_DRIVERS_RC_CRSF_RC=y

In addition, two CPP files must be modified - the CrsfRc.cpp file in src/drivers/rc/crsf_rc folder and the board_pwm_out.cpp in the boards/beaglebone/blue/src folder.

The #define CRSF_BAUDRATE in CrsfRc.cpp must be changed from 420000 to 460800. If left unchanged, the csrf_rc driver would not start properly.

The CRSF driver is not used in this example. MAVLink is used both for telemetry and command and control. However, the above change is required if CRSF is to be used for command and control instead of MAVLink.

In board_pwm_out.cpp in the BBBlueRcPWMOut::send_output_pwm function an additional line must be added before the return statement:

 rc_usleep(1000000/50);

This makes the PWM signal frequency approximately 50 Hz so the BLHeli Series 12A ESCs accept it.

Once the above changes are made, PX4 can be compiled for the BeageBone Blue board with the following command:

make beagebone_blue_default

For more information on how to upload the compiled PX4 binaries to the BeagleBone Blue board using the rsync command please refer to:

Building and running PX4 Autopilot on BeagleBone® Blue

Below is the px4.config file for PX4:

#!/bin/sh
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
. px4-alias.sh

set PARAM_FILE "px4.parameters"

param select $PARAM_FILE
if ! param import
then
	echo "Error [init] param import failed"

	#Board
	param set CBRK_SUPPLY_CHK 894281

	param set BAT1_V_CHANNEL 6
	param set BAT1_V_DIV 11.0

	
	#Set all platform-specific parameters
	
	param set ...

	param save $PARAM_FILE

fi

# Waypoint storage
dataman start

# Socket communication send_event handler
send_event start

# Resource load monitor
load_mon start

# RC update (map raw RC input to calibrate manual control) start before commander
rc_update start
manual_control start

# Sensors (start before commander so preflight checks are proprely run). Commander needs to be this early for in-air-restarts.

if param greater SYS_HITL 0
then

    pwm_out_sim start -m hil
    sensors start -h
    commander start -h
    param set GPS_1_CONFIG 0

else

    sleep 1
    bmp280 -I -a 0x76 start
    sleep 1
    mpu9250_i2c -I start
    sleep 1
    ak8963 -I -a 0xC start
    sleep 1
    qmc5883l -X -a 0x0d start
    sleep 1
    gps start -d /dev/ttyS2 -p ubx

    board_adc start
    battery_status start

    sensors start
    commander start

    linux_pwm_out start
fi

# Applications (start standard fixed wing or multicopter applications)

ekf2 start &

control_allocator start
mc_rate_control start
mc_att_control start
mc_hover_thrust_estimator start
flight_mode_manager start
mc_pos_control start
land_detector start multicopter

# Telemetry (Mavlink)
mavlink start -d /dev/ttyS5 -b 460800 -r 1200 -Z

# RC input (CRSF)
#crsf_rc start -d /dev/ttyS5
#rc_input start -d /dev/ttyS5

# Start the navigator
navigator start

# Logger
logger start -b 8 -t

mavlink boot_complete

unset PARAM_FILE

Wiring

Below is a wiring diagram showing the UART and I2C connections to the M10Q-5883 GNSS & Compass and the UART connection to the Radiomaster RP3 V2 ExpressLRS 2.4ghz Nano receiver. The BLHeli Series 12A ESCs are connected to the BeagleBone Blue board via servo 1 to 4 outputs. Only the signal and ground wires are connected to the servo outputs, as the 12V DC power connector powers the board.

Completed build

Last updated