forked from Archive/PX4-Autopilot
SITL: Run more streams at higher rates
This commit is contained in:
parent
16cb971d63
commit
44eff36819
|
@ -43,8 +43,11 @@ position_estimator_inav start
|
|||
mc_pos_control start
|
||||
mc_att_control start
|
||||
mixer load /dev/pwm_output0 ../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
|
||||
mavlink start -u 14556 -r 60000
|
||||
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
|
||||
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
|
||||
mavlink stream -r 50 -s ATTITUDE -u 14556
|
||||
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
|
||||
mavlink start -u 14556 -r 2000000
|
||||
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
|
||||
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
|
||||
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
|
||||
mavlink stream -r 80 -s ATTITUDE -u 14556
|
||||
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
|
||||
mavlink stream -r 20 -s RC_CHANNELS -u 14556
|
||||
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
|
||||
|
|
Loading…
Reference in New Issue