11 #define MAVLINK_MAX_ROUTES 20 30 bool check_and_forward(mavlink_channel_t in_channel,
const mavlink_message_t* msg);
42 bool find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel);
59 void learn_route(mavlink_channel_t in_channel,
const mavlink_message_t* msg);
65 void handle_heartbeat(mavlink_channel_t in_channel,
const mavlink_message_t* msg);
void send_to_components(const mavlink_message_t *msg)
MAVLink transport control class.
void handle_heartbeat(mavlink_channel_t in_channel, const mavlink_message_t *msg)
void learn_route(mavlink_channel_t in_channel, const mavlink_message_t *msg)
mavlink_channel_t channel
bool check_and_forward(mavlink_channel_t in_channel, const mavlink_message_t *msg)
struct MAVLink_routing::route routes[MAVLINK_MAX_ROUTES]
Common definitions and utility routines for the ArduPilot libraries.
#define MAVLINK_MAX_ROUTES
void get_targets(const mavlink_message_t *msg, int16_t &sysid, int16_t &compid)
bool find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel)