tcp_sendfile.c 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741
  1. /****************************************************************************
  2. * net/tcp/tcp_sendfile.c
  3. *
  4. * Copyright (C) 2013 UVC Ingenieure. All rights reserved.
  5. * Copyright (C) 2007-2017 Gregory Nutt. All rights reserved.
  6. * Authors: Gregory Nutt <gnutt@nuttx.org>
  7. * Max Holtzberg <mh@uvc.de>
  8. *
  9. * Redistribution and use in source and binary forms, with or without
  10. * modification, are permitted provided that the following conditions
  11. * are met:
  12. *
  13. * 1. Redistributions of source code must retain the above copyright
  14. * notice, this list of conditions and the following disclaimer.
  15. * 2. Redistributions in binary form must reproduce the above copyright
  16. * notice, this list of conditions and the following disclaimer in
  17. * the documentation and/or other materials provided with the
  18. * distribution.
  19. * 3. Neither the name NuttX nor the names of its contributors may be
  20. * used to endorse or promote products derived from this software
  21. * without specific prior written permission.
  22. *
  23. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  24. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  25. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  26. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  27. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  28. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  29. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  30. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  31. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  32. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  33. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  34. * POSSIBILITY OF SUCH DAMAGE.
  35. *
  36. ****************************************************************************/
  37. /****************************************************************************
  38. * Included Files
  39. ****************************************************************************/
  40. #include <nuttx/config.h>
  41. #include <sys/stat.h>
  42. #include <sys/types.h>
  43. #include <sys/socket.h>
  44. #include <fcntl.h>
  45. #include <stdint.h>
  46. #include <stdbool.h>
  47. #include <stdlib.h>
  48. #include <string.h>
  49. #include <unistd.h>
  50. #include <errno.h>
  51. #include <debug.h>
  52. #include <arch/irq.h>
  53. #include <nuttx/clock.h>
  54. #include <nuttx/semaphore.h>
  55. #include <nuttx/fs/fs.h>
  56. #include <nuttx/net/net.h>
  57. #include <nuttx/net/netdev.h>
  58. #include <nuttx/net/arp.h>
  59. #include <nuttx/net/tcp.h>
  60. #include "netdev/netdev.h"
  61. #include "devif/devif.h"
  62. #include "arp/arp.h"
  63. #include "icmpv6/icmpv6.h"
  64. #include "neighbor/neighbor.h"
  65. #include "socket/socket.h"
  66. #include "tcp/tcp.h"
  67. #if defined(CONFIG_NET_SENDFILE) && defined(CONFIG_NET_TCP) && \
  68. defined(NET_TCP_HAVE_STACK)
  69. /****************************************************************************
  70. * Pre-processor Definitions
  71. ****************************************************************************/
  72. #if defined(CONFIG_NET_TCP_SPLIT) && !defined(CONFIG_NET_TCP_SPLIT_SIZE)
  73. # define CONFIG_NET_TCP_SPLIT_SIZE 40
  74. #endif
  75. #define TCPIPv4BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
  76. #define TCPIPv6BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
  77. /****************************************************************************
  78. * Private Types
  79. ****************************************************************************/
  80. /* This structure holds the state of the send operation until it can be
  81. * operated upon from the driver poll event.
  82. */
  83. struct sendfile_s
  84. {
  85. FAR struct socket *snd_sock; /* Points to the parent socket structure */
  86. FAR struct devif_callback_s *snd_datacb; /* Data callback */
  87. FAR struct devif_callback_s *snd_ackcb; /* ACK callback */
  88. FAR struct file *snd_file; /* File structure of the input file */
  89. sem_t snd_sem; /* Used to wake up the waiting thread */
  90. off_t snd_foffset; /* Input file offset */
  91. size_t snd_flen; /* File length */
  92. ssize_t snd_sent; /* The number of bytes sent */
  93. uint32_t snd_isn; /* Initial sequence number */
  94. uint32_t snd_acked; /* The number of bytes acked */
  95. #ifdef CONFIG_NET_SOCKOPTS
  96. clock_t snd_time; /* Last send time for determining timeout */
  97. #endif
  98. };
  99. /****************************************************************************
  100. * Private Functions
  101. ****************************************************************************/
  102. /****************************************************************************
  103. * Name: sendfile_timeout
  104. *
  105. * Description:
  106. * Check for send timeout.
  107. *
  108. * Input Parameters:
  109. * pstate - send state structure
  110. *
  111. * Returned Value:
  112. * TRUE:timeout FALSE:no timeout
  113. *
  114. * Assumptions:
  115. * The network is locked
  116. *
  117. ****************************************************************************/
  118. #ifdef CONFIG_NET_SOCKOPTS
  119. static inline int sendfile_timeout(FAR struct sendfile_s *pstate)
  120. {
  121. FAR struct socket *psock = 0;
  122. /* Check for a timeout configured via setsockopts(SO_SNDTIMEO).
  123. * If none... we well let the send wait forever.
  124. */
  125. psock = pstate->snd_sock;
  126. if (psock && psock->s_sndtimeo != 0)
  127. {
  128. /* Check if the configured timeout has elapsed */
  129. return net_timeo(pstate->snd_time, psock->s_sndtimeo);
  130. }
  131. /* No timeout */
  132. return FALSE;
  133. }
  134. #endif /* CONFIG_NET_SOCKOPTS */
  135. static uint16_t ack_eventhandler(FAR struct net_driver_s *dev,
  136. FAR void *pvconn,
  137. FAR void *pvpriv, uint16_t flags)
  138. {
  139. FAR struct sendfile_s *pstate = (FAR struct sendfile_s *)pvpriv;
  140. ninfo("flags: %04x\n", flags);
  141. if ((flags & TCP_ACKDATA) != 0)
  142. {
  143. FAR struct tcp_hdr_s *tcp;
  144. #ifdef CONFIG_NET_SOCKOPTS
  145. /* Update the timeout */
  146. pstate->snd_time = clock_systimer();
  147. #endif
  148. /* Get the offset address of the TCP header */
  149. #ifdef CONFIG_NET_IPv6
  150. #ifdef CONFIG_NET_IPv4
  151. if (IFF_IS_IPv6(dev->d_flags))
  152. #endif
  153. {
  154. DEBUGASSERT(pstate->snd_sock == PF_INET6);
  155. tcp = TCPIPv6BUF;
  156. }
  157. #endif /* CONFIG_NET_IPv6 */
  158. #ifdef CONFIG_NET_IPv4
  159. #ifdef CONFIG_NET_IPv6
  160. else
  161. #endif
  162. {
  163. DEBUGASSERT(pstate->snd_sock == PF_INET);
  164. tcp = TCPIPv4BUF;
  165. }
  166. #endif /* CONFIG_NET_IPv4 */
  167. /* The current acknowledgement number number is the (relative) offset
  168. * of the of the next byte needed by the receiver. The snd_isn is the
  169. * offset of the first byte to send to the receiver. The difference
  170. * is the number of bytes to be acknowledged.
  171. */
  172. pstate->snd_acked = tcp_getsequence(tcp->ackno) - pstate->snd_isn;
  173. ninfo("ACK: acked=%d sent=%d flen=%d\n",
  174. pstate->snd_acked, pstate->snd_sent, pstate->snd_flen);
  175. dev->d_sndlen = 0;
  176. flags &= ~TCP_ACKDATA;
  177. }
  178. else if ((flags & TCP_REXMIT) != 0)
  179. {
  180. nwarn("WARNING: TCP_REXMIT\n");
  181. /* Yes.. in this case, reset the number of bytes that have been sent
  182. * to the number of bytes that have been ACKed.
  183. */
  184. pstate->snd_sent = pstate->snd_acked;
  185. }
  186. /* Check for a loss of connection */
  187. else if ((flags & TCP_DISCONN_EVENTS) != 0)
  188. {
  189. FAR struct socket *psock = pstate->snd_sock;
  190. nwarn("WARNING: Lost connection\n");
  191. /* We could get here recursively through the callback actions of
  192. * tcp_lost_connection(). So don't repeat that action if we have
  193. * already been disconnected.
  194. */
  195. DEBUGASSERT(psock != NULL);
  196. if (_SS_ISCONNECTED(psock->s_flags))
  197. {
  198. /* Report not connected */
  199. tcp_lost_connection(psock, pstate->snd_ackcb, flags);
  200. }
  201. /* Report not connected */
  202. pstate->snd_sent = -ENOTCONN;
  203. }
  204. /* Prohibit further callbacks */
  205. pstate->snd_ackcb->flags = 0;
  206. pstate->snd_ackcb->priv = NULL;
  207. pstate->snd_ackcb->event = NULL;
  208. /* Wake up the waiting thread */
  209. nxsem_post(&pstate->snd_sem);
  210. return flags;
  211. }
  212. /****************************************************************************
  213. * Name: sendfile_addrcheck
  214. *
  215. * Description:
  216. * Check if the destination IP address is in the IPv4 ARP or IPv6 Neighbor
  217. * tables. If not, then the send won't actually make it out... it will be
  218. * replaced with an ARP request (IPv4) or a Neighbor Solicitation (IPv6).
  219. *
  220. * NOTE 1: This could be an expensive check if there are a lot of
  221. * entries in the ARP or Neighbor tables.
  222. *
  223. * NOTE 2: If we are actually harvesting IP addresses on incoming IP
  224. * packets, then this check should not be necessary; the MAC mapping
  225. * should already be in the ARP table in many cases (IPv4 only).
  226. *
  227. * NOTE 3: If CONFIG_NET_ARP_SEND then we can be assured that the IP
  228. * address mapping is already in the ARP table.
  229. *
  230. * Input Parameters:
  231. * conn - The TCP connection structure
  232. *
  233. * Returned Value:
  234. * None
  235. *
  236. * Assumptions:
  237. * The network is locked
  238. *
  239. ****************************************************************************/
  240. #ifdef CONFIG_NET_ETHERNET
  241. static inline bool sendfile_addrcheck(FAR struct tcp_conn_s *conn)
  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. #else /* CONFIG_NET_ETHERNET */
  269. # sendfile_addrcheck(r) (true)
  270. #endif /* CONFIG_NET_ETHERNET */
  271. /****************************************************************************
  272. * Name: sendfile_eventhandler
  273. *
  274. * Description:
  275. * This function is called to perform the actual send operation when
  276. * polled by the lower, device interfacing layer.
  277. *
  278. * Input Parameters:
  279. * dev The structure of the network driver that caused the event
  280. * conn The connection structure associated with the socket
  281. * flags Set of events describing why the callback was invoked
  282. *
  283. * Returned Value:
  284. * None
  285. *
  286. * Assumptions:
  287. * The network is locked
  288. *
  289. ****************************************************************************/
  290. static uint16_t sendfile_eventhandler(FAR struct net_driver_s *dev,
  291. FAR void *pvconn, FAR void *pvpriv,
  292. uint16_t flags)
  293. {
  294. FAR struct tcp_conn_s *conn = (FAR struct tcp_conn_s *)pvconn;
  295. FAR struct sendfile_s *pstate = (FAR struct sendfile_s *)pvpriv;
  296. int ret;
  297. /* The TCP socket is connected and, hence, should be bound to a device.
  298. * Make sure that the polling device is the own that we are bound to.
  299. */
  300. DEBUGASSERT(conn->dev != NULL);
  301. if (dev != conn->dev)
  302. {
  303. return flags;
  304. }
  305. ninfo("flags: %04x acked: %d sent: %d\n",
  306. flags, pstate->snd_acked, pstate->snd_sent);
  307. /* Check for a loss of connection */
  308. if ((flags & TCP_DISCONN_EVENTS) != 0)
  309. {
  310. FAR struct socket *psock = pstate->snd_sock;
  311. nwarn("WARNING: Lost connection\n");
  312. /* We could get here recursively through the callback actions of
  313. * tcp_lost_connection(). So don't repeat that action if we have
  314. * already been disconnected.
  315. */
  316. DEBUGASSERT(psock != NULL);
  317. if (_SS_ISCONNECTED(psock->s_flags))
  318. {
  319. /* Report not connected */
  320. tcp_lost_connection(psock, pstate->snd_datacb, flags);
  321. }
  322. /* Report not connected */
  323. pstate->snd_sent = -ENOTCONN;
  324. goto end_wait;
  325. }
  326. /* We get here if (1) not all of the data has been ACKed, (2) we have been
  327. * asked to retransmit data, (3) the connection is still healthy, and (4)
  328. * the outgoing packet is available for our use. In this case, we are
  329. * now free to send more data to receiver -- UNLESS the buffer contains
  330. * unprocessing incoming data. In that event, we will have to wait for the
  331. * next polling cycle.
  332. */
  333. if ((flags & TCP_NEWDATA) == 0 && pstate->snd_sent < pstate->snd_flen)
  334. {
  335. /* Get the amount of data that we can send in the next packet */
  336. uint32_t sndlen = pstate->snd_flen - pstate->snd_sent;
  337. if (sndlen > conn->mss)
  338. {
  339. sndlen = conn->mss;
  340. }
  341. /* Check if we have "space" in the window */
  342. if ((pstate->snd_sent - pstate->snd_acked + sndlen) < conn->winsize)
  343. {
  344. uint32_t seqno;
  345. /* Then set-up to send that amount of data. (this won't actually
  346. * happen until the polling cycle completes).
  347. */
  348. ret = file_seek(pstate->snd_file,
  349. pstate->snd_foffset + pstate->snd_sent, SEEK_SET);
  350. if (ret < 0)
  351. {
  352. nerr("ERROR: Failed to lseek: %d\n", ret);
  353. pstate->snd_sent = ret;
  354. goto end_wait;
  355. }
  356. ret = file_read(pstate->snd_file, dev->d_appdata, sndlen);
  357. if (ret < 0)
  358. {
  359. nerr("ERROR: Failed to read from input file: %d\n", (int)ret);
  360. pstate->snd_sent = ret;
  361. goto end_wait;
  362. }
  363. dev->d_sndlen = sndlen;
  364. /* Set the sequence number for this packet. NOTE: The network
  365. * updates sndseq on recept of ACK *before* this function is
  366. * called. In that case sndseq will point to the next
  367. * unacknowledge byte (which might have already been sent). We
  368. * will overwrite the value of sndseq here before the packet is
  369. * sent.
  370. */
  371. seqno = pstate->snd_sent + pstate->snd_isn;
  372. ninfo("SEND: sndseq %08x->%08x len: %d\n",
  373. conn->sndseq, seqno, ret);
  374. tcp_setsequence(conn->sndseq, seqno);
  375. /* Check if the destination IP address is in the ARP or Neighbor
  376. * table. If not, then the send won't actually make it out... it
  377. * will be replaced with an ARP request or Neighbor Solicitation.
  378. */
  379. if (pstate->snd_sent != 0 || sendfile_addrcheck(conn))
  380. {
  381. /* Update the amount of data sent (but not necessarily ACKed) */
  382. pstate->snd_sent += sndlen;
  383. ninfo("pid: %d SEND: acked=%d sent=%d flen=%d\n", getpid(),
  384. pstate->snd_acked, pstate->snd_sent, pstate->snd_flen);
  385. }
  386. }
  387. else
  388. {
  389. nwarn("WARNING: Window full, wait for ack\n");
  390. goto wait;
  391. }
  392. }
  393. #ifdef CONFIG_NET_SOCKOPTS
  394. /* All data has been send and we are just waiting for ACK or re-transmit
  395. * indications to complete the send. Check for a timeout.
  396. */
  397. if (sendfile_timeout(pstate))
  398. {
  399. /* Yes.. report the timeout */
  400. nwarn("WARNING: SEND timeout\n");
  401. pstate->snd_sent = -ETIMEDOUT;
  402. goto end_wait;
  403. }
  404. #endif /* CONFIG_NET_SOCKOPTS */
  405. if (pstate->snd_sent >= pstate->snd_flen
  406. && pstate->snd_acked < pstate->snd_flen)
  407. {
  408. /* All data has been sent, but there are outstanding ACK's */
  409. goto wait;
  410. }
  411. end_wait:
  412. /* Do not allow any further callbacks */
  413. pstate->snd_datacb->flags = 0;
  414. pstate->snd_datacb->priv = NULL;
  415. pstate->snd_datacb->event = NULL;
  416. /* Wake up the waiting thread */
  417. nxsem_post(&pstate->snd_sem);
  418. wait:
  419. return flags;
  420. }
  421. /****************************************************************************
  422. * Name: sendfile_txnotify
  423. *
  424. * Description:
  425. * Notify the appropriate device driver that we are have data ready to
  426. * be send (TCP)
  427. *
  428. * Input Parameters:
  429. * psock - Socket state structure
  430. * conn - The TCP connection structure
  431. *
  432. * Returned Value:
  433. * None
  434. *
  435. ****************************************************************************/
  436. static inline void sendfile_txnotify(FAR struct socket *psock,
  437. FAR struct tcp_conn_s *conn)
  438. {
  439. #ifdef CONFIG_NET_IPv4
  440. #ifdef CONFIG_NET_IPv6
  441. /* If both IPv4 and IPv6 support are enabled, then we will need to select
  442. * the device driver using the appropriate IP domain.
  443. */
  444. if (psock->s_domain == PF_INET)
  445. #endif
  446. {
  447. /* Notify the device driver that send data is available */
  448. netdev_ipv4_txnotify(conn->u.ipv4.laddr, conn->u.ipv4.raddr);
  449. }
  450. #endif /* CONFIG_NET_IPv4 */
  451. #ifdef CONFIG_NET_IPv6
  452. #ifdef CONFIG_NET_IPv4
  453. else /* if (psock->s_domain == PF_INET6) */
  454. #endif /* CONFIG_NET_IPv4 */
  455. {
  456. /* Notify the device driver that send data is available */
  457. DEBUGASSERT(psock->s_domain == PF_INET6);
  458. netdev_ipv6_txnotify(conn->u.ipv6.laddr, conn->u.ipv6.raddr);
  459. }
  460. #endif /* CONFIG_NET_IPv6 */
  461. }
  462. /****************************************************************************
  463. * Public Functions
  464. ****************************************************************************/
  465. /****************************************************************************
  466. * Name: tcp_sendfile
  467. *
  468. * Description:
  469. * The tcp_sendfile() call may be used only when the INET socket is in a
  470. * connected state (so that the intended recipient is known).
  471. *
  472. * Input Parameters:
  473. * psock An instance of the internal socket structure.
  474. * buf Data to send
  475. * len Length of data to send
  476. * flags Send flags
  477. *
  478. * Returned Value:
  479. * On success, returns the number of characters sent. On error,
  480. * a negated errno value is returned. See sendfile() for a list
  481. * appropriate error return values.
  482. *
  483. ****************************************************************************/
  484. ssize_t tcp_sendfile(FAR struct socket *psock, FAR struct file *infile,
  485. FAR off_t *offset, size_t count)
  486. {
  487. FAR struct tcp_conn_s *conn;
  488. struct sendfile_s state;
  489. int ret;
  490. /* If this is an un-connected socket, then return ENOTCONN */
  491. if (psock->s_type != SOCK_STREAM || !_SS_ISCONNECTED(psock->s_flags))
  492. {
  493. nerr("ERROR: Not connected\n");
  494. return -ENOTCONN;
  495. }
  496. /* Make sure that we have the IP address mapping */
  497. conn = (FAR struct tcp_conn_s *)psock->s_conn;
  498. DEBUGASSERT(conn != NULL);
  499. #if defined(CONFIG_NET_ARP_SEND) || defined(CONFIG_NET_ICMPv6_NEIGHBOR)
  500. #ifdef CONFIG_NET_ARP_SEND
  501. #ifdef CONFIG_NET_ICMPv6_NEIGHBOR
  502. if (psock->s_domain == PF_INET)
  503. #endif
  504. {
  505. /* Make sure that the IP address mapping is in the ARP table */
  506. ret = arp_send(conn->u.ipv4.raddr);
  507. }
  508. #endif /* CONFIG_NET_ARP_SEND */
  509. #ifdef CONFIG_NET_ICMPv6_NEIGHBOR
  510. #ifdef CONFIG_NET_ARP_SEND
  511. else
  512. #endif
  513. {
  514. /* Make sure that the IP address mapping is in the Neighbor Table */
  515. ret = icmpv6_neighbor(conn->u.ipv6.raddr);
  516. }
  517. #endif /* CONFIG_NET_ICMPv6_NEIGHBOR */
  518. /* Did we successfully get the address mapping? */
  519. if (ret < 0)
  520. {
  521. nerr("ERROR: Not reachable\n");
  522. return -ENETUNREACH;
  523. }
  524. #endif /* CONFIG_NET_ARP_SEND || CONFIG_NET_ICMPv6_NEIGHBOR */
  525. /* Set the socket state to sending */
  526. psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND);
  527. /* Initialize the state structure. This is done with the network
  528. * locked because we don't want anything to happen until we are
  529. * ready.
  530. */
  531. net_lock();
  532. memset(&state, 0, sizeof(struct sendfile_s));
  533. /* This semaphore is used for signaling and, hence, should not have
  534. * priority inheritance enabled.
  535. */
  536. nxsem_init(&state.snd_sem, 0, 0); /* Doesn't really fail */
  537. nxsem_setprotocol(&state.snd_sem, SEM_PRIO_NONE);
  538. state.snd_sock = psock; /* Socket descriptor to use */
  539. state.snd_foffset = offset ? *offset : 0; /* Input file offset */
  540. state.snd_flen = count; /* Number of bytes to send */
  541. state.snd_file = infile; /* File to read from */
  542. /* Allocate resources to receive a callback */
  543. state.snd_datacb = tcp_callback_alloc(conn);
  544. if (state.snd_datacb == NULL)
  545. {
  546. nerr("ERROR: Failed to allocate data callback\n");
  547. ret = -ENOMEM;
  548. goto errout_locked;
  549. }
  550. state.snd_ackcb = tcp_callback_alloc(conn);
  551. if (state.snd_ackcb == NULL)
  552. {
  553. nerr("ERROR: Failed to allocate ack callback\n");
  554. ret = -ENOMEM;
  555. goto errout_datacb;
  556. }
  557. /* Get the initial sequence number that will be used */
  558. state.snd_isn = tcp_getsequence(conn->sndseq);
  559. /* There is no outstanding, unacknowledged data after this
  560. * initial sequence number.
  561. */
  562. conn->unacked = 0;
  563. #ifdef CONFIG_NET_SOCKOPTS
  564. /* Set the initial time for calculating timeouts */
  565. state.snd_time = clock_systimer();
  566. #endif
  567. /* Set up the ACK callback in the connection */
  568. state.snd_ackcb->flags = (TCP_ACKDATA | TCP_REXMIT | TCP_DISCONN_EVENTS);
  569. state.snd_ackcb->priv = (FAR void *)&state;
  570. state.snd_ackcb->event = ack_eventhandler;
  571. /* Perform the TCP send operation */
  572. do
  573. {
  574. state.snd_datacb->flags = TCP_POLL;
  575. state.snd_datacb->priv = (FAR void *)&state;
  576. state.snd_datacb->event = sendfile_eventhandler;
  577. /* Notify the device driver of the availability of TX data */
  578. sendfile_txnotify(psock, conn);
  579. net_lockedwait(&state.snd_sem);
  580. }
  581. while (state.snd_sent >= 0 && state.snd_acked < state.snd_flen);
  582. /* Set the socket state to idle */
  583. psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
  584. tcp_callback_free(conn, state.snd_ackcb);
  585. errout_datacb:
  586. tcp_callback_free(conn, state.snd_datacb);
  587. errout_locked:
  588. nxsem_destroy(&state. snd_sem);
  589. net_unlock();
  590. if (ret < 0)
  591. {
  592. return ret;
  593. }
  594. else
  595. {
  596. return state.snd_sent;
  597. }
  598. }
  599. #endif /* CONFIG_NET_SENDFILE && CONFIG_NET_TCP && NET_TCP_HAVE_STACK */