27 #define ROUTING_DEBUG 0 103 if (msg->msgid == MAVLINK_MSG_ID_RADIO ||
104 msg->msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
109 if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
115 if (msg->msgid == MAVLINK_MSG_ID_ADSB_VEHICLE) {
121 int16_t target_system = -1;
122 int16_t target_component = -1;
125 bool broadcast_system = (target_system == 0 || target_system == -1);
126 bool broadcast_component = (target_component == 0 || target_component == -1);
127 bool match_system = broadcast_system || (target_system ==
mavlink_system.sysid);
128 bool match_component = match_system && (broadcast_component ||
130 bool process_locally = match_system && match_component;
132 if (process_locally && !broadcast_system && !broadcast_component) {
138 bool forwarded =
false;
140 memset(sent_to_chan, 0,
sizeof(sent_to_chan));
142 if (broadcast_system || (target_system ==
routes[i].sysid &&
143 (broadcast_component ||
144 target_component ==
routes[i].compid ||
146 if (in_channel !=
routes[i].channel && !sent_to_chan[
routes[i].channel]) {
150 ::printf(
"fwd msg %u from chan %u on chan %u sysid=%d compid=%d\n",
152 (
unsigned)in_channel,
155 (
int)target_component);
157 _mavlink_resend_uart(
routes[i].channel, msg);
164 if (!forwarded && match_system) {
165 process_locally =
true;
168 return process_locally;
179 memset(sent_to_chan, 0,
sizeof(sent_to_chan));
187 ::printf(
"send msg %u on chan %u sysid=%u compid=%u\n",
193 _mavlink_resend_uart(
routes[i].channel, msg);
208 if (
routes[i].mavtype == mavtype) {
226 if (msg->sysid == 0 ||
235 if (
routes[i].mavtype == 0 && msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
245 if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
250 ::printf(
"learned route %u %u via %u\n",
251 (
unsigned)msg->sysid,
252 (
unsigned)msg->compid,
253 (
unsigned)in_channel);
270 mask &= ~(1U<<(in_channel-MAVLINK_COMM_0));
278 mask &= ~(1U<<((unsigned)(
routes[i].channel-MAVLINK_COMM_0)));
289 if (mask & (1U<<i)) {
290 mavlink_channel_t channel = (mavlink_channel_t)(MAVLINK_COMM_0 + i);
294 ::printf(
"fwd HB from chan %u on chan %u from sysid=%u compid=%u\n",
295 (
unsigned)in_channel,
297 (
unsigned)msg->sysid,
298 (
unsigned)msg->compid);
300 _mavlink_resend_uart(channel, msg);
314 const mavlink_msg_entry_t *msg_entry = mavlink_get_msg_entry(msg->msgid);
315 if (msg_entry ==
nullptr) {
318 if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM) {
319 sysid = _MAV_RETURN_uint8_t(msg, msg_entry->target_system_ofs);
321 if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT) {
322 compid = _MAV_RETURN_uint8_t(msg, msg_entry->target_component_ofs);
int printf(const char *fmt,...)
void send_to_components(const mavlink_message_t *msg)
Interface definition for the various Ground Control System.
static int comm_get_txspace(mavlink_channel_t chan)
static uint8_t packet_overhead_chan(mavlink_channel_t chan)
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)
static uint8_t active_channel_mask(void)
mavlink_channel_t channel
bool check_and_forward(mavlink_channel_t in_channel, const mavlink_message_t *msg)
mavlink_system_t mavlink_system
MAVLink system definition.
struct MAVLink_routing::route routes[MAVLINK_MAX_ROUTES]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
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)
handle routing of MAVLink packets by sysid/componentid
bool find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel)
#define MAVLINK_COMM_NUM_BUFFERS