2016-04-29 09:39:23 +05:30
|
|
|
uorb start
|
|
|
|
|
param set SYS_AUTOSTART 4001
|
2016-06-05 12:55:14 +02:00
|
|
|
param set MAV_BROADCAST 1
|
2016-04-29 09:39:23 +05:30
|
|
|
sleep 1
|
|
|
|
|
param set MAV_TYPE 2
|
2016-06-24 19:42:04 +02:00
|
|
|
df_lsm9ds1_wrapper start -R 4
|
|
|
|
|
#df_mpu9250_wrapper start -R 10
|
|
|
|
|
#df_hmc5883_wrapper start
|
2016-06-24 20:19:34 +02:00
|
|
|
df_ms5611_wrapper start
|
2016-07-14 13:55:21 +02:00
|
|
|
gps start -d /dev/pts/0
|
2016-04-29 09:39:23 +05:30
|
|
|
sensors start
|
|
|
|
|
commander start
|
2016-06-24 19:42:38 +02:00
|
|
|
attitude_estimator_q start
|
|
|
|
|
position_estimator_inav start
|
2016-04-29 09:39:23 +05:30
|
|
|
land_detector start multicopter
|
|
|
|
|
mc_pos_control start
|
|
|
|
|
mc_att_control start
|
|
|
|
|
mavlink start -u 14556 -r 1000000
|
|
|
|
|
sleep 1
|
|
|
|
|
mavlink stream -u 14556 -s HIGHRES_IMU -r 50
|
|
|
|
|
mavlink stream -u 14556 -s ATTITUDE -r 50
|
2016-07-14 13:55:21 +02:00
|
|
|
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
|
|
|
|
|
navio_sysfs_pwm_out start
|
|
|
|
|
mavlink boot_complete
|