From 456f70d4d9c7aae3e112ab23760378eb95ff27ef Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Sep 2024 11:01:25 +1000 Subject: [PATCH] ArduSub: split sending terrain report from terrain request --- ArduSub/GCS_Mavlink.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index fc2b5c0227..66411bb577 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -248,12 +248,16 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) send_info(); break; - case MSG_TERRAIN: #if AP_TERRAIN_AVAILABLE + case MSG_TERRAIN_REQUEST: CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); sub.terrain.send_request(chan); -#endif break; + case MSG_TERRAIN_REPORT: + CHECK_PAYLOAD_SIZE(TERRAIN_REPORT); + sub.terrain.send_report(chan); + break; +#endif default: return GCS_MAVLINK::try_send_message(id); @@ -407,7 +411,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif MSG_DISTANCE_SENSOR, #if AP_TERRAIN_AVAILABLE - MSG_TERRAIN, + MSG_TERRAIN_REQUEST, + MSG_TERRAIN_REPORT, #endif #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS,