forked from Archive/PX4-Autopilot
mavlink: Enable a few helpful streams on companion link
This commit is contained in:
parent
fbdfc698cc
commit
64ea4071a7
|
@ -1454,6 +1454,9 @@ Mavlink::task_main(int argc, char *argv[])
|
||||||
case MAVLINK_MODE_ONBOARD:
|
case MAVLINK_MODE_ONBOARD:
|
||||||
configure_stream("SYS_STATUS", 1.0f);
|
configure_stream("SYS_STATUS", 1.0f);
|
||||||
configure_stream("ATTITUDE", 50.0f);
|
configure_stream("ATTITUDE", 50.0f);
|
||||||
|
configure_stream("HIGHRES_IMU", 50.0f);
|
||||||
|
configure_stream("VFR_HUD", 5.0f);
|
||||||
|
configure_stream("GPS_RAW_INT", 5.0f);
|
||||||
configure_stream("GLOBAL_POSITION_INT", 50.0f);
|
configure_stream("GLOBAL_POSITION_INT", 50.0f);
|
||||||
configure_stream("LOCAL_POSITION_NED", 30.0f);
|
configure_stream("LOCAL_POSITION_NED", 30.0f);
|
||||||
configure_stream("CAMERA_CAPTURE", 2.0f);
|
configure_stream("CAMERA_CAPTURE", 2.0f);
|
||||||
|
@ -1462,6 +1465,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||||
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
|
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
|
||||||
configure_stream("DISTANCE_SENSOR", 10.0f);
|
configure_stream("DISTANCE_SENSOR", 10.0f);
|
||||||
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
|
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
|
||||||
|
configure_stream("RC_CHANNELS_RAW", 20.0f);
|
||||||
configure_stream("VFR_HUD", 10.0f);
|
configure_stream("VFR_HUD", 10.0f);
|
||||||
configure_stream("SYSTEM_TIME", 1.0f);
|
configure_stream("SYSTEM_TIME", 1.0f);
|
||||||
configure_stream("TIMESYNC", 10.0f);
|
configure_stream("TIMESYNC", 10.0f);
|
||||||
|
|
Loading…
Reference in New Issue