ArduSub: split sending terrain report from terrain request

This commit is contained in:
Peter Barker 2024-09-27 11:01:25 +10:00 committed by Andrew Tridgell
parent 1470176ca1
commit 456f70d4d9
1 changed files with 8 additions and 3 deletions

View File

@ -248,12 +248,16 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
send_info(); send_info();
break; break;
case MSG_TERRAIN:
#if AP_TERRAIN_AVAILABLE #if AP_TERRAIN_AVAILABLE
case MSG_TERRAIN_REQUEST:
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
sub.terrain.send_request(chan); sub.terrain.send_request(chan);
#endif
break; break;
case MSG_TERRAIN_REPORT:
CHECK_PAYLOAD_SIZE(TERRAIN_REPORT);
sub.terrain.send_report(chan);
break;
#endif
default: default:
return GCS_MAVLINK::try_send_message(id); return GCS_MAVLINK::try_send_message(id);
@ -407,7 +411,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
#endif #endif
MSG_DISTANCE_SENSOR, MSG_DISTANCE_SENSOR,
#if AP_TERRAIN_AVAILABLE #if AP_TERRAIN_AVAILABLE
MSG_TERRAIN, MSG_TERRAIN_REQUEST,
MSG_TERRAIN_REPORT,
#endif #endif
#if AP_BATTERY_ENABLED #if AP_BATTERY_ENABLED
MSG_BATTERY_STATUS, MSG_BATTERY_STATUS,