mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: add method to get link (not just channel number) for mavtype and compid
This commit is contained in:
parent
a613ae8d1d
commit
3c8e89f540
@ -389,6 +389,9 @@ public:
|
|||||||
returns true if a match is found
|
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); }
|
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
|
// update signing timestamp on GPS lock
|
||||||
static void update_signing_timestamp(uint64_t timestamp_usec);
|
static void update_signing_timestamp(uint64_t timestamp_usec);
|
||||||
|
@ -48,6 +48,14 @@ mavlink_system_t mavlink_system = {7,1};
|
|||||||
// routing table
|
// routing table
|
||||||
MAVLink_routing GCS_MAVLINK::routing;
|
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
|
// set a channel as private. Private channels get sent heartbeats, but
|
||||||
// don't get broadcast packets or forwarded packets
|
// don't get broadcast packets or forwarded packets
|
||||||
void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan)
|
void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan)
|
||||||
|
Loading…
Reference in New Issue
Block a user