From 02fe211e4c9ae86a7bcea019daa03309509fbd71 Mon Sep 17 00:00:00 2001 From: Martina Rivizzigno Date: Wed, 20 Sep 2023 08:43:30 +0200 Subject: [PATCH] mavlink mode NORMAL: increase GPS_RAW_INT rate to 5Hz --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index f7ee306dd1..c9e3853d47 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1507,7 +1507,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("GLOBAL_POSITION_INT", 5.0f); configure_stream_local("GPS2_RAW", 1.0f); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); - configure_stream_local("GPS_RAW_INT", 1.0f); + configure_stream_local("GPS_RAW_INT", 5.0f); configure_stream_local("GPS_STATUS", 1.0f); configure_stream_local("HOME_POSITION", 0.5f); configure_stream_local("HYGROMETER_SENSOR", 0.1f);