2014-12-09 23:00:53 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/// @file MAVLink_routing.h
|
|
|
|
/// @brief handle routing of MAVLink packets by sysid/componentid
|
|
|
|
|
2023-09-02 02:21:36 -03:00
|
|
|
#include "GCS_config.h"
|
|
|
|
|
|
|
|
#if HAL_GCS_ENABLED
|
|
|
|
|
2014-12-11 03:26:26 -04:00
|
|
|
#include <stdio.h>
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include "GCS.h"
|
|
|
|
#include "MAVLink_routing.h"
|
2014-12-09 23:00:53 -04:00
|
|
|
|
2024-03-04 12:11:30 -04:00
|
|
|
#include <AP_ADSB/AP_ADSB.h>
|
|
|
|
|
2014-12-09 23:00:53 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
#define ROUTING_DEBUG 0
|
|
|
|
|
|
|
|
// constructor
|
|
|
|
MAVLink_routing::MAVLink_routing(void) : num_routes(0) {}
|
|
|
|
|
|
|
|
/*
|
|
|
|
forward a MAVLink message to the right port. This also
|
|
|
|
automatically learns the route for the sender if it is not
|
|
|
|
already known.
|
|
|
|
|
2014-12-16 19:30:09 -04:00
|
|
|
This returns true if the message should be processed locally
|
2014-12-16 03:40:39 -04:00
|
|
|
|
2014-12-16 19:30:09 -04:00
|
|
|
Theory of MAVLink routing:
|
2014-12-16 03:40:39 -04:00
|
|
|
|
|
|
|
When a flight controller receives a message it should process it
|
|
|
|
locally if any of these conditions hold:
|
|
|
|
|
|
|
|
1a) the message has no target_system field
|
|
|
|
|
|
|
|
1b) the message has a target_system of zero
|
|
|
|
|
|
|
|
1c) the message has the flight controllers target system and has no
|
|
|
|
target_component field
|
|
|
|
|
|
|
|
1d) the message has the flight controllers target system and has
|
|
|
|
the flight controllers target_component
|
|
|
|
|
|
|
|
1e) the message has the flight controllers target system and the
|
|
|
|
flight controller has not seen any messages on any of its links
|
|
|
|
from a system that has the messages
|
|
|
|
target_system/target_component combination
|
|
|
|
|
|
|
|
When a flight controller receives a message it should forward it
|
|
|
|
onto another different link if any of these conditions hold for that
|
|
|
|
link:
|
|
|
|
|
|
|
|
2a) the message has no target_system field
|
|
|
|
|
|
|
|
2b) the message has a target_system of zero
|
|
|
|
|
|
|
|
2c) the message does not have the flight controllers target_system
|
|
|
|
and the flight controller has seen a message from the messages
|
|
|
|
target_system on the link
|
|
|
|
|
|
|
|
2d) the message has the flight controllers target_system and has a
|
|
|
|
target_component field and the flight controllers has seen a
|
|
|
|
message from the target_system/target_component combination on
|
|
|
|
the link
|
|
|
|
|
|
|
|
Note: This proposal assumes that ground stations will not send command
|
|
|
|
packets to a non-broadcast destination (sysid/compid combination)
|
|
|
|
until they have received at least one package from that destination
|
|
|
|
over the link. This is essential to prevent a flight controller from
|
|
|
|
acting on a message that is not meant for it. For example, a PARAM_SET
|
|
|
|
cannot be sent to a specific sysid/compid combination until the GCS
|
|
|
|
has seen a packet from that sysid/compid combination on the link.
|
|
|
|
|
|
|
|
The GCS must also reset what sysid/compid combinations it has seen on
|
|
|
|
a link when it sees a SYSTEM_TIME message with a decrease in
|
|
|
|
time_boot_ms from a particular sysid/compid. That is essential to
|
|
|
|
detect a reset of the flight controller, which implies a reset of its
|
|
|
|
routing table.
|
|
|
|
|
2014-12-09 23:00:53 -04:00
|
|
|
*/
|
2023-03-05 19:44:55 -04:00
|
|
|
bool MAVLink_routing::check_and_forward(GCS_MAVLINK &in_link, const mavlink_message_t &msg)
|
2014-12-09 23:00:53 -04:00
|
|
|
{
|
2023-05-23 05:11:13 -03:00
|
|
|
#if HAL_SOLO_GIMBAL_ENABLED
|
|
|
|
// check if a Gopro is connected. If yes, we allow the routing
|
|
|
|
// of mavlink messages to a private channel (Solo Gimbal case)
|
|
|
|
if (!gopro_status_check && (msg.msgid == MAVLINK_MSG_ID_GOPRO_HEARTBEAT)) {
|
|
|
|
gopro_status_check = true;
|
2024-08-07 00:17:22 -03:00
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "GoPro in Solo gimbal detected");
|
2023-05-23 05:11:13 -03:00
|
|
|
}
|
|
|
|
#endif // HAL_SOLO_GIMBAL_ENABLED
|
|
|
|
|
2015-02-25 23:58:42 -04:00
|
|
|
// handle the case of loopback of our own messages, due to
|
|
|
|
// incorrect serial configuration.
|
2019-07-11 05:31:45 -03:00
|
|
|
if (msg.sysid == mavlink_system.sysid &&
|
|
|
|
msg.compid == mavlink_system.compid) {
|
2023-03-16 23:20:34 -03:00
|
|
|
return false;
|
2015-02-25 23:58:42 -04:00
|
|
|
}
|
|
|
|
|
2022-06-03 03:17:48 -03:00
|
|
|
// learn new routes including private channels
|
|
|
|
// so that find_mav_type works for all channels
|
2023-03-05 19:44:55 -04:00
|
|
|
learn_route(in_link, msg);
|
2022-06-03 03:17:48 -03:00
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
if (msg.msgid == MAVLINK_MSG_ID_RADIO ||
|
|
|
|
msg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
|
2016-05-31 09:13:05 -03:00
|
|
|
// don't forward RADIO packets
|
|
|
|
return true;
|
|
|
|
}
|
2022-11-16 08:46:13 -04:00
|
|
|
|
2023-03-05 19:44:55 -04:00
|
|
|
const bool from_private_channel = in_link.is_private();
|
2022-11-16 08:46:13 -04:00
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
if (msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
|
2014-12-09 23:00:53 -04:00
|
|
|
// heartbeat needs special handling
|
2022-11-16 08:46:13 -04:00
|
|
|
if (!from_private_channel) {
|
2023-03-05 19:44:55 -04:00
|
|
|
handle_heartbeat(in_link, msg);
|
2022-11-16 08:46:13 -04:00
|
|
|
}
|
2014-12-16 19:30:09 -04:00
|
|
|
return true;
|
2014-12-09 23:00:53 -04:00
|
|
|
}
|
|
|
|
|
2024-03-04 12:11:30 -04:00
|
|
|
#if HAL_ADSB_ENABLED
|
2019-07-11 05:31:45 -03:00
|
|
|
if (msg.msgid == MAVLINK_MSG_ID_ADSB_VEHICLE) {
|
2024-03-04 12:11:30 -04:00
|
|
|
// if enabled ADSB packets are not forwarded, they have their own stream rate
|
|
|
|
const AP_ADSB *adsb = AP::ADSB();
|
|
|
|
if ((adsb != nullptr) && (adsb->enabled())) {
|
|
|
|
return true;
|
|
|
|
}
|
2016-06-15 17:54:07 -03:00
|
|
|
}
|
2024-03-04 12:11:30 -04:00
|
|
|
#endif
|
2016-06-15 17:54:07 -03:00
|
|
|
|
2014-12-09 23:00:53 -04:00
|
|
|
// extract the targets for this packet
|
2014-12-10 03:25:47 -04:00
|
|
|
int16_t target_system = -1;
|
|
|
|
int16_t target_component = -1;
|
2014-12-09 23:00:53 -04:00
|
|
|
get_targets(msg, target_system, target_component);
|
|
|
|
|
2014-12-16 03:40:39 -04:00
|
|
|
bool broadcast_system = (target_system == 0 || target_system == -1);
|
|
|
|
bool broadcast_component = (target_component == 0 || target_component == -1);
|
|
|
|
bool match_system = broadcast_system || (target_system == mavlink_system.sysid);
|
|
|
|
bool match_component = match_system && (broadcast_component ||
|
|
|
|
(target_component == mavlink_system.compid));
|
|
|
|
bool process_locally = match_system && match_component;
|
2014-12-10 03:25:47 -04:00
|
|
|
|
2022-11-16 08:46:13 -04:00
|
|
|
// don't ever forward data from a private channel
|
2023-05-23 05:11:13 -03:00
|
|
|
// unless a Gopro camera is connected to a Solo gimbal
|
|
|
|
bool should_process_locally = from_private_channel;
|
|
|
|
#if HAL_SOLO_GIMBAL_ENABLED
|
|
|
|
if (gopro_status_check) {
|
|
|
|
should_process_locally = false;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
if (should_process_locally) {
|
2022-11-16 08:46:13 -04:00
|
|
|
return process_locally;
|
|
|
|
}
|
|
|
|
|
2014-12-16 03:40:39 -04:00
|
|
|
if (process_locally && !broadcast_system && !broadcast_component) {
|
|
|
|
// nothing more to do - it can only be for us
|
2014-12-16 19:30:09 -04:00
|
|
|
return true;
|
2014-12-09 23:00:53 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// forward on any channels matching the targets
|
2014-12-16 03:40:39 -04:00
|
|
|
bool forwarded = false;
|
2015-07-21 08:49:20 -03:00
|
|
|
bool sent_to_chan[MAVLINK_COMM_NUM_BUFFERS];
|
|
|
|
memset(sent_to_chan, 0, sizeof(sent_to_chan));
|
2014-12-09 23:00:53 -04:00
|
|
|
for (uint8_t i=0; i<num_routes; i++) {
|
2018-11-26 21:55:29 -04:00
|
|
|
|
2020-08-23 00:20:27 -03:00
|
|
|
// Skip if channel is private and the target system or component IDs do not match
|
2023-03-05 19:44:55 -04:00
|
|
|
GCS_MAVLINK *out_link = gcs().chan(routes[i].channel);
|
|
|
|
if (out_link == nullptr) {
|
|
|
|
// this is bad
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if (out_link->is_private() &&
|
2020-08-23 00:20:27 -03:00
|
|
|
(target_system != routes[i].sysid ||
|
|
|
|
target_component != routes[i].compid)) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
2014-12-16 03:40:39 -04:00
|
|
|
if (broadcast_system || (target_system == routes[i].sysid &&
|
|
|
|
(broadcast_component ||
|
2015-11-12 22:37:20 -04:00
|
|
|
target_component == routes[i].compid ||
|
|
|
|
!match_system))) {
|
2018-11-26 21:55:29 -04:00
|
|
|
|
2023-03-05 19:44:55 -04:00
|
|
|
if (&in_link != out_link && !sent_to_chan[routes[i].channel]) {
|
|
|
|
if (out_link->check_payload_size(msg.len)) {
|
2014-12-09 23:00:53 -04:00
|
|
|
#if ROUTING_DEBUG
|
2015-07-21 08:50:22 -03:00
|
|
|
::printf("fwd msg %u from chan %u on chan %u sysid=%d compid=%d\n",
|
2019-07-11 05:31:45 -03:00
|
|
|
msg.msgid,
|
2024-07-07 12:47:00 -03:00
|
|
|
(unsigned)in_link.get_chan(),
|
2014-12-16 03:40:39 -04:00
|
|
|
(unsigned)routes[i].channel,
|
2015-07-21 08:50:22 -03:00
|
|
|
(int)target_system,
|
|
|
|
(int)target_component);
|
2014-12-09 23:00:53 -04:00
|
|
|
#endif
|
2019-07-11 05:31:45 -03:00
|
|
|
_mavlink_resend_uart(routes[i].channel, &msg);
|
2014-12-16 03:40:39 -04:00
|
|
|
}
|
2015-07-21 08:49:20 -03:00
|
|
|
sent_to_chan[routes[i].channel] = true;
|
2014-12-16 03:40:39 -04:00
|
|
|
forwarded = true;
|
2014-12-09 23:00:53 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2018-11-26 21:55:29 -04:00
|
|
|
|
2020-10-09 03:54:44 -03:00
|
|
|
if ((!forwarded && match_system) ||
|
|
|
|
broadcast_system) {
|
2014-12-16 03:40:39 -04:00
|
|
|
process_locally = true;
|
|
|
|
}
|
2014-12-09 23:00:53 -04:00
|
|
|
|
2014-12-16 19:30:09 -04:00
|
|
|
return process_locally;
|
2014-12-09 23:00:53 -04:00
|
|
|
}
|
|
|
|
|
2015-03-28 22:36:06 -03:00
|
|
|
/*
|
|
|
|
send a MAVLink message to all components with this vehicle's system id
|
|
|
|
|
|
|
|
This is a no-op if no routes to components have been learned
|
|
|
|
*/
|
2019-10-17 04:07:23 -03:00
|
|
|
void MAVLink_routing::send_to_components(uint32_t msgid, const char *pkt, uint8_t pkt_len)
|
2015-03-28 22:36:06 -03:00
|
|
|
{
|
2019-10-17 04:07:23 -03:00
|
|
|
const mavlink_msg_entry_t *entry = mavlink_get_msg_entry(msgid);
|
|
|
|
if (entry == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
send_to_components(pkt, entry, pkt_len);
|
|
|
|
}
|
|
|
|
|
|
|
|
void MAVLink_routing::send_to_components(const char *pkt, const mavlink_msg_entry_t *entry, const uint8_t pkt_len)
|
|
|
|
{
|
|
|
|
bool sent_to_chan[MAVLINK_COMM_NUM_BUFFERS] {};
|
2015-03-28 22:36:06 -03:00
|
|
|
|
|
|
|
// check learned routes
|
|
|
|
for (uint8_t i=0; i<num_routes; i++) {
|
2019-10-17 04:07:23 -03:00
|
|
|
if (routes[i].sysid != mavlink_system.sysid) {
|
|
|
|
// our system ID hasn't been seen on this link
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if (sent_to_chan[routes[i].channel]) {
|
|
|
|
// we've already send it on this link
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if (comm_get_txspace(routes[i].channel) <
|
|
|
|
((uint16_t)entry->max_msg_len) + GCS_MAVLINK::packet_overhead_chan(routes[i].channel)) {
|
|
|
|
// it doesn't fit on this channel
|
|
|
|
continue;
|
|
|
|
}
|
2015-03-28 22:36:06 -03:00
|
|
|
#if ROUTING_DEBUG
|
2019-10-17 04:07:23 -03:00
|
|
|
::printf("send msg %u on chan %u sysid=%u compid=%u\n",
|
2019-12-19 05:47:21 -04:00
|
|
|
entry->msgid,
|
2019-10-17 04:07:23 -03:00
|
|
|
(unsigned)routes[i].channel,
|
|
|
|
(unsigned)routes[i].sysid,
|
|
|
|
(unsigned)routes[i].compid);
|
2015-03-28 22:36:06 -03:00
|
|
|
#endif
|
2019-10-17 04:07:23 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
if (entry->max_msg_len > pkt_len) {
|
|
|
|
AP_HAL::panic("Passed packet message length (%u > %u)",
|
|
|
|
entry->max_msg_len, pkt_len);
|
2015-03-28 22:36:06 -03:00
|
|
|
}
|
2019-10-17 04:07:23 -03:00
|
|
|
#endif
|
|
|
|
_mav_finalize_message_chan_send(routes[i].channel,
|
|
|
|
entry->msgid,
|
|
|
|
pkt,
|
|
|
|
entry->min_msg_len,
|
|
|
|
MIN(entry->max_msg_len, pkt_len),
|
|
|
|
entry->crc_extra);
|
|
|
|
sent_to_chan[routes[i].channel] = true;
|
2015-03-28 22:36:06 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-07-24 08:52:06 -03:00
|
|
|
/*
|
|
|
|
search for the first vehicle or component in the routing table with given mav_type and retrieve it's sysid, compid and channel
|
|
|
|
returns true if a match is found
|
|
|
|
*/
|
|
|
|
bool MAVLink_routing::find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel)
|
|
|
|
{
|
|
|
|
// check learned routes
|
|
|
|
for (uint8_t i=0; i<num_routes; i++) {
|
|
|
|
if (routes[i].mavtype == mavtype) {
|
|
|
|
sysid = routes[i].sysid;
|
|
|
|
compid = routes[i].compid;
|
|
|
|
channel = routes[i].channel;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// if we've reached we have not found the component
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2022-09-07 05:18:53 -03:00
|
|
|
/*
|
|
|
|
search for the first vehicle or component in the routing table with given mav_type and component id and retrieve its sysid and channel
|
|
|
|
returns true if a match is found
|
|
|
|
*/
|
|
|
|
bool MAVLink_routing::find_by_mavtype_and_compid(uint8_t mavtype, uint8_t compid, uint8_t &sysid, mavlink_channel_t &channel) const
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<num_routes; i++) {
|
|
|
|
if ((routes[i].mavtype == mavtype) && (routes[i].compid == compid)) {
|
|
|
|
sysid = routes[i].sysid;
|
|
|
|
channel = routes[i].channel;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2014-12-09 23:00:53 -04:00
|
|
|
/*
|
|
|
|
see if the message is for a new route and learn it
|
|
|
|
*/
|
2023-03-05 19:44:55 -04:00
|
|
|
void MAVLink_routing::learn_route(GCS_MAVLINK &in_link, const mavlink_message_t &msg)
|
2014-12-09 23:00:53 -04:00
|
|
|
{
|
|
|
|
uint8_t i;
|
2020-06-16 23:09:30 -03:00
|
|
|
if (msg.sysid == 0) {
|
|
|
|
// don't learn routes to the broadcast system
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (msg.sysid == mavlink_system.sysid &&
|
|
|
|
msg.compid == mavlink_system.compid) {
|
|
|
|
// don't learn routes to ourself. We know where we are.
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (msg.sysid == mavlink_system.sysid &&
|
|
|
|
msg.compid == MAV_COMP_ID_ALL) {
|
|
|
|
// don't learn routes to the broadcast component ID for our
|
|
|
|
// own system id. We should still broadcast these, but we
|
|
|
|
// should also process them locally.
|
2014-12-16 19:30:09 -04:00
|
|
|
return;
|
|
|
|
}
|
2023-03-05 19:44:55 -04:00
|
|
|
const mavlink_channel_t in_channel = in_link.get_chan();
|
2014-12-09 23:00:53 -04:00
|
|
|
for (i=0; i<num_routes; i++) {
|
2019-07-11 05:31:45 -03:00
|
|
|
if (routes[i].sysid == msg.sysid &&
|
|
|
|
routes[i].compid == msg.compid &&
|
2014-12-10 02:33:56 -04:00
|
|
|
routes[i].channel == in_channel) {
|
2019-07-11 05:31:45 -03:00
|
|
|
if (routes[i].mavtype == 0 && msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
|
|
|
|
routes[i].mavtype = mavlink_msg_heartbeat_get_type(&msg);
|
2015-07-24 08:52:06 -03:00
|
|
|
}
|
2014-12-09 23:00:53 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2014-12-16 19:30:09 -04:00
|
|
|
if (i == num_routes && i<MAVLINK_MAX_ROUTES) {
|
2019-07-11 05:31:45 -03:00
|
|
|
routes[i].sysid = msg.sysid;
|
|
|
|
routes[i].compid = msg.compid;
|
2014-12-09 23:00:53 -04:00
|
|
|
routes[i].channel = in_channel;
|
2019-07-11 05:31:45 -03:00
|
|
|
if (msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
|
|
|
|
routes[i].mavtype = mavlink_msg_heartbeat_get_type(&msg);
|
2015-07-24 08:52:06 -03:00
|
|
|
}
|
2014-12-09 23:00:53 -04:00
|
|
|
num_routes++;
|
|
|
|
#if ROUTING_DEBUG
|
|
|
|
::printf("learned route %u %u via %u\n",
|
2019-07-11 05:31:45 -03:00
|
|
|
(unsigned)msg.sysid,
|
|
|
|
(unsigned)msg.compid,
|
2014-12-09 23:00:53 -04:00
|
|
|
(unsigned)in_channel);
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
special handling for heartbeat messages. To ensure routing
|
2016-05-12 13:51:11 -03:00
|
|
|
propagation heartbeat messages need to be forwarded on all channels
|
2014-12-09 23:00:53 -04:00
|
|
|
except channels where the sysid/compid of the heartbeat could come from
|
|
|
|
*/
|
2023-03-05 19:44:55 -04:00
|
|
|
void MAVLink_routing::handle_heartbeat(GCS_MAVLINK &link, const mavlink_message_t &msg)
|
2014-12-09 23:00:53 -04:00
|
|
|
{
|
2019-08-27 02:15:46 -03:00
|
|
|
uint16_t mask = GCS_MAVLINK::active_channel_mask() & ~GCS_MAVLINK::private_channel_mask();
|
|
|
|
|
2023-03-05 19:44:55 -04:00
|
|
|
const mavlink_channel_t in_channel = link.get_chan();
|
|
|
|
|
2014-12-09 23:00:53 -04:00
|
|
|
// don't send on the incoming channel. This should only matter if
|
|
|
|
// the routing table is full
|
|
|
|
mask &= ~(1U<<(in_channel-MAVLINK_COMM_0));
|
2016-05-11 06:24:59 -03:00
|
|
|
|
|
|
|
// mask out channels that do not want the heartbeat to be forwarded
|
|
|
|
mask &= ~no_route_mask;
|
|
|
|
|
2014-12-09 23:00:53 -04:00
|
|
|
// mask out channels that are known sources for this sysid/compid
|
|
|
|
for (uint8_t i=0; i<num_routes; i++) {
|
2019-07-11 05:31:45 -03:00
|
|
|
if (routes[i].sysid == msg.sysid && routes[i].compid == msg.compid) {
|
2014-12-09 23:00:53 -04:00
|
|
|
mask &= ~(1U<<((unsigned)(routes[i].channel-MAVLINK_COMM_0)));
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (mask == 0) {
|
|
|
|
// nothing to send to
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// send on the remaining channels
|
|
|
|
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
|
|
|
|
if (mask & (1U<<i)) {
|
|
|
|
mavlink_channel_t channel = (mavlink_channel_t)(MAVLINK_COMM_0 + i);
|
2019-07-11 05:31:45 -03:00
|
|
|
if (comm_get_txspace(channel) >= ((uint16_t)msg.len) +
|
2016-04-05 01:09:47 -03:00
|
|
|
GCS_MAVLINK::packet_overhead_chan(channel)) {
|
2014-12-09 23:00:53 -04:00
|
|
|
#if ROUTING_DEBUG
|
|
|
|
::printf("fwd HB from chan %u on chan %u from sysid=%u compid=%u\n",
|
|
|
|
(unsigned)in_channel,
|
|
|
|
(unsigned)channel,
|
2019-07-11 05:31:45 -03:00
|
|
|
(unsigned)msg.sysid,
|
|
|
|
(unsigned)msg.compid);
|
2014-12-09 23:00:53 -04:00
|
|
|
#endif
|
2019-07-11 05:31:45 -03:00
|
|
|
_mavlink_resend_uart(channel, &msg);
|
2014-12-09 23:00:53 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
extract target sysid and compid from a message. int16_t is used so
|
|
|
|
that the caller can set them to -1 and know when a sysid or compid
|
|
|
|
target is found in the message
|
|
|
|
*/
|
2019-07-11 05:31:45 -03:00
|
|
|
void MAVLink_routing::get_targets(const mavlink_message_t &msg, int16_t &sysid, int16_t &compid)
|
2014-12-09 23:00:53 -04:00
|
|
|
{
|
2019-07-11 05:31:45 -03:00
|
|
|
const mavlink_msg_entry_t *msg_entry = mavlink_get_msg_entry(msg.msgid);
|
2016-05-16 02:01:02 -03:00
|
|
|
if (msg_entry == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM) {
|
2019-07-11 05:31:45 -03:00
|
|
|
sysid = _MAV_RETURN_uint8_t(&msg, msg_entry->target_system_ofs);
|
2016-05-16 02:01:02 -03:00
|
|
|
}
|
|
|
|
if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT) {
|
2019-07-11 05:31:45 -03:00
|
|
|
compid = _MAV_RETURN_uint8_t(&msg, msg_entry->target_component_ofs);
|
2014-12-09 23:00:53 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-09-02 02:21:36 -03:00
|
|
|
#endif // HAL_GCS_ENABLED
|