From bdcc626f296fc28c2fad752d1e0bad838765848d Mon Sep 17 00:00:00 2001 From: Kabir Mohammed Date: Fri, 16 Dec 2016 21:54:37 +0530 Subject: [PATCH] mavlink : correct stream name for vision message --- src/modules/mavlink/mavlink_main.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index d24f813f03..eda3dab57e 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1997,7 +1997,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("COLLISION", 2.0f); configure_stream("DISTANCE_SENSOR", 0.5f); configure_stream("OPTICAL_FLOW_RAD", 1.0f); - configure_stream("VISION_POSITION_NED", 1.0f); + configure_stream("VISION_POSITION_ESTIMATE", 1.0f); configure_stream("ESTIMATOR_STATUS", 0.5f); configure_stream("NAV_CONTROLLER_OUTPUT", 1.5f); configure_stream("GLOBAL_POSITION_INT", 5.0f); @@ -2024,7 +2024,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("COLLISION", 10.0f); configure_stream("DISTANCE_SENSOR", 10.0f); configure_stream("OPTICAL_FLOW_RAD", 10.0f); - configure_stream("VISION_POSITION_NED", 10.0f); + configure_stream("VISION_POSITION_ESTIMATE", 10.0f); configure_stream("ESTIMATOR_STATUS", 1.0f); configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f); configure_stream("GLOBAL_POSITION_INT", 50.0f); @@ -2081,7 +2081,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("COLLISION", 20.0f); configure_stream("DISTANCE_SENSOR", 10.0f); configure_stream("OPTICAL_FLOW_RAD", 10.0f); - configure_stream("VISION_POSITION_NED", 10.0f); + configure_stream("VISION_POSITION_ESTIMATE", 10.0f); configure_stream("ESTIMATOR_STATUS", 5.0f); configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f); configure_stream("GLOBAL_POSITION_INT", 10.0f);