From a8b342722e6a1cdc092eaf5b7e2c7fcfe6d8b1e9 Mon Sep 17 00:00:00 2001 From: marcirsch Date: Wed, 10 Aug 2022 08:00:21 +0200 Subject: [PATCH] mavlink_main: Add TIME_ESTIMATE_TO_TARGET stream to config, onboard, and onboard_low_bandwidth modes Signed-off-by: marcirsch --- src/modules/mavlink/mavlink_main.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e68249edd7..e1eb29e366 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1585,6 +1585,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("SERVO_OUTPUT_RAW_0", 10.0f); configure_stream_local("SYS_STATUS", 5.0f); configure_stream_local("SYSTEM_TIME", 1.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); configure_stream_local("VFR_HUD", 10.0f); @@ -1738,6 +1739,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("SERVO_OUTPUT_RAW_1", 20.0f); configure_stream_local("SYS_STATUS", 1.0f); configure_stream_local("SYSTEM_TIME", 1.0f); + configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f); configure_stream_local("UTM_GLOBAL_POSITION", 1.0f); configure_stream_local("VFR_HUD", 20.0f); configure_stream_local("VIBRATION", 2.5f); @@ -1811,6 +1813,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("RC_CHANNELS", 5.0f); configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f); configure_stream_local("SYS_STATUS", 5.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); configure_stream_local("VFR_HUD", 4.0f);