lib_sendfile.c 9.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289
  1. /****************************************************************************
  2. * libs/libc/misc/lib_sendfile.c
  3. *
  4. * Copyright (C) 2007, 2009, 2011, 2013 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. #include <sys/sendfile.h>
  40. #include <stdbool.h>
  41. #include <stdlib.h>
  42. #include <unistd.h>
  43. #include <errno.h>
  44. #include <nuttx/fs/fs.h>
  45. #include "libc.h"
  46. /****************************************************************************
  47. * Public Functions
  48. ****************************************************************************/
  49. /****************************************************************************
  50. * Name: sendfile / lib_sendfile
  51. *
  52. * Description:
  53. * sendfile() copies data between one file descriptor and another.
  54. * sendfile() basically just wraps a sequence of reads() and writes()
  55. * to perform a copy. It serves a purpose in systems where there is
  56. * a penalty for copies to between user and kernal space, but really
  57. * nothing in NuttX but provide some Linux compatible (and adding
  58. * another 'almost standard' interface).
  59. *
  60. * NOTE: This interface is *not* specified in POSIX.1-2001, or other
  61. * standards. The implementation here is very similar to the Linux
  62. * sendfile interface. Other UNIX systems implement sendfile() with
  63. * different semantics and prototypes. sendfile() should not be used
  64. * in portable programs.
  65. *
  66. * Input Parameters:
  67. * infd - A file (or socket) descriptor opened for reading
  68. * outfd - A descriptor opened for writing.
  69. * offset - If 'offset' is not NULL, then it points to a variable
  70. * holding the file offset from which sendfile() will start
  71. * reading data from 'infd'. When sendfile() returns, this
  72. * variable will be set to the offset of the byte following
  73. * the last byte that was read. If 'offset' is not NULL,
  74. * then sendfile() does not modify the current file offset of
  75. * 'infd'; otherwise the current file offset is adjusted to
  76. * reflect the number of bytes read from 'infd.'
  77. *
  78. * If 'offset' is NULL, then data will be read from 'infd'
  79. * starting at the current file offset, and the file offset
  80. * will be updated by the call.
  81. * count - The number of bytes to copy between the file descriptors.
  82. *
  83. * Returned Value:
  84. * If the transfer was successful, the number of bytes written to outfd is
  85. * returned. On error, -1 is returned, and errno is set appropriately.
  86. * There error values are those returned by read() or write() plus:
  87. *
  88. * EINVAL - Bad input parameters.
  89. * ENOMEM - Could not allocated an I/O buffer
  90. *
  91. ****************************************************************************/
  92. #ifdef CONFIG_NET_SENDFILE
  93. ssize_t lib_sendfile(int outfd, int infd, off_t *offset, size_t count)
  94. #else
  95. ssize_t sendfile(int outfd, int infd, off_t *offset, size_t count)
  96. #endif
  97. {
  98. FAR uint8_t *iobuffer;
  99. FAR uint8_t *wrbuffer;
  100. off_t startpos = 0;
  101. ssize_t nbytesread;
  102. ssize_t nbyteswritten;
  103. size_t ntransferred;
  104. bool endxfr;
  105. /* Get the current file position. */
  106. if (offset)
  107. {
  108. /* Use lseek to get the current file position */
  109. startpos = lseek(infd, 0, SEEK_CUR);
  110. if (startpos == (off_t)-1)
  111. {
  112. return ERROR;
  113. }
  114. /* Use lseek again to set the new file position */
  115. if (lseek(infd, *offset, SEEK_SET) == (off_t)-1)
  116. {
  117. return ERROR;
  118. }
  119. }
  120. /* Allocate an I/O buffer */
  121. iobuffer = (FAR void *)lib_malloc(CONFIG_LIB_SENDFILE_BUFSIZE);
  122. if (!iobuffer)
  123. {
  124. set_errno(ENOMEM);
  125. return ERROR;
  126. }
  127. /* Now transfer 'count' bytes from the infd to the outfd */
  128. for (ntransferred = 0, endxfr = false; ntransferred < count && !endxfr; )
  129. {
  130. /* Loop until the read side of the transfer comes to some conclusion */
  131. do
  132. {
  133. /* Read a buffer of data from the infd */
  134. nbytesread = _NX_READ(infd, iobuffer, CONFIG_LIB_SENDFILE_BUFSIZE);
  135. /* Check for end of file */
  136. if (nbytesread == 0)
  137. {
  138. /* End of file. Break out and return current number of bytes
  139. * transferred.
  140. */
  141. endxfr = true;
  142. break;
  143. }
  144. /* Check for a read ERROR. EINTR is a special case. This function
  145. * should break out and return an error if EINTR is returned and
  146. * no data has been transferred. But what should it do if some
  147. * data has been transferred? I suppose just continue?
  148. */
  149. else if (nbytesread < 0)
  150. {
  151. int errcode = _NX_GETERRNO(nbytesread);
  152. /* EINTR is not an error (but will still stop the copy) */
  153. if (errcode != EINTR || ntransferred == 0)
  154. {
  155. /* Read error. Break out and return the error condition. */
  156. _NX_SETERRNO(nbytesread);
  157. ntransferred = ERROR;
  158. endxfr = true;
  159. break;
  160. }
  161. }
  162. }
  163. while (nbytesread < 0);
  164. /* Was anything read? */
  165. if (!endxfr)
  166. {
  167. /* Yes.. Loop until the read side of the transfer comes to some
  168. * conclusion.
  169. */
  170. wrbuffer = iobuffer;
  171. do
  172. {
  173. /* Write the buffer of data to the outfd */
  174. nbyteswritten = _NX_WRITE(outfd, wrbuffer, nbytesread);
  175. /* Check for a complete (or parial) write. write() should not
  176. * return zero.
  177. */
  178. if (nbyteswritten >= 0)
  179. {
  180. /* Advance the buffer pointer and decrement the number of bytes
  181. * remaining in the iobuffer. Typically, nbytesread will now
  182. * be zero.
  183. */
  184. wrbuffer += nbyteswritten;
  185. nbytesread -= nbyteswritten;
  186. /* Increment the total number of bytes successfully transferred. */
  187. ntransferred += nbyteswritten;
  188. }
  189. /* Otherwise an error occurred */
  190. else
  191. {
  192. int errcode = _NX_GETERRNO(nbyteswritten);
  193. /* Check for a read ERROR. EINTR is a special case. This
  194. * function should break out and return an error if EINTR
  195. * is returned and no data has been transferred. But what
  196. * should it do if some data has been transferred? I
  197. * suppose just continue?
  198. */
  199. if (errcode != EINTR || ntransferred == 0)
  200. {
  201. /* Write error. Break out and return the error
  202. * condition.
  203. */
  204. _NX_SETERRNO(nbyteswritten);
  205. ntransferred = ERROR;
  206. endxfr = true;
  207. break;
  208. }
  209. }
  210. }
  211. while (nbytesread > 0);
  212. }
  213. }
  214. /* Release the I/O buffer */
  215. lib_free(iobuffer);
  216. /* Return the current file position */
  217. if (offset)
  218. {
  219. /* Use lseek to get the current file position */
  220. off_t curpos = lseek(infd, 0, SEEK_CUR);
  221. if (curpos == (off_t)-1)
  222. {
  223. return ERROR;
  224. }
  225. /* Return the current file position */
  226. *offset = curpos;
  227. /* Use lseek again to restore the original file position */
  228. if (lseek(infd, startpos, SEEK_SET) == (off_t)-1)
  229. {
  230. return ERROR;
  231. }
  232. }
  233. /* Finally return the number of bytes actually transferred (or ERROR
  234. * if any failure occurred).
  235. */
  236. return ntransferred;
  237. }