2017-05-08 06:47:22 -03:00
|
|
|
# navio config for a quad
|
2016-07-18 12:01:39 -03:00
|
|
|
uorb start
|
2016-12-22 09:26:50 -04:00
|
|
|
param load
|
2016-07-18 12:01:39 -03:00
|
|
|
param set SYS_AUTOSTART 4001
|
|
|
|
param set MAV_BROADCAST 1
|
|
|
|
param set MAV_TYPE 2
|
2017-03-09 06:13:33 -04:00
|
|
|
param set SYS_MC_EST_GROUP 2
|
2017-05-14 10:22:49 -03:00
|
|
|
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
|
2017-03-09 09:29:17 -04:00
|
|
|
dataman start
|
2016-07-18 12:01:39 -03:00
|
|
|
df_lsm9ds1_wrapper start -R 4
|
|
|
|
#df_mpu9250_wrapper start -R 10
|
|
|
|
#df_hmc5883_wrapper start
|
|
|
|
df_ms5611_wrapper start
|
2017-02-24 05:24:40 -04:00
|
|
|
navio_rgbled start
|
2017-05-14 03:54:15 -03:00
|
|
|
navio_adc start
|
2016-09-06 17:43:28 -03:00
|
|
|
gps start -d /dev/spidev0.0 -i spi -p ubx
|
2016-07-18 12:01:39 -03:00
|
|
|
sensors start
|
|
|
|
commander start
|
2016-12-22 09:26:50 -04:00
|
|
|
navigator start
|
2017-03-09 06:13:33 -04:00
|
|
|
ekf2 start
|
2016-07-18 12:01:39 -03:00
|
|
|
land_detector start multicopter
|
|
|
|
mc_pos_control start
|
|
|
|
mc_att_control start
|
|
|
|
mavlink start -u 14556 -r 1000000
|
|
|
|
mavlink stream -u 14556 -s HIGHRES_IMU -r 50
|
|
|
|
mavlink stream -u 14556 -s ATTITUDE -r 50
|
|
|
|
mavlink start -d /dev/ttyUSB0
|
|
|
|
mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
|
|
|
|
mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
|
|
|
|
navio_sysfs_rc_in start
|
2017-06-06 10:40:24 -03:00
|
|
|
linux_pwm_out start
|
2017-04-24 04:12:10 -03:00
|
|
|
logger start -t -b 200
|
2016-09-03 00:05:57 -03:00
|
|
|
mavlink boot_complete
|