Building and running PX4 Autopilot on BeagleBone Blue

This article will explain how build and run the PX4 Autopilot on BeagleBone Blue.

Requirements

  • Windows Subsystem for Linux (WSL) - Ubuntu 20.04.5 LTS

  • BeagleBone Blue - Debian GNU/Linux 10 (buster)

  • Arm GNU Toolchain - 8.3-2013.02

  • USB to UART Bridge - Silicon Labs CP210x

  • GNSS and Compass M10Q-5883 - Mateksys (optional)

  • Digital Airspeed Sensor ASPD-4525 - Mateksys (optional)

PX4 1.14.0 BBBlue pre-compiled binaries PX4 1.13.3 BBBlue pre-compiled binaries

Setup

You need to connect the USB to UART Bridge to the UART1 port of the BeagleBone Blue board. The bridge will allow you to connect to the PX4 Autopilot via QGroundControl or to perform hardware-in-the-loop simulations. The image below shows the setup.

Building PX4 Autopilot v1.13.3

  • Open a WLS window.

  • Download and unzip the Arm GNU Toolchain (gcc-arm-8.3-2019.02-x86_64-arm-linux-gnueabihf.tar.xz).

  • Clone the PX4 Autopilot repository. Make sure you checkout v1.13.3.

git clone --branch v1.13.3 https://github.com/PX4/PX4-Autopilot.git --recursive
  • Enter the PX4-autopilot folder.

cd PX4-Autopilot

The above step might not be needed for newer PX4 Autopilot builds - v1.14.x.

  • Open the default.px4board file in the boards/beaglebone/blue/ folder.

  • Add the following lines to the file.

CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS5"
CONFIG_DRIVERS_MAGNETOMETER_AKM_AK8963=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
  • Go back to the PX4-autopilot folder and execute the following commands.

export PATH=$PATH:/home/<username>/gcc-arm-8.3-2019.02-x86_64-arm-linux-gnueabihf/bin
make beaglebone_blue_default
  • During the build process, you should observe the following output.

[0/1] Re-running CMake...
-- PX4 version: v1.13.3
-- PX4 config file: /home/kboychev/PX4-Autopilot/boards/beaglebone/blue/default.px4board
-- PLATFORM posix
-- LINUX y
-- TOOLCHAIN arm-linux-gnueabihf
-- ARCHITECTURE cortex-a8
-- ROMFSROOT px4fmu_common
-- TESTING y
-- SERIAL_TEL1 /dev/ttyS1
-- PX4 config: beaglebone_blue_default
-- PX4 platform: posix
-- PX4 lockstep: disabled
-- cmake build type: RelWithDebInfo
-- Building for code coverage
-- ROMFS: ROMFS/px4fmu_common
-- ROMFS:  Adding boards/beaglebone/blue/init/rc.board_defaults -> /etc/init.d/rc.board_defaults
-- Configuring done
-- Generating done
-- Build files have been written to: /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default
[0/963] git submodule src/drivers/gps/devices
[3/963] git submodule src/modules/mavlink/mavlink
[9/963] Generating Mavlink development: src/modules/mavlink/mavlink/message_definitions/v1.0/development.xml
Validating /home/kboychev/PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/development.xml
Parsing /home/kboychev/PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/development.xml
Validating /home/kboychev/PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/standard.xml
Parsing /home/kboychev/PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/standard.xml
Validating /home/kboychev/PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/common.xml
Parsing /home/kboychev/PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/common.xml
Validating /home/kboychev/PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/minimal.xml
Parsing /home/kboychev/PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/minimal.xml
Merged enum MAV_CMD
Merged enum MAV_CMD
Found 229 MAVLink message types in 4 XML files
Generating C implementation in directory /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default/mavlink/development
Generating C implementation in directory /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default/mavlink/standard
Generating C implementation in directory /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default/mavlink/common
Generating C implementation in directory /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default/mavlink/minimal
Copying fixed headers for protocol 2.0 to /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default/mavlink
[19/963] Performing download step (git clone) for 'librobotcontrol'
-- librobotcontrol download command succeeded.  See also /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default/librobotcontrol-prefix/src/librobotcontrol-stamp/librobotcontrol-download-*.log
[22/963] Performing configure step for 'librobotcontrol'
-- librobotcontrol configure command succeeded.  See also /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default/librobotcontrol-prefix/src/librobotcontrol-stamp/librobotcontrol-configure-*.log
[23/963] Performing build step for 'librobotcontrol'
-- librobotcontrol build command succeeded.  See also /home/kboychev/PX4-Autopilot/build/beaglebone_blue_default/librobotcontrol-prefix/src/librobotcontrol-stamp/librobotcontrol-build-*.log
[963/963] Linking CXX shared library src/examples/dyn_hello/examples__dyn_hello.px4mod
  • Once the build is complete, you must upload the binaries to the BeagleBone Blue board. Use the following command to upload the binaries and the configuration files.

