From d89937502c0b0ccf04524be5af985a257f2d20e5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 13 May 2016 10:34:25 +0200 Subject: [PATCH] MAVLink: Clean up stream init --- src/modules/mavlink/mavlink_main.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index c6e9772f42..650fd3c34f 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1868,7 +1868,6 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("EXTENDED_SYS_STATE", 2.0f); configure_stream("ALTITUDE", 10.0f); configure_stream("VISION_POSITION_NED", 10.0f); - configure_stream("NAMED_VALUE_FLOAT", 10.0f); configure_stream("ESTIMATOR_STATUS", 1.0f); configure_stream("ADSB_VEHICLE", 10.0f); break; @@ -1899,7 +1898,6 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("HOME_POSITION", 0.5f); configure_stream("GLOBAL_POSITION_INT", 10.0f); configure_stream("ATTITUDE_TARGET", 8.0f); - //configure_stream("PARAM_VALUE", 300.0f); configure_stream("MISSION_ITEM", 50.0f); configure_stream("NAMED_VALUE_FLOAT", 50.0f); configure_stream("OPTICAL_FLOW_RAD", 10.0f); @@ -1914,12 +1912,11 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("LOCAL_POSITION_NED", 30.0f); configure_stream("MANUAL_CONTROL", 5.0f); configure_stream("HIGHRES_IMU", 50.0f); - configure_stream("GPS_RAW_INT", 20.0f); + configure_stream("GPS_RAW_INT", 10.0f); configure_stream("CAMERA_TRIGGER", 500.0f); configure_stream("EXTENDED_SYS_STATE", 2.0f); configure_stream("ALTITUDE", 10.0f); configure_stream("VISION_POSITION_NED", 10.0f); - configure_stream("NAMED_VALUE_FLOAT", 50.0f); configure_stream("ESTIMATOR_STATUS", 5.0f); configure_stream("ADSB_VEHICLE", 20.0f); default: