sixlowpan_input.c 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888
  1. /****************************************************************************
  2. * net/sixlowpan/sixlowpan_input.c
  3. * 6LoWPAN implementation (RFC 4944 and RFC 6282)
  4. *
  5. * Copyright (C) 2017, Gregory Nutt, all rights reserved
  6. * Author: Gregory Nutt <gnutt@nuttx.org>
  7. *
  8. * Derives in large part from Contiki:
  9. *
  10. * Copyright (c) 2008, Swedish Institute of Computer Science.
  11. * All rights reserved.
  12. * Authors: Adam Dunkels <adam@sics.se>
  13. * Nicolas Tsiftes <nvt@sics.se>
  14. * Niclas Finne <nfi@sics.se>
  15. * Mathilde Durvy <mdurvy@cisco.com>
  16. * Julien Abeille <jabeille@cisco.com>
  17. * Joakim Eriksson <joakime@sics.se>
  18. * Joel Hoglund <joel@sics.se>
  19. *
  20. * Redistribution and use in source and binary forms, with or without
  21. * modification, are permitted provided that the following conditions
  22. * are met:
  23. * 1. Redistributions of source code must retain the above copyright
  24. * notice, this list of conditions and the following disclaimer.
  25. * 2. Redistributions in binary form must reproduce the above copyright
  26. * notice, this list of conditions and the following disclaimer in the
  27. * documentation and/or other materials provided with the distribution.
  28. * 3. Neither the name of the Institute nor the names of its contributors
  29. * may be used to endorse or promote products derived from this software
  30. * without specific prior written permission.
  31. *
  32. * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
  33. * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
  34. * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
  35. * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
  36. * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
  37. * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
  38. * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
  39. * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  40. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
  41. * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
  42. * SUCH DAMAGE.
  43. *
  44. ****************************************************************************/
  45. /****************************************************************************
  46. * Included Files
  47. ****************************************************************************/
  48. #include <nuttx/config.h>
  49. #include <string.h>
  50. #include <assert.h>
  51. #include <errno.h>
  52. #include <debug.h>
  53. #include "nuttx/mm/iob.h"
  54. #include "nuttx/net/netdev.h"
  55. #include "nuttx/net/radiodev.h"
  56. #include "nuttx/net/ip.h"
  57. #include "nuttx/net/icmpv6.h"
  58. #include "nuttx/net/sixlowpan.h"
  59. #include "nuttx/wireless/ieee802154/ieee802154_mac.h"
  60. #ifdef CONFIG_NET_PKT
  61. # include "pkt/pkt.h"
  62. #endif
  63. #include "sixlowpan/sixlowpan_internal.h"
  64. #ifdef CONFIG_NET_6LOWPAN
  65. /****************************************************************************
  66. * Pre-processor Definitions
  67. ****************************************************************************/
  68. /* Success return values from sixlowpan_frame_process */
  69. #define INPUT_PARTIAL 0 /* Frame processed successful, packet incomplete */
  70. #define INPUT_COMPLETE 1 /* Frame processed successful, packet complete */
  71. /* This is the size of a buffer large enough to hold the largest uncompressed
  72. * HC06 or HC1 headers.
  73. */
  74. #ifdef CONFIG_NET_TCP
  75. /* The basic TCP header length is TCP_HDRLEN but could include up to 16
  76. * additional 32-bit words of optional data.
  77. */
  78. # define UNCOMP_MAXHDR (IPv6_HDRLEN + TCP_HDRLEN + 16*sizeof(uint32_t))
  79. #elif defined(CONFIG_NET_UDP)
  80. /* The UDP header length is always 8 bytes */
  81. # define UNCOMP_MAXHDR (IPv6_HDRLEN + UDP_HDRLEN)
  82. #elif defined(CONFIG_NET_ICMPv6)
  83. /* The ICMPv6 header length is a mere 4 bytes */
  84. # define UNCOMP_MAXHDR (IPv6_HDRLEN + ICMPv6_HDRLEN)
  85. #else
  86. /* No other header type is handled. */
  87. # define UNCOMP_MAXHDR IPv6_HDRLEN
  88. #endif
  89. /* Buffer access helpers */
  90. #define IPv6BUF(dev) ((FAR struct ipv6_hdr_s *)((dev)->d_buf))
  91. #define TCPBUF(dev) ((FAR struct tcp_hdr_s *)&(dev)->d_buf[IPv6_HDRLEN])
  92. /****************************************************************************
  93. * Private Data
  94. ****************************************************************************/
  95. /* This big buffer could be avoided with a little more effort */
  96. static uint8_t g_bitbucket[UNCOMP_MAXHDR];
  97. /****************************************************************************
  98. * Private Functions
  99. ****************************************************************************/
  100. /****************************************************************************
  101. * Name: sixlowpan_compress_ipv6hdr
  102. *
  103. * Description:
  104. * IPv6 dispatch "compression" function. Packets "Compression" when only
  105. * IPv6 dispatch is used
  106. *
  107. * There is no compression in this case, all fields are sent
  108. * inline. We just add the IPv6 dispatch byte before the packet.
  109. *
  110. * 0 1 2 3
  111. * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1
  112. * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+
  113. * | IPv6 Dsp | IPv6 header and payload ...
  114. * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+
  115. *
  116. * Input Parameters:
  117. * fptr - Pointer to the beginning of the frame under construction
  118. * bptr - Output goes here. Normally this is a known offset into d_buf,
  119. * may be redirected to g_bitbucket on the case of FRAGN frames.
  120. * proto - True: Copy the protocol header following the IPv6 header too.
  121. *
  122. * Returned Value:
  123. * None
  124. *
  125. ****************************************************************************/
  126. static void sixlowpan_uncompress_ipv6hdr(FAR uint8_t *fptr,
  127. FAR uint8_t *bptr)
  128. {
  129. FAR struct ipv6_hdr_s *ipv6 = (FAR struct ipv6_hdr_s *)bptr;
  130. /* Put uncompressed IPv6 header in d_buf. */
  131. g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN;
  132. memcpy(ipv6, fptr + g_frame_hdrlen, IPv6_HDRLEN);
  133. /* Update g_uncomp_hdrlen and g_frame_hdrlen. */
  134. g_frame_hdrlen += IPv6_HDRLEN;
  135. g_uncomp_hdrlen += IPv6_HDRLEN;
  136. }
  137. /****************************************************************************
  138. * Name: sixlowpan_uncompress_ipv6proto
  139. *
  140. * Description:
  141. * Copy the protocol header following the IPv4 header
  142. *
  143. * Input Parameters:
  144. * fptr - Pointer to the beginning of the frame under construction
  145. * bptr - Output goes here. Normally this is a known offset into d_buf,
  146. * may be redirected to g_bitbucket on the case of FRAGN frames.
  147. * proto - True: Copy the protocol header following the IPv6 header too.
  148. *
  149. * Returned Value:
  150. * The size of the protocol header that was copied.
  151. *
  152. ****************************************************************************/
  153. static uint16_t sixlowpan_uncompress_ipv6proto(FAR uint8_t *fptr,
  154. FAR uint8_t *bptr)
  155. {
  156. FAR struct ipv6_hdr_s *ipv6 = (FAR struct ipv6_hdr_s *)bptr;
  157. uint16_t protosize = 0;
  158. /* Copy the following protocol header. */
  159. switch (ipv6->proto)
  160. {
  161. #ifdef CONFIG_NET_TCP
  162. case IP_PROTO_TCP:
  163. {
  164. FAR struct tcp_hdr_s *tcp =
  165. (FAR struct tcp_hdr_s *)(fptr + g_frame_hdrlen);
  166. /* The TCP header length is encoded in the top 4 bits of the
  167. * tcpoffset field (in units of 32-bit words).
  168. */
  169. protosize = ((uint16_t)tcp->tcpoffset >> 4) << 2;
  170. }
  171. break;
  172. #endif
  173. #ifdef CONFIG_NET_UDP
  174. case IP_PROTO_UDP:
  175. protosize = sizeof(struct udp_hdr_s);
  176. break;
  177. #endif
  178. #ifdef CONFIG_NET_ICMPv6
  179. case IP_PROTO_ICMP6:
  180. protosize = sizeof(struct icmpv6_hdr_s);
  181. break;
  182. #endif
  183. default:
  184. nwarn("WARNING: Unrecognized proto: %u\n", ipv6->proto);
  185. return 0;
  186. }
  187. /* Copy the protocol header. */
  188. memcpy((FAR uint8_t *)ipv6 + g_uncomp_hdrlen, fptr + g_frame_hdrlen,
  189. protosize);
  190. g_frame_hdrlen += protosize;
  191. g_uncomp_hdrlen += protosize;
  192. return protosize;
  193. }
  194. /****************************************************************************
  195. * Public Functions
  196. ****************************************************************************/
  197. /****************************************************************************
  198. * Name: sixlowpan_frame_process
  199. *
  200. * Description:
  201. * Process an incoming 6LoWPAN frame in 'iob'.
  202. *
  203. * If its a FRAG1 or a non-fragmented frame we first uncompress the IP
  204. * header. The 6LoWPAN payload and possibly the uncompressed IP header
  205. * are then copied into d_buf. An indication is returned if the packet
  206. * in d_buf is complete (i.e., non-fragmented frame or and the last
  207. * FRAGN frame).
  208. *
  209. * NOTE: We do not check for overlapping sixlowpan fragments (that is a
  210. * SHALL in the RFC 4944 and should never happen)
  211. *
  212. * Input Parameters:
  213. * radio - The radio network device driver interface.
  214. * metadata - Metadata characterizing the received frame.
  215. * iob - The IOB containing the frame.
  216. *
  217. * Returned Value:
  218. * On success, a value greater than equal to zero is returned, either:
  219. *
  220. * INPUT_PARTIAL Frame processed successful, packet incomplete
  221. * INPUT_COMPLETE Frame processed successful, packet complete
  222. *
  223. * Otherwise a negated errno value is returned to indicate the nature of
  224. * the failure.
  225. *
  226. * Assumptions:
  227. * Network is locked
  228. *
  229. ****************************************************************************/
  230. static int sixlowpan_frame_process(FAR struct radio_driver_s *radio,
  231. FAR const void *metadata,
  232. FAR struct iob_s *iob)
  233. {
  234. FAR struct sixlowpan_reassbuf_s *reass;
  235. struct netdev_varaddr_s fragsrc;
  236. FAR uint8_t *fptr; /* Convenience pointer to beginning of the frame */
  237. FAR uint8_t *bptr; /* Used to redirect uncompressed header to the bitbucket */
  238. FAR uint8_t *hc1; /* Convenience pointer to HC1 data */
  239. FAR uint8_t *fragptr; /* Pointer to the fragmentation header */
  240. uint16_t fragsize = 0; /* Size of the IP packet (read from fragment) */
  241. uint16_t paysize; /* Size of the data payload */
  242. uint16_t fragtag = 0; /* Tag of the fragment */
  243. uint8_t fragoffset = 0; /* Offset of the fragment in the IP packet */
  244. uint8_t protosize = 0; /* Length of the protocol header (treated like payload) */
  245. bool isfrag = false; /* true: Frame is a fragment */
  246. bool isfrag1 = false; /* true: Frame is the first fragment of the series */
  247. int reqsize; /* Required buffer size */
  248. int hdrsize; /* Size of the IEEE802.15.4 header */
  249. int ret;
  250. /* Get a pointer to the payload following the IEEE802.15.4 frame header(s).
  251. * This size includes both fragmentation and FCF headers.
  252. */
  253. fptr = iob->io_data; /* Frame data is in I/O buffer */
  254. hdrsize = iob->io_offset; /* Offset past the MAC header */
  255. DEBUGASSERT((unsigned)hdrsize < iob->io_len);
  256. /* Initialize global data. Locking the network guarantees that we have
  257. * exclusive use of the global values for intermediate calculations.
  258. */
  259. g_uncomp_hdrlen = 0;
  260. g_frame_hdrlen = hdrsize;
  261. /* Since we don't support the mesh and broadcast header, the first header
  262. * we look for is the fragmentation header. NOTE that g_frame_hdrlen
  263. * already includes the fragmentation header, if presetn.
  264. */
  265. fragptr = fptr + hdrsize;
  266. switch ((GETUINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0xf800) >> 8)
  267. {
  268. /* First fragment of new reassembly */
  269. case SIXLOWPAN_DISPATCH_FRAG1:
  270. {
  271. /* Set up for the reassembly */
  272. fragsize = GETUINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0x07ff;
  273. fragtag = GETUINT16(fragptr, SIXLOWPAN_FRAG_TAG);
  274. g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN;
  275. ninfo("FRAG1: fragsize=%d fragtag=%d fragoffset=%d\n",
  276. fragsize, fragtag, fragoffset);
  277. /* Drop any zero length fragments */
  278. if (fragsize == 0)
  279. {
  280. nwarn("WARNING: Dropping zero-length 6LoWPAN fragment\n");
  281. return INPUT_PARTIAL;
  282. }
  283. /* Drop the packet if it cannot fit into the d_buf */
  284. if (fragsize > CONFIG_NET_6LOWPAN_PKTSIZE)
  285. {
  286. nwarn("WARNING: Reassembled packet size exceeds "
  287. "CONFIG_NET_6LOWPAN_PKTSIZE\n");
  288. return -ENOSPC;
  289. }
  290. /* Extract the source address from the 'metadata'. */
  291. ret = sixlowpan_extract_srcaddr(radio, metadata, &fragsrc);
  292. if (ret < 0)
  293. {
  294. nerr("ERROR: sixlowpan_extract_srcaddr failed: %d\n", ret);
  295. return ret;
  296. }
  297. /* Allocate a new reassembly buffer */
  298. reass = sixlowpan_reass_allocate(fragtag, &fragsrc);
  299. if (reass == NULL)
  300. {
  301. nerr("ERROR: Failed to allocate a reassembly buffer\n");
  302. return -ENOMEM;
  303. }
  304. radio->r_dev.d_buf = reass->rb_buf;
  305. radio->r_dev.d_len = 0;
  306. reass->rb_pktlen = fragsize;
  307. /* Indicate the first fragment of the reassembly */
  308. bptr = reass->rb_buf;
  309. isfrag1 = true;
  310. isfrag = true;
  311. }
  312. break;
  313. case SIXLOWPAN_DISPATCH_FRAGN:
  314. {
  315. /* Get offset, tag, size. Offset is in units of 8 bytes. */
  316. fragoffset = fragptr[SIXLOWPAN_FRAG_OFFSET];
  317. fragtag = GETUINT16(fragptr, SIXLOWPAN_FRAG_TAG);
  318. fragsize = GETUINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0x07ff;
  319. g_frame_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN;
  320. /* Extract the source address from the 'metadata'. */
  321. ret = sixlowpan_extract_srcaddr(radio, metadata, &fragsrc);
  322. if (ret < 0)
  323. {
  324. nerr("ERROR: sixlowpan_extract_srcaddr failed: %d\n", ret);
  325. return ret;
  326. }
  327. /* Find the existing reassembly buffer
  328. * with the same tag and source address
  329. */
  330. reass = sixlowpan_reass_find(fragtag, &fragsrc);
  331. if (reass == NULL)
  332. {
  333. nerr("ERROR: Failed to find a reassembly buffer for tag=%04x\n",
  334. fragtag);
  335. return -ENOENT;
  336. }
  337. if (fragsize != reass->rb_pktlen)
  338. {
  339. /* The packet is a fragment but its size does not match. */
  340. nwarn("WARNING: Dropping 6LoWPAN packet. Bad fragsize: %u vs %u\n",
  341. fragsize, reass->rb_pktlen);
  342. ret = -EPERM;
  343. goto errout_with_reass;
  344. }
  345. radio->r_dev.d_buf = reass->rb_buf;
  346. radio->r_dev.d_len = 0;
  347. ninfo("FRAGN: fragsize=%d fragtag=%d fragoffset=%d\n",
  348. fragsize, fragtag, fragoffset);
  349. ninfo("FRAGN: rb_accumlen=%d paysize=%u fragsize=%u\n",
  350. reass->rb_accumlen, iob->io_len - g_frame_hdrlen, fragsize);
  351. /* Indicate that this frame is a another fragment for reassembly */
  352. bptr = g_bitbucket;
  353. isfrag = true;
  354. }
  355. break;
  356. /* Not a fragment */
  357. default:
  358. /* We still need a packet buffer. But in this case, the driver should
  359. * have provided one.
  360. */
  361. DEBUGASSERT(radio->r_dev.d_buf != NULL);
  362. reass = (FAR struct sixlowpan_reassbuf_s *)radio->r_dev.d_buf;
  363. reass->rb_pool = REASS_POOL_RADIO;
  364. bptr = reass->rb_buf;
  365. break;
  366. }
  367. /* Process next dispatch and headers */
  368. hc1 = fptr + g_frame_hdrlen;
  369. #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06
  370. if ((hc1[SIXLOWPAN_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) ==
  371. SIXLOWPAN_DISPATCH_IPHC)
  372. {
  373. ninfo("IPHC Dispatch\n");
  374. sixlowpan_uncompresshdr_hc06(radio, metadata,
  375. fragsize, iob, fptr, bptr);
  376. }
  377. else
  378. #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */
  379. #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1
  380. if (hc1[SIXLOWPAN_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1)
  381. {
  382. ninfo("HC1 Dispatch\n");
  383. sixlowpan_uncompresshdr_hc1(radio, metadata,
  384. fragsize, iob, fptr, bptr);
  385. }
  386. else
  387. #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */
  388. if (hc1[SIXLOWPAN_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6)
  389. {
  390. ninfo("IPv6 Dispatch\n");
  391. /* Uncompress the IPv6 header */
  392. sixlowpan_uncompress_ipv6hdr(fptr, bptr);
  393. /* A protocol header will follow the IPv6 header only on a non-
  394. * fragmented packet or on the first fragment of a fragmented
  395. * packet.
  396. */
  397. if (!isfrag || isfrag1)
  398. {
  399. protosize = sixlowpan_uncompress_ipv6proto(fptr, bptr);
  400. }
  401. }
  402. else
  403. {
  404. /* Unknown or unsupported header */
  405. nwarn("WARNING: Unknown dispatch: %u\n", hc1[SIXLOWPAN_HC1_DISPATCH]);
  406. ret = -ENOSYS;
  407. goto errout_with_reass;
  408. }
  409. /* Is this the first fragment is a sequence? */
  410. if (isfrag1)
  411. {
  412. /* Yes.. Remember the offset from the beginning of d_buf where we
  413. * begin placing the data payload.
  414. */
  415. reass->rb_boffset = g_uncomp_hdrlen - protosize;
  416. }
  417. /* No.. is this a subsequent fragment in the same sequence? */
  418. else if (isfrag)
  419. {
  420. /* Yes, recover the offset from the beginning of the d_buf where
  421. * we began placing payload data.
  422. */
  423. g_uncomp_hdrlen = reass->rb_boffset;
  424. }
  425. /* Copy "payload" from the frame buffer to the IEEE802.15.4 MAC driver's
  426. * packet buffer, d_buf. If this frame is a first fragment or not part of
  427. * a fragmented packet, we have already copied the compressed headers,
  428. * g_uncomp_hdrlen and g_frame_hdrlen are non-zerio, fragoffset is.
  429. */
  430. paysize = iob->io_len - g_frame_hdrlen;
  431. if (paysize > CONFIG_NET_6LOWPAN_PKTSIZE)
  432. {
  433. nwarn("Packet dropped due to payload (%u) > packet buffer (%u)\n",
  434. paysize, CONFIG_NET_6LOWPAN_PKTSIZE);
  435. ret = -ENOSPC;
  436. goto errout_with_reass;
  437. }
  438. /* Sanity-check size of incoming packet to avoid buffer overflow */
  439. reqsize = g_uncomp_hdrlen + (fragoffset << 3) + paysize;
  440. if (reqsize > CONFIG_NET_6LOWPAN_PKTSIZE)
  441. {
  442. nwarn("WARNING: Required buffer size: %u+%u+%u=%u Available=%u\n",
  443. g_uncomp_hdrlen, (fragoffset << 3), paysize,
  444. reqsize, CONFIG_NET_6LOWPAN_PKTSIZE);
  445. ret = -ENOMEM;
  446. goto errout_with_reass;
  447. }
  448. memcpy(radio->r_dev.d_buf + g_uncomp_hdrlen + (fragoffset << 3),
  449. fptr + g_frame_hdrlen, paysize);
  450. /* Update reass->rb_accumlen if the frame is a fragment, reass->rb_pktlen
  451. * otherwise.
  452. */
  453. if (isfrag)
  454. {
  455. /* Check if it is the last fragment to be processed.
  456. *
  457. * If this is the last fragment, we may shave off any extrenous
  458. * bytes at the end. We must be liberal in what we accept.
  459. */
  460. reass->rb_accumlen = g_uncomp_hdrlen + (fragoffset << 3) + paysize;
  461. }
  462. else
  463. {
  464. reass->rb_pktlen = paysize + g_uncomp_hdrlen;
  465. }
  466. /* If we have a full IP packet in sixlowpan_buf, deliver it to
  467. * the IP stack
  468. */
  469. ninfo("rb_accumlen=%d rb_pktlen=%d paysize=%d\n",
  470. reass->rb_accumlen, reass->rb_pktlen, paysize);
  471. if (reass->rb_accumlen == 0 || reass->rb_accumlen >= reass->rb_pktlen)
  472. {
  473. ninfo("IP packet ready (length %d)\n", reass->rb_pktlen);
  474. radio->r_dev.d_buf = reass->rb_buf;
  475. radio->r_dev.d_len = reass->rb_pktlen;
  476. reass->rb_active = false;
  477. reass->rb_pktlen = 0;
  478. reass->rb_accumlen = 0;
  479. return INPUT_COMPLETE;
  480. }
  481. radio->r_dev.d_buf = NULL;
  482. radio->r_dev.d_len = 0;
  483. return INPUT_PARTIAL;
  484. errout_with_reass:
  485. sixlowpan_reass_free(reass);
  486. return ret;
  487. }
  488. /****************************************************************************
  489. * Name: sixlowpan_dispatch
  490. *
  491. * Description:
  492. * Inject the packet in d_buf into the network for normal packet
  493. * processing.
  494. *
  495. * Input Parameters:
  496. * radio - The IEEE802.15.4 MAC network driver interface.
  497. *
  498. * Returned Value:
  499. * None
  500. *
  501. ****************************************************************************/
  502. static int sixlowpan_dispatch(FAR struct radio_driver_s *radio)
  503. {
  504. FAR struct sixlowpan_reassbuf_s *reass;
  505. int ret;
  506. sixlowpan_dumpbuffer("Incoming packet",
  507. (FAR const uint8_t *)IPv6BUF(&radio->r_dev),
  508. radio->r_dev.d_len);
  509. #ifdef CONFIG_NET_PKT
  510. /* When packet sockets are enabled, feed the frame into the tap */
  511. ninfo("Packet tap\n");
  512. pkt_input(&radio->r_dev);
  513. #endif
  514. /* We only accept IPv6 packets. */
  515. ninfo("IPv6 packet dispatch\n");
  516. NETDEV_RXIPV6(&radio->r_dev);
  517. /* Give the IPv6 packet to the network layer. NOTE: If there is a
  518. * problem with IPv6 header, it will be silently dropped and d_len will
  519. * be set to zero. Oddly, ipv6_input() will return OK in this case.
  520. */
  521. ret = ipv6_input(&radio->r_dev);
  522. /* Free the reassemby buffer */
  523. reass = (FAR struct sixlowpan_reassbuf_s *)radio->r_dev.d_buf;
  524. DEBUGASSERT(reass != NULL);
  525. sixlowpan_reass_free(reass);
  526. return ret;
  527. }
  528. /****************************************************************************
  529. * Public Functions
  530. ****************************************************************************/
  531. /****************************************************************************
  532. * Name: sixlowpan_input
  533. *
  534. * Description:
  535. * Process an incoming 6LoWPAN frame.
  536. *
  537. * This function is called when the radio device driver has received an
  538. * frame from the network. The frame from the device driver must be
  539. * provided in by the IOB frame argument of the function call:
  540. *
  541. * - The frame data is in the IOB io_data[] buffer,
  542. * - The length of the frame is in the IOB io_len field, and
  543. * - The offset past and radio MAC header is provided in the io_offset
  544. * field.
  545. *
  546. * The frame argument may refer to a single frame (a list of length one)
  547. * or may it be the head of a list of multiple frames.
  548. *
  549. * - The io_flink field points to the next frame in the list (if enable)
  550. * - The last frame in the list will have io_flink == NULL.
  551. *
  552. * An non-NULL d_buf of size CONFIG_NET_6LOWPAN_PKTSIZE +
  553. * CONFIG_NET_GUARDSIZE must also be provided. The frame will be
  554. * decompressed and placed in the d_buf. Fragmented packets will also be
  555. * reassembled in the d_buf as they are received (meaning for the driver,
  556. * that two packet buffers are required: One for reassembly of RX packets
  557. * and one used for TX polling).
  558. *
  559. * After each frame is processed into d_buf, the IOB is deallocated. If
  560. * reassembly is incomplete, the partially reassembled packet must be
  561. * preserved by the radio network driver and provided again when the next
  562. * frame is received.
  563. *
  564. * When the packet in the d_buf is fully reassembled, it will be provided
  565. * to the network as with any other received packet. d_len will be set
  566. * the length of the uncompressed, reassembled packet.
  567. *
  568. * After the network processes the packet, d_len will be set to zero.
  569. * Network logic may also decide to send a response to the packet. In
  570. * that case, the outgoing network packet will be placed in d_buf and
  571. * d_len will be set to a non-zero value. That case is handled by this
  572. * function.
  573. *
  574. * If that case occurs, the packet will be converted to a list of
  575. * compressed and possibly fragmented frames and provided to the MAC
  576. * network driver via the req_data() method as with other TX operations.
  577. *
  578. * Input Parameters:
  579. * radio The radio network driver interface.
  580. * framelist - The head of an incoming list of frames. Normally this
  581. * would be a single frame. A list may be provided if
  582. * appropriate, however.
  583. * metadata - Meta data characterizing the received packet. The specific
  584. * type of this metadata is obfuscated and depends on the
  585. * type of the radio driver. This could be be either
  586. * (1) struct ieee802154_data_ind_s for an IEEE 802.15.4
  587. * radio, or (2) struct pktradio_metadata_s for a non-standard
  588. * packet radio.
  589. *
  590. * If there are multilple frames in the list, this metadata
  591. * must apply to all of the frames in the list.
  592. *
  593. * Returned Value:
  594. * Zero (OK) is returned if the the frame was consumed; Otherwise a negated
  595. * errno value is returned.
  596. *
  597. ****************************************************************************/
  598. int sixlowpan_input(FAR struct radio_driver_s *radio,
  599. FAR struct iob_s *framelist, FAR const void *metadata)
  600. {
  601. int ret = -EINVAL;
  602. uint8_t *d_buf_backup;
  603. DEBUGASSERT(radio != NULL && framelist != NULL);
  604. /* Sixlowpan modifies the d_buf to process fragments using reassembly
  605. * buffers. Save the value of d_buf on entry and set it back before
  606. * returning
  607. */
  608. d_buf_backup = radio->r_dev.d_buf;
  609. /* Verify that an frame has been provided. */
  610. while (framelist != NULL)
  611. {
  612. FAR struct iob_s *iob;
  613. /* Remove the IOB containing the frame from the device structure */
  614. iob = framelist;
  615. framelist = iob->io_flink;
  616. sixlowpan_dumpbuffer("Incoming frame", iob->io_data, iob->io_len);
  617. /* Process the frame, decompressing it into the packet buffer */
  618. ret = sixlowpan_frame_process(radio, metadata, iob);
  619. /* If the frame was a valid 6LoWPAN frame, free the IOB the held the
  620. * consumed frame. Otherwise, the frame must stay allocated since the
  621. * MAC layer will try and pass it to another receiver to see if that
  622. * receiver wants it.
  623. */
  624. if (ret >= 0)
  625. {
  626. iob_free(iob, IOBUSER_NET_6LOWPAN);
  627. }
  628. /* Was the frame successfully processed? Is the packet in d_buf fully
  629. * reassembled?
  630. */
  631. if (ret == INPUT_COMPLETE)
  632. {
  633. /* Inject the uncompressed, reassembled packet into the network */
  634. ret = sixlowpan_dispatch(radio);
  635. if (ret >= 0)
  636. {
  637. /* Check if this resulted in a request to send an outgoing
  638. * packet.
  639. */
  640. if (radio->r_dev.d_len > 0)
  641. {
  642. FAR struct ipv6_hdr_s *ipv6hdr;
  643. FAR uint8_t *buffer;
  644. struct netdev_varaddr_s destmac;
  645. size_t hdrlen;
  646. size_t buflen;
  647. /* The IPv6 header followed by TCP or UDP headers should
  648. * lie at the beginning of d_buf since there is no link
  649. * layer protocol header.
  650. */
  651. ipv6hdr = IPv6BUF(&radio->r_dev);
  652. /* Get the IEEE 802.15.4 MAC address of the destination.
  653. * This assumes an encoding of the MAC address in the IPv6
  654. * address.
  655. */
  656. ret = sixlowpan_nexthopaddr(radio, ipv6hdr->destipaddr,
  657. &destmac);
  658. if (ret < 0)
  659. {
  660. nerr("ERROR: Failed to get dest MAC address: %d\n",
  661. ret);
  662. goto drop;
  663. }
  664. /* The data payload should follow the IPv6 header plus
  665. * the protocol header.
  666. */
  667. switch (ipv6hdr->proto)
  668. {
  669. #ifdef CONFIG_NET_TCP
  670. case IP_PROTO_TCP:
  671. {
  672. FAR struct tcp_hdr_s *tcp = TCPBUF(&radio->r_dev);
  673. uint16_t tcplen;
  674. /* The TCP header length is encoded in the top 4
  675. * bits of the tcpoffset field (in units of 32-bit
  676. * words).
  677. */
  678. tcplen = ((uint16_t)tcp->tcpoffset >> 4) << 2;
  679. hdrlen = IPv6_HDRLEN + tcplen;
  680. }
  681. break;
  682. #endif
  683. #ifdef CONFIG_NET_UDP
  684. case IP_PROTO_UDP:
  685. {
  686. hdrlen = IPv6_HDRLEN + UDP_HDRLEN;
  687. }
  688. break;
  689. #endif
  690. #ifdef CONFIG_NET_ICMPv6
  691. case IP_PROTO_ICMP6:
  692. {
  693. hdrlen = IPv6_HDRLEN + ICMPv6_HDRLEN;
  694. }
  695. break;
  696. #endif
  697. default:
  698. {
  699. nwarn("WARNING: Unsupported prototype: %u\n",
  700. ipv6hdr->proto);
  701. goto drop;
  702. }
  703. }
  704. if (hdrlen > radio->r_dev.d_len)
  705. {
  706. nwarn("WARNING: Packet too small: Have %u need >%zu\n",
  707. radio->r_dev.d_len, hdrlen);
  708. goto drop;
  709. }
  710. /* Convert the outgoing packet into a frame list. */
  711. buffer = radio->r_dev.d_buf + hdrlen;
  712. buflen = radio->r_dev.d_len - hdrlen;
  713. ret = sixlowpan_queue_frames(radio, ipv6hdr, buffer,
  714. buflen, &destmac);
  715. drop:
  716. radio->r_dev.d_len = 0;
  717. /* We consumed the frame, so we must return 0. */
  718. ret = 0;
  719. }
  720. }
  721. }
  722. }
  723. /* Restore the d_buf back to it's original state */
  724. radio->r_dev.d_buf = d_buf_backup;
  725. return ret;
  726. }
  727. #endif /* CONFIG_NET_6LOWPAN */