Browse Source

GCS_MAVLink: add route mask for blocking MAVlink forwading

master
proficnc 9 years ago committed by Andrew Tridgell
parent
commit
c8b3c527f9
  1. 7
      libraries/GCS_MAVLink/GCS.h
  2. 7
      libraries/GCS_MAVLink/MAVLink_routing.cpp
  3. 7
      libraries/GCS_MAVLink/MAVLink_routing.h

7
libraries/GCS_MAVLink/GCS.h

@ -185,7 +185,12 @@ public: @@ -185,7 +185,12 @@ public:
This is a no-op if no routes to components have been learned
*/
static void send_to_components(const mavlink_message_t* msg) { routing.send_to_components(msg); }
/*
allow forwarding of packets / heartbeats to be blocked as required by some components to reduce traffic
*/
static void disable_channel_routing(mavlink_channel_t chan) { routing.no_route_mask |= (1U<<(chan-MAVLINK_COMM_0)); }
/*
search for a component in the routing table with given mav_type and retrieve it's sysid, compid and channel
returns if a matching component is found

7
libraries/GCS_MAVLink/MAVLink_routing.cpp

@ -254,11 +254,14 @@ void MAVLink_routing::learn_route(mavlink_channel_t in_channel, const mavlink_me @@ -254,11 +254,14 @@ void MAVLink_routing::learn_route(mavlink_channel_t in_channel, const mavlink_me
void MAVLink_routing::handle_heartbeat(mavlink_channel_t in_channel, const mavlink_message_t* msg)
{
uint16_t mask = GCS_MAVLINK::active_channel_mask();
// don't send on the incoming channel. This should only matter if
// the routing table is full
mask &= ~(1U<<(in_channel-MAVLINK_COMM_0));
// mask out channels that do not want the heartbeat to be forwarded
mask &= ~no_route_mask;
// mask out channels that are known sources for this sysid/compid
for (uint8_t i=0; i<num_routes; i++) {
if (routes[i].sysid == msg->sysid && routes[i].compid == msg->compid) {

7
libraries/GCS_MAVLink/MAVLink_routing.h

@ -17,6 +17,8 @@ @@ -17,6 +17,8 @@
*/
class MAVLink_routing
{
friend class GCS_MAVLINK;
public:
MAVLink_routing(void);
@ -51,7 +53,10 @@ private: @@ -51,7 +53,10 @@ private:
mavlink_channel_t channel;
uint8_t mavtype;
} routes[MAVLINK_MAX_ROUTES];
// a channel mask to block routing as required
uint8_t no_route_mask;
// learn new routes
void learn_route(mavlink_channel_t in_channel, const mavlink_message_t* msg);

Loading…
Cancel
Save