mirror of https://github.com/ArduPilot/ardupilot
ArduSub: split sending terrain report from terrain request
This commit is contained in:
parent
1470176ca1
commit
456f70d4d9
|
@ -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,
|
||||
|
|
Loading…
Reference in New Issue