From 4154ab4e2629a1ebfa0802b624223b97a375d52d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 3 Oct 2015 10:03:50 +0200 Subject: [PATCH] Include named value float --- src/modules/mavlink/mavlink_main.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 95ed3e8f64..ca5cf307e5 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1644,6 +1644,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("GPS_RAW_INT", 1.0f); configure_stream("GLOBAL_POSITION_INT", 3.0f); configure_stream("LOCAL_POSITION_NED", 3.0f); + configure_stream("NAMED_VALUE_FLOAT", 2.0f); configure_stream("RC_CHANNELS", 1.0f); configure_stream("SERVO_OUTPUT_RAW_0", 1.0f); configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f); @@ -1660,6 +1661,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("GPS_RAW_INT", 5.0f); configure_stream("GLOBAL_POSITION_INT", 50.0f); configure_stream("LOCAL_POSITION_NED", 30.0f); + configure_stream("NAMED_VALUE_FLOAT", 10.0f); configure_stream("CAMERA_CAPTURE", 2.0f); configure_stream("HOME_POSITION", 0.5f); configure_stream("ATTITUDE_TARGET", 10.0f); @@ -1701,7 +1703,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("ATTITUDE_TARGET", 8.0f); configure_stream("PARAM_VALUE", 300.0f); configure_stream("MISSION_ITEM", 50.0f); - configure_stream("NAMED_VALUE_FLOAT", 10.0f); + configure_stream("NAMED_VALUE_FLOAT", 50.0f); configure_stream("OPTICAL_FLOW_RAD", 10.0f); configure_stream("DISTANCE_SENSOR", 10.0f); configure_stream("VFR_HUD", 20.0f);