rsync -arh --progress /home/<username>/PX4-Autopilot/build/beaglebone_blue_default/bin debian@192.168.7.2:/home/debian/px4
rsync -arh --progress /home/<username>/PX4-Autopilot/build/beaglebone_blue_default/etc debian@192.168.7.2:/home/debian/px4

Running PX4 Autopilot v1.13.3

Once the binaries and the configuration files are uploaded to the BeagleBone Blue you can SSH into the BeagleBone Blue and run the px4 binary. To SSH into the BeagleBone Blue and run the px4 binary execute the following commands:

ssh debian@192.168.7.2
cd /home/debian/px4
./bin/px4 -s px4.config

The px4.config file

The px4.config file is specific for every board. The px4.config file below is specific to the BeagleBoneBlue board only.

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

set REQUESTED_AUTOSTART 2100
set PARAM_FILE eeprom/parameters_"$REQUESTED_AUTOSTART"
set AUTOSTART_FILE etc/init.d/airframes/2100_standard_plane

#Circuit breakers
param set CBRK_SUPPLY_CHK 894281

#Parameters 
param select $PARAM_FILE
if [ -f $PARAM_FILE ]
then
	if param load
	then
		echo "[param] Loaded: $PARAM_FILE"
	else
		echo "[param] FAILED loading $PARAM_FILE"
	fi
else
	echo "[param] Parameter file not found, creating $PARAM_FILE"
fi

if param compare SYS_AUTOSTART $REQUESTED_AUTOSTART
then
	param set SYS_AUTOCONFIG 0
else
	param set SYS_AUTOCONFIG 1 
	param set SYS_AUTOSTART 2100
fi

. "$AUTOSTART_FILE"

if param compare SYS_AUTOCONFIG 1
then
	param set SYS_AUTOCONFIG 0
fi

# Board defaults
param set BAT1_V_CHANNEL 5
param set BAT1_V_DIV 11.0


# User-defined params 

param set SYS_HITL 0
param set SYS_CTRL_ALLOC 1

# Waypoint storage
dataman start

# Resource load monitor
load_mon start

# RC update
rc_update start
manual_control start

# Sensors

if param compare SYS_HITL 1
then
    param set COM_RC_IN_MODE 1
    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 -a 0x68 start
    sleep 1
    ak8963 -I -a 0xC start
    sleep 1
    qmc5883l -X -a 0x0D start
    sleep 1
    ms4525do -X -a 0x2 start
    sleep 1
    gps start -d /dev/ttyS5 -b 9600 -p nmea

    board_adc start
    battery_status start

    sensors start
    commander start
fi

# Interface (configure outputs)

if param compare SYS_HITL 1
then
    pwm_out_sim start -m hil
else
    linux_pwm_out start
fi

# FW applications (start standard fixed-wing applications)

ekf2 start &

if param compare SYS_CTRL_ALLOC 1
then
	control_allocator start
fi

fw_att_control start
fw_pos_control_l1 start
airspeed_selector start
fw_autotune_attitude_control start
land_detector start fixedwing

# Mavlink

mavlink start -d /dev/ttyS1 -b 921600 -x -Z

# RC input
rc_input start -d /dev/ttyS4

# Navigator
navigator start

# Logger

logger start -t -b 200

# Boot complete

mavlink boot_complete

Last updated