mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: tidy ADSB message handling
This commit is contained in:
parent
c1f0c9e70a
commit
1f0ae343b1
|
@ -3811,15 +3811,15 @@ void GCS_MAVLINK::handle_obstacle_distance_3d(const mavlink_message_t &msg)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_ADSB_ENABLED
|
||||||
void GCS_MAVLINK::handle_adsb_message(const mavlink_message_t &msg)
|
void GCS_MAVLINK::handle_adsb_message(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
#if HAL_ADSB_ENABLED
|
|
||||||
AP_ADSB *adsb = AP::ADSB();
|
AP_ADSB *adsb = AP::ADSB();
|
||||||
if (adsb != nullptr) {
|
if (adsb != nullptr) {
|
||||||
adsb->handle_message(chan, msg);
|
adsb->handle_message(chan, msg);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void GCS_MAVLINK::handle_osd_param_config(const mavlink_message_t &msg) const
|
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);
|
handle_osd_param_config(msg);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#if HAL_ADSB_ENABLED
|
||||||
case MAVLINK_MSG_ID_ADSB_VEHICLE:
|
case MAVLINK_MSG_ID_ADSB_VEHICLE:
|
||||||
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG:
|
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG:
|
||||||
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC:
|
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:
|
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL:
|
||||||
handle_adsb_message(msg);
|
handle_adsb_message(msg);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_LANDING_TARGET:
|
case MAVLINK_MSG_ID_LANDING_TARGET:
|
||||||
handle_landing_target(msg);
|
handle_landing_target(msg);
|
||||||
|
|
Loading…
Reference in New Issue