GCS_MAVLink: move ADSB mavlink handling from vehicles to common library
This commit is contained in:
parent
a06a192255
commit
12192f60e3
@ -458,6 +458,8 @@ protected:
|
||||
void handle_obstacle_distance(const mavlink_message_t &msg);
|
||||
void handle_obstacle_distance_3d(const mavlink_message_t &msg);
|
||||
|
||||
void handle_adsb_message(const mavlink_message_t &msg);
|
||||
|
||||
void handle_osd_param_config(const mavlink_message_t &msg) const;
|
||||
|
||||
void handle_common_param_message(const mavlink_message_t &msg);
|
||||
|
@ -3359,6 +3359,16 @@ void GCS_MAVLINK::handle_obstacle_distance_3d(const mavlink_message_t &msg)
|
||||
#endif
|
||||
}
|
||||
|
||||
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
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::handle_osd_param_config(const mavlink_message_t &msg) const
|
||||
{
|
||||
#if OSD_PARAM_ENABLED
|
||||
@ -3581,6 +3591,13 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
|
||||
handle_osd_param_config(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_ADSB_VEHICLE:
|
||||
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG:
|
||||
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC:
|
||||
case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT:
|
||||
handle_adsb_message(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_LANDING_TARGET:
|
||||
handle_landing_target(msg);
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user