You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
48 lines
1.1 KiB
48 lines
1.1 KiB
#!/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 a quad |
|
uorb start |
|
if [ -f eeprom/parameters ] |
|
then |
|
param load |
|
fi |
|
param set SYS_AUTOSTART 4001 |
|
param set MAV_BROADCAST 1 |
|
param set MAV_TYPE 2 |
|
param set BAT_CNT_V_VOLT 0.001 |
|
param set BAT_V_DIV 10.9176300578 |
|
param set BAT_CNT_V_CURR 0.001 |
|
param set BAT_A_PER_V 15.391030303 |
|
dataman start |
|
df_lsm9ds1_wrapper start -R 4 |
|
#df_mpu9250_wrapper start -R 10 |
|
#df_hmc5883_wrapper start |
|
df_ms5611_wrapper start |
|
navio_rgbled start |
|
navio_adc start |
|
gps start -d /dev/spidev0.0 -i spi -p ubx |
|
sensors start |
|
commander start |
|
navigator start |
|
ekf2 start |
|
land_detector start multicopter |
|
mc_pos_control start |
|
mc_att_control start |
|
mavlink start -x -u 14556 -r 1000000 |
|
mavlink stream -u 14556 -s HIGHRES_IMU -r 50 |
|
mavlink stream -u 14556 -s ATTITUDE -r 50 |
|
|
|
if [ -f /dev/ttyUSB0 ] |
|
then |
|
mavlink start -x -d /dev/ttyUSB0 |
|
mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50 |
|
mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50 |
|
fi |
|
|
|
navio_sysfs_rc_in start |
|
linux_pwm_out start |
|
logger start -t -b 200 |
|
mavlink boot_complete
|
|
|