From 1eb9434b8c39fef3691684df520686231dce3939 Mon Sep 17 00:00:00 2001 From: Balduin Date: Fri, 17 Jan 2025 10:38:42 +0100 Subject: [PATCH] stream ATTITUDE_QUATERNION in low bandwidth mode --- 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 1c63f8adeeee..6e8184960030 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1744,6 +1744,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("CAMERA_TRIGGER", unlimited_rate); configure_stream_local("LOCAL_POSITION_NED", 30.0f); configure_stream_local("ATTITUDE", 20.0f); + configure_stream_local("ATTITUDE_QUATERNION", 20.0f); configure_stream_local("ALTITUDE", 10.0f); configure_stream_local("DISTANCE_SENSOR", 10.0f); configure_stream_local("MOUNT_ORIENTATION", 10.0f);