Skip to content

Commit

Permalink
ArduSub: split sending terrain report from terrain request
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Sep 27, 2024
1 parent 3f3d441 commit 3570ce3
Showing 1 changed file with 6 additions and 2 deletions.
8 changes: 6 additions & 2 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
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);
Expand Down

0 comments on commit 3570ce3

Please sign in to comment.