MAVLink_routing.cpp 12 KB

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