GCS_MAVLink: only try to fwd packets to active channels

This commit is contained in:
Andrew Tridgell 2014-12-10 14:30:42 +11:00 committed by Randy Mackay
parent 411766f45a
commit 34be7f808e

View File

@ -20,6 +20,7 @@
#include <AP_HAL.h>
#include <AP_Common.h>
#include <GCS.h>
#include <MAVLink_routing.h>
#include <stdio.h>
@ -119,7 +120,7 @@ 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 = (1U<<MAVLINK_COMM_NUM_BUFFERS)-1;
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