GCS_MAVLink: tidy ADSB message handling

This commit is contained in:
Peter Barker 2023-10-25 15:07:02 +11:00 committed by Peter Barker
parent c1f0c9e70a
commit 1f0ae343b1
1 changed files with 4 additions and 2 deletions

View File

@ -3811,15 +3811,15 @@ void GCS_MAVLINK::handle_obstacle_distance_3d(const mavlink_message_t &msg)
#endif
}
#if HAL_ADSB_ENABLED
void GCS_MAVLINK::handle_adsb_message(const mavlink_message_t &msg)
{
#if HAL_ADSB_ENABLED
AP_ADSB *adsb = AP::ADSB();
if (adsb != nullptr) {
adsb->handle_message(chan, msg);
}
#endif
}
#endif
void GCS_MAVLINK::handle_osd_param_config(const mavlink_message_t &msg) const
{
@ -4089,6 +4089,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
handle_osd_param_config(msg);
break;
#if HAL_ADSB_ENABLED
case MAVLINK_MSG_ID_ADSB_VEHICLE:
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG:
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC:
@ -4096,6 +4097,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL:
handle_adsb_message(msg);
break;
#endif
case MAVLINK_MSG_ID_LANDING_TARGET:
handle_landing_target(msg);