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.
This commit is contained in:
Peter Barker 2024-12-16 10:36:27 +11:00 committed by Peter Barker
parent 6e49333a40
commit c5284c6fdf
2 changed files with 1 additions and 4 deletions

View File

@ -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,

View File

@ -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