Files
bizhang_-obav/posix-configs/rpi/px4_test.config
blazczak 57da61dc17 posix-configs/rpi: Fix mavlink over UART (/dev/ttyAMA0)
UART is the primary interface for telemetry radio: https://docs.emlid.com/navio2/ardupilot/hardware-setup/#uart-radio

Check first if /dev/ttyUSB0 exists (https://docs.emlid.com/navio2/ardupilot/hardware-setup/#usb-radio); if not, fall back to configuring over UART (/dev/ttyAMA0).

Use stricter check for character special file (-c) rather than just file (-f).

'console=serial0,115200' needs to be removed from /cmdline.txt as additional configuration step. This should be documented in the Navio2 section of docs.px4.io. Presumably, this is already performed as part of the Raspberry Pi OS prebuilt image Emlid spins.
2020-10-03 10:51:27 -04:00

94 lines
1.3 KiB
Bash

#!/bin/sh
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
. px4-alias.sh
# navio config for simple testing
uorb start
if [ -f eeprom/parameters ]
then
param load
fi
param set CBRK_SUPPLY_CHK 894281
param set SYS_AUTOSTART 4001
param set MAV_BROADCAST 1
param set MAV_TYPE 2
param set IMU_GYRO_RATEMAX 400
dataman start
load_mon start
mpu9250 -s -R 2 start
lsm9ds1 -s -R 4 start
lsm9ds1_mag -s -R 4 start
ms5611 -X start
navio_rgbled start
board_adc start
battery_status start
gps start -d /dev/spidev0.0 -i spi -p ubx
rc_update start
sensors start
commander start
navigator start
ekf2 start
land_detector start multicopter
mc_hover_thrust_estimator start
mc_pos_control start
mc_att_control start
mavlink start -x -u 14556 -r 1000000
if [ -c /dev/ttyUSB0 ]
then
mavlink start -x -d /dev/ttyUSB0
elif [ -c /dev/ttyAMA0 ]
then
mavlink start -x -d /dev/ttyAMA0
fi
navio_sysfs_rc_in start
linux_pwm_out start
logger start -t -f -b 200
mavlink boot_complete
sleep 5
ver all
sleep 1
commander check
sleep 1
dataman status
sleep 1
ekf2 status
sleep 1
logger status
sleep 1
mavlink status
sleep 1
mavlink status streams
sleep 1
param status
sleep 1
pwm info
sleep 1
sensors status
sleep 1
perf
sleep 1
perf latency
sleep 1
work_queue status
sleep 1
uorb top -1
sleep 1
shutdown