GCS_MAVLink: make mavlink-required methods available even if not HAL_GCS_ENABLED

This commit is contained in:
Peter Barker 2024-01-18 15:37:06 +11:00 committed by Andrew Tridgell
parent e8708227a1
commit cac3a2216d
1 changed files with 24 additions and 16 deletions

View File

@ -41,6 +41,30 @@ extern const AP_HAL::HAL& hal;
#pragma GCC diagnostic pop
#endif
mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) {
#if HAL_GCS_ENABLED
GCS_MAVLINK *link = gcs().chan(chan);
if (link == nullptr) {
return nullptr;
}
return link->channel_buffer();
#else
return nullptr;
#endif
}
mavlink_status_t* mavlink_get_channel_status(uint8_t chan) {
#if HAL_GCS_ENABLED
GCS_MAVLINK *link = gcs().chan(chan);
if (link == nullptr) {
return nullptr;
}
return link->channel_status();
#else
return nullptr;
#endif
}
#endif // HAL_MAVLINK_BINDINGS_ENABLED
#if HAL_GCS_ENABLED
@ -65,22 +89,6 @@ GCS_MAVLINK *GCS_MAVLINK::find_by_mavtype_and_compid(uint8_t mav_type, uint8_t c
return gcs().chan(channel);
}
mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) {
GCS_MAVLINK *link = gcs().chan(chan);
if (link == nullptr) {
return nullptr;
}
return link->channel_buffer();
}
mavlink_status_t* mavlink_get_channel_status(uint8_t chan) {
GCS_MAVLINK *link = gcs().chan(chan);
if (link == nullptr) {
return nullptr;
}
return link->channel_status();
}
// set a channel as private. Private channels get sent heartbeats, but
// don't get broadcast packets or forwarded packets
void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan)