mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
MAVLink app: Use better default rates
This commit is contained in:
parent
3ccc6823a2
commit
d0d46c9713
@ -1440,15 +1440,15 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
case MAVLINK_MODE_NORMAL:
|
||||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("GPS_GLOBAL_ORIGIN", 0.5f);
|
||||
configure_stream("HIGHRES_IMU", 1.0f);
|
||||
configure_stream("ATTITUDE", 10.0f);
|
||||
configure_stream("HIGHRES_IMU", 2.0f);
|
||||
configure_stream("ATTITUDE", 20.0f);
|
||||
configure_stream("VFR_HUD", 8.0f);
|
||||
configure_stream("GPS_RAW_INT", 1.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 3.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 3.0f);
|
||||
configure_stream("RC_CHANNELS_RAW", 1.0f);
|
||||
configure_stream("RC_CHANNELS_RAW", 4.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 3.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 8.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 0.5f);
|
||||
configure_stream("OPTICAL_FLOW_RAD", 5.0f);
|
||||
break;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user