AP_OSD: move from HAL_NO_GCS to HAL_GCS_ENABLED

This commit is contained in:
Peter Barker 2021-09-17 23:37:20 +10:00 committed by Peter Barker
parent dac4134533
commit 6ce79785b5
3 changed files with 9 additions and 0 deletions

View File

@ -534,6 +534,7 @@ void AP_OSD::set_nav_info(NavInfo &navinfo)
#endif // OSD_ENABLED
// handle OSD parameter configuration
#if HAL_GCS_ENABLED
void AP_OSD::handle_msg(const mavlink_message_t &msg, const GCS_MAVLINK& link)
{
bool found = false;
@ -578,6 +579,7 @@ void AP_OSD::handle_msg(const mavlink_message_t &msg, const GCS_MAVLINK& link)
break;
}
}
#endif
AP_OSD *AP::osd() {
return AP_OSD::get_singleton();

View File

@ -371,8 +371,10 @@ public:
#if HAL_WITH_OSD_BITMAP || HAL_WITH_MSP_DISPLAYPORT
void draw(void) override;
#endif
#if HAL_GCS_ENABLED
void handle_write_msg(const mavlink_osd_param_config_t& packet, const GCS_MAVLINK& link);
void handle_read_msg(const mavlink_osd_param_show_config_t& packet, const GCS_MAVLINK& link);
#endif
// get a setting and associated metadata
AP_OSD_ParamSetting* get_setting(uint8_t param_idx);
// Save button co-ordinates
@ -555,7 +557,10 @@ public:
}
#endif
// handle OSD parameter configuration
#if HAL_GCS_ENABLED
void handle_msg(const mavlink_message_t &msg, const GCS_MAVLINK& link);
#endif
// allow threads to lock against OSD update
HAL_Semaphore &get_semaphore(void) {
return _sem;

View File

@ -628,6 +628,7 @@ void AP_OSD_ParamScreen::save_parameters()
}
// handle OSD configuration messages
#if HAL_GCS_ENABLED
void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& packet, const GCS_MAVLINK& link)
{
// request out of range - return an error
@ -666,5 +667,6 @@ void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t&
mavlink_msg_osd_param_show_config_reply_send(link.get_chan(), packet.request_id, OSD_PARAM_SUCCESS,
buf, param._type, param._param_min, param._param_max, param._param_incr);
}
#endif
#endif // OSD_PARAM_ENABLED