GCS_MAVLink: add method to get link (not just channel number) for mavtype and compid

This commit is contained in:
Peter Barker 2023-02-23 16:06:48 +11:00 committed by Randy Mackay
parent d1acebe415
commit 6cc4afaa56
2 changed files with 11 additions and 0 deletions

View File

@ -389,6 +389,9 @@ public:
returns true if a match is found
*/
static bool find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid, mavlink_channel_t &channel) { return routing.find_by_mavtype_and_compid(mav_type, compid, sysid, channel); }
// same as above, but returns a pointer to the GCS_MAVLINK object
// corresponding to the channel
static GCS_MAVLINK *find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid);
// update signing timestamp on GPS lock
static void update_signing_timestamp(uint64_t timestamp_usec);

View File

@ -48,6 +48,14 @@ mavlink_system_t mavlink_system = {7,1};
// routing table
MAVLink_routing GCS_MAVLINK::routing;
GCS_MAVLINK *GCS_MAVLINK::find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid) {
mavlink_channel_t channel;
if (!routing.find_by_mavtype_and_compid(mav_type, compid, sysid, channel)) {
return nullptr;
}
return gcs().chan(channel);
}
// 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)