udp_psock_sendto_buffered.c 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932
  1. /****************************************************************************
  2. * net/udp/udp_send_buffered.c
  3. *
  4. * Copyright (C) 2018 Gregory Nutt. All rights reserved.
  5. * Author: Gregory Nutt <gnutt@nuttx.org>
  6. *
  7. * Redistribution and use in source and binary forms, with or without
  8. * modification, are permitted provided that the following conditions
  9. * are met:
  10. *
  11. * 1. Redistributions of source code must retain the above copyright
  12. * notice, this list of conditions and the following disclaimer.
  13. * 2. Redistributions in binary form must reproduce the above copyright
  14. * notice, this list of conditions and the following disclaimer in
  15. * the documentation and/or other materials provided with the
  16. * distribution.
  17. * 3. Neither the name NuttX nor the names of its contributors may be
  18. * used to endorse or promote products derived from this software
  19. * without specific prior written permission.
  20. *
  21. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  22. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  23. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  24. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  25. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  26. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  27. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  28. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  29. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  30. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  31. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  32. * POSSIBILITY OF SUCH DAMAGE.
  33. *
  34. ****************************************************************************/
  35. /****************************************************************************
  36. * Included Files
  37. ****************************************************************************/
  38. #include <nuttx/config.h>
  39. #if defined(CONFIG_NET) && defined(CONFIG_NET_UDP) && \
  40. defined(CONFIG_NET_UDP_WRITE_BUFFERS)
  41. #if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_NET_UDP_WRBUFFER_DEBUG)
  42. /* Force debug output (from this file only) */
  43. # undef CONFIG_DEBUG_NET
  44. # define CONFIG_DEBUG_NET 1
  45. #endif
  46. #include <sys/types.h>
  47. #include <sys/socket.h>
  48. #include <stdint.h>
  49. #include <stdbool.h>
  50. #include <stdio.h>
  51. #include <string.h>
  52. #include <errno.h>
  53. #include <debug.h>
  54. #include <debug.h>
  55. #include <arch/irq.h>
  56. #include <nuttx/clock.h>
  57. #include <nuttx/net/net.h>
  58. #include <nuttx/mm/iob.h>
  59. #include <nuttx/net/netdev.h>
  60. #include <nuttx/net/arp.h>
  61. #include <nuttx/net/udp.h>
  62. #include "netdev/netdev.h"
  63. #include "socket/socket.h"
  64. #include "inet/inet.h"
  65. #include "arp/arp.h"
  66. #include "icmpv6/icmpv6.h"
  67. #include "neighbor/neighbor.h"
  68. #include "udp/udp.h"
  69. #include "devif/devif.h"
  70. /****************************************************************************
  71. * Pre-processor Definitions
  72. ****************************************************************************/
  73. /* If both IPv4 and IPv6 support are both enabled, then we will need to build
  74. * in some additional domain selection support.
  75. */
  76. #if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6)
  77. # define NEED_IPDOMAIN_SUPPORT 1
  78. #endif
  79. #define UDPIPv4BUF ((struct udp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
  80. #define UDPIPv6BUF ((struct udp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
  81. /* Debug */
  82. #ifdef CONFIG_NET_UDP_WRBUFFER_DUMP
  83. # define BUF_DUMP(msg,buf,len) lib_dumpbuffer(msg,buf,len)
  84. #else
  85. # define BUF_DUMP(msg,buf,len)
  86. # undef UDP_WBDUMP
  87. # define UDP_WBDUMP(msg,wrb,len,offset)
  88. #endif
  89. /****************************************************************************
  90. * Private Function Prototypes
  91. ****************************************************************************/
  92. #ifdef NEED_IPDOMAIN_SUPPORT
  93. static inline void sendto_ipselect(FAR struct net_driver_s *dev,
  94. FAR struct udp_conn_s *conn);
  95. #endif
  96. #ifdef CONFIG_NET_ETHERNET
  97. static inline bool sendto_addrcheck(FAR struct udp_conn_s *conn,
  98. FAR struct net_driver_s *dev);
  99. #else
  100. # define sendto_addrcheck(c,d) (true)
  101. #endif
  102. #ifdef CONFIG_NET_SOCKOPTS
  103. static inline int sendto_timeout(FAR struct socket *psock,
  104. FAR struct udp_conn_s *conn);
  105. #endif
  106. static int sendto_next_transfer(FAR struct socket *psock,
  107. FAR struct udp_conn_s *conn);
  108. static uint16_t sendto_eventhandler(FAR struct net_driver_s *dev,
  109. FAR void *pvconn, FAR void *pvpriv,
  110. uint16_t flags);
  111. /****************************************************************************
  112. * Private Functions
  113. ****************************************************************************/
  114. /****************************************************************************
  115. * Name: sendto_writebuffer_release
  116. *
  117. * Description:
  118. * Release the write buffer at the head of the write buffer queue.
  119. *
  120. * Input Parameters:
  121. * dev - The structure of the network driver that caused the event
  122. * psock - Socket state structure
  123. *
  124. * Returned Value:
  125. * None
  126. *
  127. * Assumptions:
  128. * The network is locked
  129. *
  130. ****************************************************************************/
  131. static void sendto_writebuffer_release(FAR struct socket *psock,
  132. FAR struct udp_conn_s *conn)
  133. {
  134. FAR struct udp_wrbuffer_s *wrb;
  135. int ret = OK;
  136. do
  137. {
  138. /* Check if the write queue became empty */
  139. if (sq_empty(&conn->write_q))
  140. {
  141. /* Yes.. stifle any further callbacks until more write data is
  142. * enqueued.
  143. */
  144. psock->s_sndcb->flags = 0;
  145. psock->s_sndcb->priv = NULL;
  146. psock->s_sndcb->event = NULL;
  147. wrb = NULL;
  148. }
  149. else
  150. {
  151. /* Remove the write buffer from the head of the write buffer queue
  152. * and release it.
  153. */
  154. wrb = (FAR struct udp_wrbuffer_s *)sq_remfirst(&conn->write_q);
  155. DEBUGASSERT(wrb != NULL);
  156. udp_wrbuffer_release(wrb);
  157. /* Set up for the next packet transfer by setting the connection
  158. * address to the address of the next packet now at the header of
  159. * the write buffer queue.
  160. */
  161. ret = sendto_next_transfer(psock, conn);
  162. }
  163. }
  164. while (wrb != NULL && ret < 0);
  165. }
  166. /****************************************************************************
  167. * Name: sendto_ipselect
  168. *
  169. * Description:
  170. * If both IPv4 and IPv6 support are enabled, then we will need to select
  171. * which one to use when generating the outgoing packet. If only one
  172. * domain is selected, then the setup is already in place and we need do
  173. * nothing.
  174. *
  175. * Input Parameters:
  176. * dev - The structure of the network driver that caused the event
  177. * psock - Socket state structure
  178. *
  179. * Returned Value:
  180. * None
  181. *
  182. * Assumptions:
  183. * The network is locked
  184. *
  185. ****************************************************************************/
  186. #ifdef NEED_IPDOMAIN_SUPPORT
  187. static inline void sendto_ipselect(FAR struct net_driver_s *dev,
  188. FAR struct udp_conn_s *conn)
  189. {
  190. /* Which domain the socket support */
  191. if (conn->domain == PF_INET)
  192. {
  193. /* Select the IPv4 domain */
  194. udp_ipv4_select(dev);
  195. }
  196. else /* if (conn->domain == PF_INET6) */
  197. {
  198. /* Select the IPv6 domain */
  199. DEBUGASSERT(conn->domain == PF_INET6);
  200. udp_ipv6_select(dev);
  201. }
  202. }
  203. #endif
  204. /****************************************************************************
  205. * Name: sendto_addrcheck
  206. *
  207. * Description:
  208. * Check if the destination IP address is in the IPv4 ARP or IPv6 Neighbor
  209. * tables. If not, then the send won't actually make it out... it will be
  210. * replaced with an ARP request (IPv4) or a Neighbor Solicitation (IPv6).
  211. *
  212. * NOTE 1: This could be an expensive check if there are a lot of
  213. * entries in the ARP or Neighbor tables.
  214. *
  215. * NOTE 2: If we are actually harvesting IP addresses on incoming IP
  216. * packets, then this check should not be necessary; the MAC mapping
  217. * should already be in the ARP table in many cases (IPv4 only).
  218. *
  219. * NOTE 3: If CONFIG_NET_ARP_SEND then we can be assured that the IP
  220. * address mapping is already in the ARP table.
  221. *
  222. * Input Parameters:
  223. * conn - The UDP connection structure
  224. * dev - Polling network device
  225. *
  226. * Returned Value:
  227. * true - The Ethernet MAC address is in the ARP or Neighbor table (OR
  228. * the network device is not Ethernet).
  229. *
  230. * Assumptions:
  231. * The network is locked
  232. *
  233. ****************************************************************************/
  234. #ifdef CONFIG_NET_ETHERNET
  235. static inline bool sendto_addrcheck(FAR struct udp_conn_s *conn,
  236. FAR struct net_driver_s *dev)
  237. {
  238. /* REVISIT: Could the MAC address not also be in a routing table? */
  239. if (dev->d_lltype != NET_LL_ETHERNET)
  240. {
  241. return true;
  242. }
  243. #ifdef CONFIG_NET_IPv4
  244. #ifdef CONFIG_NET_IPv6
  245. if (conn->domain == PF_INET)
  246. #endif
  247. {
  248. #if !defined(CONFIG_NET_ARP_IPIN) && !defined(CONFIG_NET_ARP_SEND)
  249. return (arp_find(conn->u.ipv4.raddr, NULL) >= 0);
  250. #else
  251. return true;
  252. #endif
  253. }
  254. #endif /* CONFIG_NET_IPv4 */
  255. #ifdef CONFIG_NET_IPv6
  256. #ifdef CONFIG_NET_IPv4
  257. else
  258. #endif
  259. {
  260. #if !defined(CONFIG_NET_ICMPv6_NEIGHBOR)
  261. return (neighbor_lookup(conn->u.ipv6.raddr, NULL) >= 0);
  262. #else
  263. return true;
  264. #endif
  265. }
  266. #endif /* CONFIG_NET_IPv6 */
  267. }
  268. #endif /* CONFIG_NET_ETHERNET */
  269. /****************************************************************************
  270. * Name: sendto_timeout
  271. *
  272. * Description:
  273. * Check for send timeout.
  274. *
  275. * Input Parameters:
  276. * pstate - sendto state structure
  277. *
  278. * Returned Value:
  279. * TRUE:timeout FALSE:no timeout
  280. *
  281. * Assumptions:
  282. * The network is locked
  283. *
  284. ****************************************************************************/
  285. #ifdef CONFIG_NET_SOCKOPTS
  286. static inline int sendto_timeout(FAR struct socket *psock,
  287. FAR struct udp_conn_s *conn)
  288. {
  289. FAR struct udp_wrbuffer_s *wrb;
  290. /* Peek at the head of the write queue (without altering the write queue). */
  291. wrb = (FAR struct udp_wrbuffer_s *)sq_peek(&conn->write_q);
  292. if (wrb != NULL)
  293. {
  294. /* Check for a timeout configured via setsockopts(SO_SNDTIMEO).
  295. * If none... we well let the send wait forever.
  296. */
  297. if (psock->s_sndtimeo != 0)
  298. {
  299. /* Check if the configured timeout has elapsed */
  300. return net_timeo(wrb->wb_start, psock->s_sndtimeo);
  301. }
  302. }
  303. /* No timeout */
  304. return FALSE;
  305. }
  306. #endif /* CONFIG_NET_SOCKOPTS */
  307. /****************************************************************************
  308. * Name: sendto_next_transfer
  309. *
  310. * Description:
  311. * Setup for the next packet transfer
  312. *
  313. * Input Parameters:
  314. * psock - Socket state structure
  315. * conn - The UDP connection structure
  316. *
  317. * Returned Value:
  318. * None
  319. *
  320. ****************************************************************************/
  321. static int sendto_next_transfer(FAR struct socket *psock,
  322. FAR struct udp_conn_s *conn)
  323. {
  324. FAR struct udp_wrbuffer_s *wrb;
  325. FAR struct net_driver_s *dev;
  326. int ret;
  327. /* Set the UDP "connection" to the destination address of the write buffer
  328. * at the head of the queue.
  329. */
  330. wrb = (FAR struct udp_wrbuffer_s *)sq_peek(&conn->write_q);
  331. if (wrb == NULL)
  332. {
  333. ninfo("Write buffer queue is empty\n");
  334. return -ENOENT;
  335. }
  336. ret = udp_connect(conn, (FAR const struct sockaddr *)&wrb->wb_dest);
  337. if (ret < 0)
  338. {
  339. nerr("ERROR: udp_connect failed: %d\n", ret);
  340. return ret;
  341. }
  342. /* Get the device that will handle the remote packet transfers. This
  343. * should never be NULL.
  344. */
  345. dev = udp_find_raddr_device(conn);
  346. if (dev == NULL)
  347. {
  348. nerr("ERROR: udp_find_raddr_device failed\n");
  349. return -ENETUNREACH;
  350. }
  351. /* Make sure that the device is in the UP state */
  352. if ((dev->d_flags & IFF_UP) == 0)
  353. {
  354. nwarn("WARNING: device is DOWN\n");
  355. return -EHOSTUNREACH;
  356. }
  357. /* If this is not the same device that we used in the last call to
  358. * udp_callback_alloc(), then we need to release and reallocate the old
  359. * callback instance.
  360. */
  361. if (psock->s_sndcb != NULL && conn->dev != dev)
  362. {
  363. udp_callback_free(conn->dev, conn, psock->s_sndcb);
  364. psock->s_sndcb = NULL;
  365. }
  366. /* Allocate resources to receive a callback from this device if the
  367. * callback is not already in place.
  368. */
  369. if (psock->s_sndcb == NULL)
  370. {
  371. psock->s_sndcb = udp_callback_alloc(dev, conn);
  372. }
  373. /* Test if the callback has been allocated */
  374. if (psock->s_sndcb == NULL)
  375. {
  376. /* A buffer allocation error occurred */
  377. nerr("ERROR: Failed to allocate callback\n");
  378. return -ENOMEM;
  379. }
  380. conn->dev = dev;
  381. /* Set up the callback in the connection */
  382. psock->s_sndcb->flags = (UDP_POLL | NETDEV_DOWN);
  383. psock->s_sndcb->priv = (FAR void *)psock;
  384. psock->s_sndcb->event = sendto_eventhandler;
  385. /* Notify the device driver of the availability of TX data */
  386. netdev_txnotify_dev(dev);
  387. return OK;
  388. }
  389. /****************************************************************************
  390. * Name: sendto_eventhandler
  391. *
  392. * Description:
  393. * This function is called to perform the actual send operation when
  394. * polled by the lower, device interfacing layer.
  395. *
  396. * Input Parameters:
  397. * dev The structure of the network driver that caused the event
  398. * conn The connection structure associated with the socket
  399. * flags Set of events describing why the callback was invoked
  400. *
  401. * Returned Value:
  402. * None
  403. *
  404. * Assumptions:
  405. * The network is locked
  406. *
  407. ****************************************************************************/
  408. static uint16_t sendto_eventhandler(FAR struct net_driver_s *dev,
  409. FAR void *pvconn, FAR void *pvpriv,
  410. uint16_t flags)
  411. {
  412. FAR struct udp_conn_s *conn = (FAR struct udp_conn_s *)pvconn;
  413. FAR struct socket *psock = (FAR struct socket *)pvpriv;
  414. ninfo("flags: %04x\n", flags);
  415. /* Check if the network device has gone down */
  416. if ((flags & NETDEV_DOWN) != 0)
  417. {
  418. ninfo("Device down: %04x\n", flags);
  419. /* Free the write buffer at the head of the queue and attempt to setup
  420. * the next transfer.
  421. */
  422. sendto_writebuffer_release(psock, conn);
  423. return flags;
  424. }
  425. /* Check for a normal polling cycle and if the outgoing packet is
  426. * available. It would not be available if it has been claimed by a send
  427. * event serving a different thread -OR- if the output buffer currently
  428. * contains unprocessed incoming data. In these cases we will just have
  429. * to wait for the next polling cycle.
  430. *
  431. * And, of course, we can do nothing if we have no data in the write
  432. * buffers to send.
  433. */
  434. if (dev->d_sndlen <= 0 && (flags & UDP_NEWDATA) == 0 &&
  435. (flags & UDP_POLL) != 0 && !sq_empty(&conn->write_q))
  436. {
  437. /* Check if the destination IP address is in the ARP, Neighbor
  438. * table, or routing table. If not, then the send won't actually
  439. * make it out... it will be replaced with an ARP request or
  440. * Neighbor Solicitation.
  441. */
  442. if (sendto_addrcheck(conn, dev))
  443. {
  444. FAR struct udp_wrbuffer_s *wrb;
  445. size_t sndlen;
  446. /* Peek at the head of the write queue (but don't remove anything
  447. * from the write queue yet). We know from the above test that
  448. * the write_q is not empty.
  449. */
  450. wrb = (FAR struct udp_wrbuffer_s *)sq_peek(&conn->write_q);
  451. DEBUGASSERT(wrb != NULL);
  452. /* Get the amount of data that we can send in the next packet.
  453. * We will send either the remaining data in the buffer I/O
  454. * buffer chain, or as much as will fit given the MSS and current
  455. * window size.
  456. */
  457. sndlen = wrb->wb_iob->io_pktlen;
  458. ninfo("wrb=%p sndlen=%u\n", wrb, sndlen);
  459. #ifdef NEED_IPDOMAIN_SUPPORT
  460. /* If both IPv4 and IPv6 support are enabled, then we will need to
  461. * select which one to use when generating the outgoing packet.
  462. * If only one domain is selected, then the setup is already in
  463. * place and we need do nothing.
  464. */
  465. sendto_ipselect(dev, conn);
  466. #endif
  467. /* Then set-up to send that amount of data with the offset
  468. * corresponding to the size of the IP-dependent address structure.
  469. */
  470. devif_iob_send(dev, wrb->wb_iob, sndlen, 0);
  471. /* Free the write buffer at the head of the queue and attempt to
  472. * setup the next transfer.
  473. */
  474. sendto_writebuffer_release(psock, conn);
  475. /* Only one data can be sent by low level driver at once,
  476. * tell the caller stop polling the other connections.
  477. */
  478. flags &= ~UDP_POLL;
  479. }
  480. }
  481. #ifdef CONFIG_NET_SOCKOPTS
  482. /* We cannot send the data now. Check for a timeout. */
  483. else if (sendto_timeout(psock, conn))
  484. {
  485. /* Free the write buffer at the head of the queue and attempt to setup
  486. * the next transfer.
  487. */
  488. sendto_writebuffer_release(psock, conn);
  489. }
  490. #endif /* CONFIG_NET_SOCKOPTS */
  491. /* Continue waiting */
  492. return flags;
  493. }
  494. /****************************************************************************
  495. * Public Functions
  496. ****************************************************************************/
  497. /****************************************************************************
  498. * Name: psock_udp_sendto
  499. *
  500. * Description:
  501. * This function implements the UDP-specific logic of the standard
  502. * sendto() socket operation.
  503. *
  504. * Input Parameters:
  505. * psock A pointer to a NuttX-specific, internal socket structure
  506. * buf Data to send
  507. * len Length of data to send
  508. * flags Send flags
  509. * to Address of recipient
  510. * tolen The length of the address structure
  511. *
  512. * NOTE: All input parameters were verified by sendto() before this
  513. * function was called.
  514. *
  515. * Returned Value:
  516. * On success, returns the number of characters sent. On error,
  517. * a negated errno value is returned. See the description in
  518. * net/socket/sendto.c for the list of appropriate return value.
  519. *
  520. ****************************************************************************/
  521. ssize_t psock_udp_sendto(FAR struct socket *psock, FAR const void *buf,
  522. size_t len, int flags, FAR const struct sockaddr *to,
  523. socklen_t tolen)
  524. {
  525. FAR struct udp_conn_s *conn;
  526. FAR struct udp_wrbuffer_s *wrb;
  527. int ret = OK;
  528. /* If the UDP socket was previously assigned a remote peer address via
  529. * connect(), then as with connection-mode socket, sendto() may not be
  530. * used with a non-NULL destination address. Normally send() would be
  531. * used with such connected UDP sockets.
  532. */
  533. if (to != NULL && _SS_ISCONNECTED(psock->s_flags))
  534. {
  535. /* EISCONN - A destination address was specified and the socket is
  536. * already connected.
  537. */
  538. return -EISCONN;
  539. }
  540. /* Otherwise, if the socket is not connected, then a destination address
  541. * must be provided.
  542. */
  543. else if (to == NULL && !_SS_ISCONNECTED(psock->s_flags))
  544. {
  545. /* EDESTADDRREQ - The socket is not connection-mode and no peer
  546. * address is set.
  547. */
  548. return -EDESTADDRREQ;
  549. }
  550. /* Get the underlying the UDP connection structure. */
  551. conn = (FAR struct udp_conn_s *)psock->s_conn;
  552. DEBUGASSERT(conn);
  553. #if defined(CONFIG_NET_ARP_SEND) || defined(CONFIG_NET_ICMPv6_NEIGHBOR)
  554. #ifdef CONFIG_NET_ARP_SEND
  555. /* Assure the the IPv4 destination address maps to a valid MAC address in
  556. * the ARP table.
  557. */
  558. #ifdef CONFIG_NET_ICMPv6_NEIGHBOR
  559. if (psock->s_domain == PF_INET)
  560. #endif
  561. {
  562. in_addr_t destipaddr;
  563. /* Check if the socket is connection mode */
  564. if (_SS_ISCONNECTED(psock->s_flags))
  565. {
  566. /* Yes.. use the connected remote address (the 'to' address is
  567. * null).
  568. */
  569. destipaddr = conn->u.ipv4.raddr;
  570. }
  571. else
  572. {
  573. FAR const struct sockaddr_in *into;
  574. /* No.. use the destination address provided by the non-NULL 'to'
  575. * argument.
  576. */
  577. into = (FAR const struct sockaddr_in *)to;
  578. destipaddr = into->sin_addr.s_addr;
  579. }
  580. /* Make sure that the IP address mapping is in the ARP table */
  581. ret = arp_send(destipaddr);
  582. }
  583. #endif /* CONFIG_NET_ARP_SEND */
  584. #ifdef CONFIG_NET_ICMPv6_NEIGHBOR
  585. /* Assure the the IPv6 destination address maps to a valid MAC address in
  586. * the neighbor table.
  587. */
  588. #ifdef CONFIG_NET_ARP_SEND
  589. else
  590. #endif
  591. {
  592. FAR const uint16_t *destipaddr;
  593. /* Check if the socket is connection mode */
  594. if (_SS_ISCONNECTED(psock->s_flags))
  595. {
  596. /* Yes.. use the connected remote address (the 'to' address is
  597. * null).
  598. */
  599. destipaddr = conn->u.ipv6.raddr;
  600. }
  601. else
  602. {
  603. FAR const struct sockaddr_in6 *into;
  604. /* No.. use the destination address provided by the non-NULL 'to'
  605. * argument.
  606. */
  607. into = (FAR const struct sockaddr_in6 *)to;
  608. destipaddr = into->sin6_addr.s6_addr16;
  609. }
  610. /* Make sure that the IP address mapping is in the Neighbor Table */
  611. ret = icmpv6_neighbor(destipaddr);
  612. }
  613. #endif /* CONFIG_NET_ICMPv6_NEIGHBOR */
  614. /* Did we successfully get the address mapping? */
  615. if (ret < 0)
  616. {
  617. nerr("ERROR: Not reachable\n");
  618. return -ENETUNREACH;
  619. }
  620. #endif /* CONFIG_NET_ARP_SEND || CONFIG_NET_ICMPv6_NEIGHBOR */
  621. /* Dump the incoming buffer */
  622. BUF_DUMP("psock_udp_send", buf, len);
  623. /* Set the socket state to sending */
  624. psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND);
  625. if (len > 0)
  626. {
  627. /* Allocate a write buffer. Careful, the network will be momentarily
  628. * unlocked here.
  629. */
  630. net_lock();
  631. wrb = udp_wrbuffer_alloc();
  632. if (wrb == NULL)
  633. {
  634. /* A buffer allocation error occurred */
  635. nerr("ERROR: Failed to allocate write buffer\n");
  636. ret = -ENOMEM;
  637. goto errout_with_lock;
  638. }
  639. /* Initialize the write buffer */
  640. /* Check if the socket is connected */
  641. if (_SS_ISCONNECTED(psock->s_flags))
  642. {
  643. /* Yes.. get the connection address from the connection structure */
  644. #ifdef CONFIG_NET_IPv4
  645. #ifdef CONFIG_NET_IPv6
  646. if (conn->domain == PF_INET)
  647. #endif
  648. {
  649. FAR struct sockaddr_in *addr4 =
  650. (FAR struct sockaddr_in *)&wrb->wb_dest;
  651. addr4->sin_family = AF_INET;
  652. addr4->sin_port = conn->rport;
  653. net_ipv4addr_copy(addr4->sin_addr.s_addr, conn->u.ipv4.raddr);
  654. }
  655. #endif /* CONFIG_NET_IPv4 */
  656. #ifdef CONFIG_NET_IPv6
  657. #ifdef CONFIG_NET_IPv4
  658. else
  659. #endif
  660. {
  661. FAR struct sockaddr_in6 *addr6 =
  662. (FAR struct sockaddr_in6 *)&wrb->wb_dest;
  663. addr6->sin6_family = AF_INET6;
  664. addr6->sin6_port = conn->rport;
  665. net_ipv6addr_copy(addr6->sin6_addr.s6_addr, conn->u.ipv6.raddr);
  666. }
  667. #endif /* CONFIG_NET_IPv6 */
  668. }
  669. /* Not connected. Use the provided destination address */
  670. else
  671. {
  672. memcpy(&wrb->wb_dest, to, tolen);
  673. }
  674. #ifdef CONFIG_NET_SOCKOPTS
  675. wrb->wb_start = clock_systimer();
  676. #endif
  677. /* Copy the user data into the write buffer. We cannot wait for
  678. * buffer space if the socket was opened non-blocking.
  679. */
  680. if (_SS_ISNONBLOCK(psock->s_flags))
  681. {
  682. ret = iob_trycopyin(wrb->wb_iob, (FAR uint8_t *)buf, len, 0, false);
  683. }
  684. else
  685. {
  686. ret = iob_copyin(wrb->wb_iob, (FAR uint8_t *)buf, len, 0, false);
  687. }
  688. if (ret < 0)
  689. {
  690. goto errout_with_wrb;
  691. }
  692. /* Dump I/O buffer chain */
  693. UDP_WBDUMP("I/O buffer chain", wrb, wrb->wb_iob->io_pktlen, 0);
  694. /* sendto_eventhandler() will send data in FIFO order from the
  695. * conn->write_q.
  696. *
  697. * REVISIT: Why FIFO order? Because it is easy. In a real world
  698. * environment where there are multiple network devices this might
  699. * be inefficient because we could be sending data to different
  700. * device out-of-queued-order to optimize performance. Sending
  701. * data to different networks from a single UDP socket is probably
  702. * not a very common use case, however.
  703. */
  704. sq_addlast(&wrb->wb_node, &conn->write_q);
  705. ninfo("Queued WRB=%p pktlen=%u write_q(%p,%p)\n",
  706. wrb, wrb->wb_iob->io_pktlen,
  707. conn->write_q.head, conn->write_q.tail);
  708. /* Set up for the next packet transfer by setting the connection
  709. * address to the address of the next packet now at the header of the
  710. * write buffer queue.
  711. */
  712. ret = sendto_next_transfer(psock, conn);
  713. if (ret < 0)
  714. {
  715. (void)sq_remlast(&conn->write_q);
  716. goto errout_with_wrb;
  717. }
  718. net_unlock();
  719. }
  720. /* Set the socket state to idle */
  721. psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
  722. /* Return the number of bytes that will be sent */
  723. return len;
  724. errout_with_wrb:
  725. udp_wrbuffer_release(wrb);
  726. errout_with_lock:
  727. net_unlock();
  728. return ret;
  729. }
  730. /****************************************************************************
  731. * Name: psock_udp_cansend
  732. *
  733. * Description:
  734. * psock_udp_cansend() returns a value indicating if a write to the socket
  735. * would block. No space in the buffer is actually reserved, so it is
  736. * possible that the write may still block if the buffer is filled by
  737. * another means.
  738. *
  739. * Input Parameters:
  740. * psock An instance of the internal socket structure.
  741. *
  742. * Returned Value:
  743. * OK
  744. * At least one byte of data could be successfully written.
  745. * -EWOULDBLOCK
  746. * There is no room in the output buffer.
  747. * -EBADF
  748. * An invalid descriptor was specified.
  749. *
  750. ****************************************************************************/
  751. int psock_udp_cansend(FAR struct socket *psock)
  752. {
  753. /* Verify that we received a valid socket */
  754. if (!psock || psock->s_crefs <= 0)
  755. {
  756. nerr("ERROR: Invalid socket\n");
  757. return -EBADF;
  758. }
  759. /* In order to setup the send, we need to have at least one free write
  760. * buffer head and at least one free IOB to initialize the write buffer head.
  761. *
  762. * REVISIT: The send will still block if we are unable to buffer the entire
  763. * user-provided buffer which may be quite large. We will almost certainly
  764. * need to have more than one free IOB, but we don't know how many more.
  765. */
  766. if (udp_wrbuffer_test() < 0 || iob_navail(false) <= 0)
  767. {
  768. return -EWOULDBLOCK;
  769. }
  770. return OK;
  771. }
  772. #endif /* CONFIG_NET && CONFIG_NET_UDP && CONFIG_NET_UDP_WRITE_BUFFERS */