From d8d2213cabd8636aeb8f86471b6c35914e7a1a97 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 1 Dec 2023 14:00:43 +0100 Subject: [PATCH] mavlink streams: add SYSTEM_TIME to onboard low bandwidth It's required with 2Hz by some MAVLink enabled payloads. --- src/modules/mavlink/mavlink_main.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 138effc5ca..c730dd0f47 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1756,6 +1756,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("RC_CHANNELS", 20.0f); configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f); configure_stream_local("SYS_STATUS", 5.0f); + configure_stream_local("SYSTEM_TIME", 2.0f); configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f); configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f); configure_stream_local("UTM_GLOBAL_POSITION", 1.0f);