From c5284c6fdf0e154c7d264f073438c1440ad50789 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 16 Dec 2024 10:36:27 +1100 Subject: [PATCH] Rover: allow WATER_DEPTH mavlink message rate to be specified ... and reduce the default rate this is currently unconditionally streamed at 50Hz, chewing up all available bandwidth on some telemetry radios. --- Rover/GCS_Mavlink.cpp | 1 + Rover/Log.cpp | 4 ---- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index a903e591c6..eaa26eee7d 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -589,6 +589,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_WIND, #if AP_RANGEFINDER_ENABLED MSG_RANGEFINDER, + MSG_WATER_DEPTH, #endif MSG_DISTANCE_SENSOR, MSG_SYSTEM_TIME, diff --git a/Rover/Log.cpp b/Rover/Log.cpp index f13ad700ad..e474cda125 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -79,10 +79,6 @@ void Rover::Log_Write_Depth() (double)(s->distance()), temp_C); } -#if AP_RANGEFINDER_ENABLED - // send water depth and temp to ground station - gcs().send_message(MSG_WATER_DEPTH); -#endif } #endif