APM:Libraries
MAVLink_routing.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14 */
15 
18 
19 #include <stdio.h>
20 #include <AP_HAL/AP_HAL.h>
21 #include <AP_Common/AP_Common.h>
22 #include "GCS.h"
23 #include "MAVLink_routing.h"
24 
25 extern const AP_HAL::HAL& hal;
26 
27 #define ROUTING_DEBUG 0
28 
29 // constructor
30 MAVLink_routing::MAVLink_routing(void) : num_routes(0) {}
31 
32 /*
33  forward a MAVLink message to the right port. This also
34  automatically learns the route for the sender if it is not
35  already known.
36 
37  This returns true if the message should be processed locally
38 
39  Theory of MAVLink routing:
40 
41  When a flight controller receives a message it should process it
42  locally if any of these conditions hold:
43 
44  1a) the message has no target_system field
45 
46  1b) the message has a target_system of zero
47 
48  1c) the message has the flight controllers target system and has no
49  target_component field
50 
51  1d) the message has the flight controllers target system and has
52  the flight controllers target_component
53 
54  1e) the message has the flight controllers target system and the
55  flight controller has not seen any messages on any of its links
56  from a system that has the messages
57  target_system/target_component combination
58 
59  When a flight controller receives a message it should forward it
60  onto another different link if any of these conditions hold for that
61  link:
62 
63  2a) the message has no target_system field
64 
65  2b) the message has a target_system of zero
66 
67  2c) the message does not have the flight controllers target_system
68  and the flight controller has seen a message from the messages
69  target_system on the link
70 
71  2d) the message has the flight controllers target_system and has a
72  target_component field and the flight controllers has seen a
73  message from the target_system/target_component combination on
74  the link
75 
76 Note: This proposal assumes that ground stations will not send command
77 packets to a non-broadcast destination (sysid/compid combination)
78 until they have received at least one package from that destination
79 over the link. This is essential to prevent a flight controller from
80 acting on a message that is not meant for it. For example, a PARAM_SET
81 cannot be sent to a specific sysid/compid combination until the GCS
82 has seen a packet from that sysid/compid combination on the link.
83 
84 The GCS must also reset what sysid/compid combinations it has seen on
85 a link when it sees a SYSTEM_TIME message with a decrease in
86 time_boot_ms from a particular sysid/compid. That is essential to
87 detect a reset of the flight controller, which implies a reset of its
88 routing table.
89 
90 */
91 bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavlink_message_t* msg)
92 {
93  // handle the case of loopback of our own messages, due to
94  // incorrect serial configuration.
95  if (msg->sysid == mavlink_system.sysid &&
96  msg->compid == mavlink_system.compid) {
97  return true;
98  }
99 
100  // learn new routes
101  learn_route(in_channel, msg);
102 
103  if (msg->msgid == MAVLINK_MSG_ID_RADIO ||
104  msg->msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
105  // don't forward RADIO packets
106  return true;
107  }
108 
109  if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
110  // heartbeat needs special handling
111  handle_heartbeat(in_channel, msg);
112  return true;
113  }
114 
115  if (msg->msgid == MAVLINK_MSG_ID_ADSB_VEHICLE) {
116  // ADSB packets are not forwarded, they have their own stream rate
117  return true;
118  }
119 
120  // extract the targets for this packet
121  int16_t target_system = -1;
122  int16_t target_component = -1;
123  get_targets(msg, target_system, target_component);
124 
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 ||
129  (target_component == mavlink_system.compid));
130  bool process_locally = match_system && match_component;
131 
132  if (process_locally && !broadcast_system && !broadcast_component) {
133  // nothing more to do - it can only be for us
134  return true;
135  }
136 
137  // forward on any channels matching the targets
138  bool forwarded = false;
139  bool sent_to_chan[MAVLINK_COMM_NUM_BUFFERS];
140  memset(sent_to_chan, 0, sizeof(sent_to_chan));
141  for (uint8_t i=0; i<num_routes; i++) {
142  if (broadcast_system || (target_system == routes[i].sysid &&
143  (broadcast_component ||
144  target_component == routes[i].compid ||
145  !match_system))) {
146  if (in_channel != routes[i].channel && !sent_to_chan[routes[i].channel]) {
147  if (comm_get_txspace(routes[i].channel) >= ((uint16_t)msg->len) +
149 #if ROUTING_DEBUG
150  ::printf("fwd msg %u from chan %u on chan %u sysid=%d compid=%d\n",
151  msg->msgid,
152  (unsigned)in_channel,
153  (unsigned)routes[i].channel,
154  (int)target_system,
155  (int)target_component);
156 #endif
157  _mavlink_resend_uart(routes[i].channel, msg);
158  }
159  sent_to_chan[routes[i].channel] = true;
160  forwarded = true;
161  }
162  }
163  }
164  if (!forwarded && match_system) {
165  process_locally = true;
166  }
167 
168  return process_locally;
169 }
170 
171 /*
172  send a MAVLink message to all components with this vehicle's system id
173 
174  This is a no-op if no routes to components have been learned
175 */
176 void MAVLink_routing::send_to_components(const mavlink_message_t* msg)
177 {
178  bool sent_to_chan[MAVLINK_COMM_NUM_BUFFERS];
179  memset(sent_to_chan, 0, sizeof(sent_to_chan));
180 
181  // check learned routes
182  for (uint8_t i=0; i<num_routes; i++) {
183  if ((routes[i].sysid == mavlink_system.sysid) && !sent_to_chan[routes[i].channel]) {
184  if (comm_get_txspace(routes[i].channel) >= ((uint16_t)msg->len) +
186 #if ROUTING_DEBUG
187  ::printf("send msg %u on chan %u sysid=%u compid=%u\n",
188  msg->msgid,
189  (unsigned)routes[i].channel,
190  (unsigned)routes[i].sysid,
191  (unsigned)routes[i].compid);
192 #endif
193  _mavlink_resend_uart(routes[i].channel, msg);
194  sent_to_chan[routes[i].channel] = true;
195  }
196  }
197  }
198 }
199 
200 /*
201  search for the first vehicle or component in the routing table with given mav_type and retrieve it's sysid, compid and channel
202  returns true if a match is found
203  */
204 bool MAVLink_routing::find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel)
205 {
206  // check learned routes
207  for (uint8_t i=0; i<num_routes; i++) {
208  if (routes[i].mavtype == mavtype) {
209  sysid = routes[i].sysid;
210  compid = routes[i].compid;
211  channel = routes[i].channel;
212  return true;
213  }
214  }
215 
216  // if we've reached we have not found the component
217  return false;
218 }
219 
220 /*
221  see if the message is for a new route and learn it
222 */
223 void MAVLink_routing::learn_route(mavlink_channel_t in_channel, const mavlink_message_t* msg)
224 {
225  uint8_t i;
226  if (msg->sysid == 0 ||
227  (msg->sysid == mavlink_system.sysid &&
228  msg->compid == mavlink_system.compid)) {
229  return;
230  }
231  for (i=0; i<num_routes; i++) {
232  if (routes[i].sysid == msg->sysid &&
233  routes[i].compid == msg->compid &&
234  routes[i].channel == in_channel) {
235  if (routes[i].mavtype == 0 && msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
236  routes[i].mavtype = mavlink_msg_heartbeat_get_type(msg);
237  }
238  break;
239  }
240  }
241  if (i == num_routes && i<MAVLINK_MAX_ROUTES) {
242  routes[i].sysid = msg->sysid;
243  routes[i].compid = msg->compid;
244  routes[i].channel = in_channel;
245  if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
246  routes[i].mavtype = mavlink_msg_heartbeat_get_type(msg);
247  }
248  num_routes++;
249 #if ROUTING_DEBUG
250  ::printf("learned route %u %u via %u\n",
251  (unsigned)msg->sysid,
252  (unsigned)msg->compid,
253  (unsigned)in_channel);
254 #endif
255  }
256 }
257 
258 
259 /*
260  special handling for heartbeat messages. To ensure routing
261  propagation heartbeat messages need to be forwarded on all channels
262  except channels where the sysid/compid of the heartbeat could come from
263 */
264 void MAVLink_routing::handle_heartbeat(mavlink_channel_t in_channel, const mavlink_message_t* msg)
265 {
266  uint16_t mask = GCS_MAVLINK::active_channel_mask();
267 
268  // don't send on the incoming channel. This should only matter if
269  // the routing table is full
270  mask &= ~(1U<<(in_channel-MAVLINK_COMM_0));
271 
272  // mask out channels that do not want the heartbeat to be forwarded
273  mask &= ~no_route_mask;
274 
275  // mask out channels that are known sources for this sysid/compid
276  for (uint8_t i=0; i<num_routes; i++) {
277  if (routes[i].sysid == msg->sysid && routes[i].compid == msg->compid) {
278  mask &= ~(1U<<((unsigned)(routes[i].channel-MAVLINK_COMM_0)));
279  }
280  }
281 
282  if (mask == 0) {
283  // nothing to send to
284  return;
285  }
286 
287  // send on the remaining channels
288  for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
289  if (mask & (1U<<i)) {
290  mavlink_channel_t channel = (mavlink_channel_t)(MAVLINK_COMM_0 + i);
291  if (comm_get_txspace(channel) >= ((uint16_t)msg->len) +
293 #if ROUTING_DEBUG
294  ::printf("fwd HB from chan %u on chan %u from sysid=%u compid=%u\n",
295  (unsigned)in_channel,
296  (unsigned)channel,
297  (unsigned)msg->sysid,
298  (unsigned)msg->compid);
299 #endif
300  _mavlink_resend_uart(channel, msg);
301  }
302  }
303  }
304 }
305 
306 
307 /*
308  extract target sysid and compid from a message. int16_t is used so
309  that the caller can set them to -1 and know when a sysid or compid
310  target is found in the message
311 */
312 void MAVLink_routing::get_targets(const mavlink_message_t* msg, int16_t &sysid, int16_t &compid)
313 {
314  const mavlink_msg_entry_t *msg_entry = mavlink_get_msg_entry(msg->msgid);
315  if (msg_entry == nullptr) {
316  return;
317  }
318  if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM) {
319  sysid = _MAV_RETURN_uint8_t(msg, msg_entry->target_system_ofs);
320  }
321  if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT) {
322  compid = _MAV_RETURN_uint8_t(msg, msg_entry->target_component_ofs);
323  }
324 }
325 
int printf(const char *fmt,...)
Definition: stdio.c:113
Interface definition for the various Ground Control System.
Common definitions and utility routines for the ArduPilot libraries.