GCS_MAVLink: add find_by_mavtype_and_compid

This commit is contained in:
olliw42 2022-09-07 17:18:53 +09:00 committed by Randy Mackay
parent b1909d9edf
commit c034f8a099
3 changed files with 28 additions and 0 deletions

View File

@ -383,6 +383,12 @@ public:
*/ */
static bool find_by_mavtype(uint8_t mav_type, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel) { return routing.find_by_mavtype(mav_type, sysid, compid, channel); } static bool find_by_mavtype(uint8_t mav_type, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel) { return routing.find_by_mavtype(mav_type, sysid, compid, channel); }
/*
search for the first vehicle or component in the routing table with given mav_type and component id and retrieve its sysid and channel
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); }
// update signing timestamp on GPS lock // update signing timestamp on GPS lock
static void update_signing_timestamp(uint64_t timestamp_usec); static void update_signing_timestamp(uint64_t timestamp_usec);

View File

@ -262,6 +262,22 @@ bool MAVLink_routing::find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &
return false; return false;
} }
/*
search for the first vehicle or component in the routing table with given mav_type and component id and retrieve its sysid and channel
returns true if a match is found
*/
bool MAVLink_routing::find_by_mavtype_and_compid(uint8_t mavtype, uint8_t compid, uint8_t &sysid, mavlink_channel_t &channel) const
{
for (uint8_t i=0; i<num_routes; i++) {
if ((routes[i].mavtype == mavtype) && (routes[i].compid == compid)) {
sysid = routes[i].sysid;
channel = routes[i].channel;
return true;
}
}
return false;
}
/* /*
see if the message is for a new route and learn it see if the message is for a new route and learn it
*/ */

View File

@ -43,6 +43,12 @@ public:
*/ */
bool find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel); bool find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel);
/*
search for the first vehicle or component in the routing table with given mav_type and component id and retrieve its sysid and channel
returns true if a match is found
*/
bool find_by_mavtype_and_compid(uint8_t mavtype, uint8_t compid, uint8_t &sysid, mavlink_channel_t &channel) const;
private: private:
// a simple linear routing table. We don't expect to have a lot of // a simple linear routing table. We don't expect to have a lot of
// routes, so a scalable structure isn't worthwhile yet. // routes, so a scalable structure isn't worthwhile yet.