mavlink_main: Add TIME_ESTIMATE_TO_TARGET stream to config, onboard, and onboard_low_bandwidth modes

Signed-off-by: marcirsch <marcell@auterion.com>
This commit is contained in:
marcirsch
2022-08-10 08:00:21 +02:00
committed by Beat Küng
parent 4bf6ebf4c3
commit a8b342722e
+3
View File
@@ -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);