GCS_MAVLink: tidy OSD param message handling

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

View File

@ -3821,15 +3821,15 @@ void GCS_MAVLINK::handle_adsb_message(const mavlink_message_t &msg)
}
#endif
#if OSD_PARAM_ENABLED
void GCS_MAVLINK::handle_osd_param_config(const mavlink_message_t &msg) const
{
#if OSD_PARAM_ENABLED
AP_OSD *osd = AP::osd();
if (osd != nullptr) {
osd->handle_msg(msg, *this);
}
#endif
}
#endif
void GCS_MAVLINK::handle_heartbeat(const mavlink_message_t &msg) const
{
@ -4084,10 +4084,12 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
handle_obstacle_distance_3d(msg);
break;
#if OSD_PARAM_ENABLED
case MAVLINK_MSG_ID_OSD_PARAM_CONFIG:
case MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG:
handle_osd_param_config(msg);
break;
#endif
#if HAL_ADSB_ENABLED
case MAVLINK_MSG_ID_ADSB_VEHICLE: