|
|
|
#!/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
|
|
|
|
|
|
|
|
mpu9250 -s -R 2 start
|
|
|
|
lsm9ds1 -s -R 4 start
|
|
|
|
lsm9ds1_mag -s -R 4 start
|
|
|
|
ms5611 -X start
|
|
|
|
|
|
|
|
navio_rgbled start
|
|
|
|
|
|
|
|
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 [ -f /dev/ttyUSB0 ]
|
|
|
|
then
|
|
|
|
mavlink start -x -d /dev/ttyUSB0
|
|
|
|
fi
|
|
|
|
|
|
|
|
navio_sysfs_rc_in start
|
|
|
|
linux_pwm_out start
|
|
|
|
|
|
|
|
logger start -t -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 show
|
|
|
|
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
|