fs_userfs.c 55 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004
  1. /****************************************************************************
  2. * fs/userfs/fs_userfs.c
  3. *
  4. * Copyright (C) 2017-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. #include <sys/types.h>
  40. #include <sys/statfs.h>
  41. #include <sys/stat.h>
  42. #include <sys/socket.h>
  43. #include <stdint.h>
  44. #include <stdbool.h>
  45. #include <string.h>
  46. #include <fcntl.h>
  47. #include <assert.h>
  48. #include <errno.h>
  49. #include <debug.h>
  50. #include <arpa/inet.h>
  51. #include <netinet/in.h>
  52. #include <nuttx/kmalloc.h>
  53. #include <nuttx/fs/fs.h>
  54. #include <nuttx/fs/userfs.h>
  55. #include <nuttx/fs/dirent.h>
  56. #include <nuttx/fs/ioctl.h>
  57. #include <nuttx/net/net.h>
  58. #include <nuttx/semaphore.h>
  59. /****************************************************************************
  60. * Pre-processor Definitions
  61. ****************************************************************************/
  62. #define IOBUFFER_SIZE(p) (USERFS_REQ_MAXSIZE + (p)->mxwrite)
  63. /****************************************************************************
  64. * Private Types
  65. ****************************************************************************/
  66. /* This structure holds the internal state of the UserFS proxy */
  67. struct userfs_state_s
  68. {
  69. /* Fields copied from struct userfs_config_s */
  70. size_t mxwrite; /* The max size of a write data */
  71. /* Internal state */
  72. struct socket psock; /* Client socket instance */
  73. struct sockaddr_in server; /* Server address */
  74. sem_t exclsem; /* Exclusive access for request-response sequence */
  75. /* I/O Buffer (actual size depends on USERFS_REQ_MAXSIZE and the configured
  76. * mxwrite).
  77. */
  78. uint8_t iobuffer[1];
  79. };
  80. #define SIZEOF_USERFS_STATE_S(n) (sizeof(struct userfs_state_s) + (n) - 1)
  81. /****************************************************************************
  82. * Private Function Prototypes
  83. ****************************************************************************/
  84. static int userfs_open(FAR struct file *filep, const char *relpath,
  85. int oflags, mode_t mode);
  86. static int userfs_close(FAR struct file *filep);
  87. static ssize_t userfs_read(FAR struct file *filep, char *buffer,
  88. size_t buflen);
  89. static ssize_t userfs_read(FAR struct file *filep, FAR char *buffer,
  90. size_t buflen);
  91. static ssize_t userfs_write(FAR struct file *filep, FAR const char *buffer,
  92. size_t buflen);
  93. static off_t userfs_seek(FAR struct file *filep, off_t offset, int whence);
  94. static int userfs_ioctl(FAR struct file *filep, int cmd,
  95. unsigned long arg);
  96. static int userfs_sync(FAR struct file *filep);
  97. static int userfs_dup(FAR const struct file *oldp,
  98. FAR struct file *newp);
  99. static int userfs_fstat(FAR const struct file *filep,
  100. FAR struct stat *buf);
  101. static int userfs_truncate(FAR struct file *filep, off_t length);
  102. static int userfs_opendir(FAR struct inode *mountpt,
  103. FAR const char *relpath, FAR struct fs_dirent_s *dir);
  104. static int userfs_closedir(FAR struct inode *mountpt,
  105. FAR struct fs_dirent_s *dir);
  106. static int userfs_readdir(FAR struct inode *mountpt,
  107. FAR struct fs_dirent_s *dir);
  108. static int userfs_rewinddir(FAR struct inode *mountpt,
  109. FAR struct fs_dirent_s *dir);
  110. static int userfs_bind(FAR struct inode *blkdriver, FAR const void *data,
  111. FAR void **handle);
  112. static int userfs_unbind(FAR void *handle, FAR struct inode **blkdriver,
  113. unsigned int flags);
  114. static int userfs_statfs(FAR struct inode *mountpt,
  115. FAR struct statfs *buf);
  116. static int userfs_unlink(FAR struct inode *mountpt,
  117. FAR const char *relpath);
  118. static int userfs_mkdir(FAR struct inode *mountpt,
  119. FAR const char *relpath, mode_t mode);
  120. static int userfs_rmdir(FAR struct inode *mountpt,
  121. FAR const char *relpath);
  122. static int userfs_rename(FAR struct inode *mountpt,
  123. FAR const char *oldrelpath, FAR const char *newrelpath);
  124. static int userfs_stat(FAR struct inode *mountpt,
  125. FAR const char *relpath, FAR struct stat *buf);
  126. /****************************************************************************
  127. * Public Data
  128. ****************************************************************************/
  129. /* See fs_mount.c -- this structure is explicitly extern'ed there.
  130. * We use the old-fashioned kind of initializers so that this will compile
  131. * with any compiler.
  132. */
  133. const struct mountpt_operations userfs_operations =
  134. {
  135. userfs_open, /* open */
  136. userfs_close, /* close */
  137. userfs_read, /* read */
  138. userfs_write, /* write */
  139. userfs_seek, /* seek */
  140. userfs_ioctl, /* ioctl */
  141. userfs_sync, /* sync */
  142. userfs_dup, /* dup */
  143. userfs_fstat, /* fstat */
  144. userfs_truncate, /* truncate */
  145. userfs_opendir, /* opendir */
  146. userfs_closedir, /* closedir */
  147. userfs_readdir, /* readdir */
  148. userfs_rewinddir, /* rewinddir */
  149. userfs_bind, /* bind */
  150. userfs_unbind, /* unbind */
  151. userfs_statfs, /* statfs */
  152. userfs_unlink, /* unlink */
  153. userfs_mkdir, /* mkdir */
  154. userfs_rmdir, /* rmdir */
  155. userfs_rename, /* rename */
  156. userfs_stat /* stat */
  157. };
  158. /****************************************************************************
  159. * Private Functions
  160. ****************************************************************************/
  161. /****************************************************************************
  162. * Name: userfs_open
  163. ****************************************************************************/
  164. static int userfs_open(FAR struct file *filep, FAR const char *relpath,
  165. int oflags, mode_t mode)
  166. {
  167. FAR struct userfs_state_s *priv;
  168. FAR struct userfs_open_request_s *req;
  169. FAR struct userfs_open_response_s *resp;
  170. ssize_t nsent;
  171. ssize_t nrecvd;
  172. int pathlen;
  173. int ret;
  174. finfo("Open '%s'\n", relpath);
  175. DEBUGASSERT(filep != NULL &&
  176. filep->f_inode != NULL &&
  177. filep->f_inode->i_private != NULL);
  178. priv = filep->f_inode->i_private;
  179. /* Check the path length */
  180. DEBUGASSERT(relpath != NULL);
  181. pathlen = strlen(relpath);
  182. if (pathlen > priv->mxwrite)
  183. {
  184. return -E2BIG;
  185. }
  186. /* Get exclusive access */
  187. ret = nxsem_wait(&priv->exclsem);
  188. if (ret < 0)
  189. {
  190. return ret;
  191. }
  192. /* Construct and send the request to the server */
  193. req = (FAR struct userfs_open_request_s *)priv->iobuffer;
  194. req->req = USERFS_REQ_OPEN;
  195. req->oflags = oflags;
  196. req->mode = mode;
  197. strncpy(req->relpath, relpath, priv->mxwrite);
  198. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  199. SIZEOF_USERFS_OPEN_REQUEST_S(pathlen + 1), 0,
  200. (FAR struct sockaddr *)&priv->server,
  201. sizeof(struct sockaddr_in));
  202. if (nsent < 0)
  203. {
  204. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  205. nxsem_post(&priv->exclsem);
  206. return (int)nsent;
  207. }
  208. /* Then get the response from the server */
  209. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  210. 0, NULL, NULL);
  211. nxsem_post(&priv->exclsem);
  212. if (nrecvd < 0)
  213. {
  214. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  215. return (int)nrecvd;
  216. }
  217. if (nrecvd != sizeof(struct userfs_open_response_s))
  218. {
  219. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  220. return -EIO;
  221. }
  222. /* Save the returned openinfo as the filep private data. */
  223. resp = (FAR struct userfs_open_response_s *)priv->iobuffer;
  224. if (resp->resp != USERFS_RESP_OPEN)
  225. {
  226. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  227. return -EIO;
  228. }
  229. filep->f_priv = resp->openinfo;
  230. return resp->ret;
  231. }
  232. /****************************************************************************
  233. * Name: userfs_close
  234. ****************************************************************************/
  235. static int userfs_close(FAR struct file *filep)
  236. {
  237. FAR struct userfs_state_s *priv;
  238. FAR struct userfs_close_request_s *req;
  239. FAR struct userfs_close_response_s *resp;
  240. ssize_t nsent;
  241. ssize_t nrecvd;
  242. int ret;
  243. DEBUGASSERT(filep != NULL &&
  244. filep->f_inode != NULL &&
  245. filep->f_inode->i_private != NULL);
  246. priv = filep->f_inode->i_private;
  247. /* Get exclusive access */
  248. ret = nxsem_wait(&priv->exclsem);
  249. if (ret < 0)
  250. {
  251. return ret;
  252. }
  253. /* Construct and send the request to the server */
  254. req = (FAR struct userfs_close_request_s *)priv->iobuffer;
  255. req->req = USERFS_REQ_CLOSE;
  256. req->openinfo = filep->f_priv;
  257. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  258. sizeof(struct userfs_close_request_s), 0,
  259. (FAR struct sockaddr *)&priv->server,
  260. sizeof(struct sockaddr_in));
  261. if (nsent < 0)
  262. {
  263. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  264. nxsem_post(&priv->exclsem);
  265. return (int)nsent;
  266. }
  267. /* Then get the response from the server */
  268. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  269. 0, NULL, NULL);
  270. nxsem_post(&priv->exclsem);
  271. if (nrecvd < 0)
  272. {
  273. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  274. return (int)nrecvd;
  275. }
  276. if (nrecvd != sizeof(struct userfs_close_response_s))
  277. {
  278. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  279. return -EIO;
  280. }
  281. resp = (FAR struct userfs_close_response_s *)priv->iobuffer;
  282. if (resp->resp != USERFS_RESP_CLOSE)
  283. {
  284. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  285. return -EIO;
  286. }
  287. if (resp->ret >= 0)
  288. {
  289. filep->f_priv = NULL;
  290. }
  291. return resp->ret;
  292. }
  293. /****************************************************************************
  294. * Name: userfs_read
  295. ****************************************************************************/
  296. static ssize_t userfs_read(FAR struct file *filep, char *buffer,
  297. size_t buflen)
  298. {
  299. FAR struct userfs_state_s *priv;
  300. FAR struct userfs_read_request_s *req;
  301. FAR struct userfs_read_response_s *resp;
  302. ssize_t nsent;
  303. ssize_t nrecvd;
  304. int respsize;
  305. int ret;
  306. finfo("Read %d bytes from offset %d\n", buflen, filep->f_pos);
  307. DEBUGASSERT(filep != NULL &&
  308. filep->f_inode != NULL &&
  309. filep->f_inode->i_private != NULL);
  310. priv = filep->f_inode->i_private;
  311. /* Get exclusive access */
  312. ret = nxsem_wait(&priv->exclsem);
  313. if (ret < 0)
  314. {
  315. return ret;
  316. }
  317. /* Construct and send the request to the server */
  318. req = (FAR struct userfs_read_request_s *)priv->iobuffer;
  319. req->req = USERFS_REQ_READ;
  320. req->openinfo = filep->f_priv;
  321. req->readlen = buflen;
  322. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  323. sizeof(struct userfs_read_request_s), 0,
  324. (FAR struct sockaddr *)&priv->server,
  325. sizeof(struct sockaddr_in));
  326. if (nsent < 0)
  327. {
  328. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  329. nxsem_post(&priv->exclsem);
  330. return (int)nsent;
  331. }
  332. /* Then get the response from the server */
  333. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  334. 0, NULL, NULL);
  335. nxsem_post(&priv->exclsem);
  336. if (nrecvd < 0)
  337. {
  338. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  339. return (int)nrecvd;
  340. }
  341. if (nrecvd < SIZEOF_USERFS_READ_RESPONSE_S(0))
  342. {
  343. ferr("ERROR: Response too small: %u\n", (unsigned int)nrecvd);
  344. return -EIO;
  345. }
  346. resp = (FAR struct userfs_read_response_s *)priv->iobuffer;
  347. if (resp->resp != USERFS_RESP_READ)
  348. {
  349. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  350. return -EIO;
  351. }
  352. if (resp->nread > buflen)
  353. {
  354. ferr("ERROR: Response size too large: %u\n", (unsigned int)nrecvd);
  355. return -EIO;
  356. }
  357. respsize = SIZEOF_USERFS_READ_RESPONSE_S(resp->nread);
  358. if (respsize != nrecvd)
  359. {
  360. ferr("ERROR: Incorrect response size: %u\n", (unsigned int)nrecvd);
  361. return -EIO;
  362. }
  363. /* Copy the received data to the user buffer */
  364. memcpy(buffer, resp->rddata, resp->nread);
  365. return resp->nread;
  366. }
  367. /****************************************************************************
  368. * Name: userfs_write
  369. ****************************************************************************/
  370. static ssize_t userfs_write(FAR struct file *filep, FAR const char *buffer,
  371. size_t buflen)
  372. {
  373. FAR struct userfs_state_s *priv;
  374. FAR struct userfs_write_request_s *req;
  375. FAR struct userfs_write_response_s *resp;
  376. ssize_t nsent;
  377. ssize_t nrecvd;
  378. int ret;
  379. finfo("Write %d bytes to offset %d\n", buflen, filep->f_pos);
  380. DEBUGASSERT(filep != NULL &&
  381. filep->f_inode != NULL &&
  382. filep->f_inode->i_private != NULL);
  383. priv = filep->f_inode->i_private;
  384. /* Perform multiple writes if the write length exceeds the configured
  385. * maximum (mxwrite).
  386. */
  387. if (buflen > priv->mxwrite)
  388. {
  389. return -E2BIG; /* No implemented yet */
  390. }
  391. /* Get exclusive access */
  392. ret = nxsem_wait(&priv->exclsem);
  393. if (ret < 0)
  394. {
  395. return ret;
  396. }
  397. /* Construct and send the request to the server */
  398. req = (FAR struct userfs_write_request_s *)priv->iobuffer;
  399. req->req = USERFS_REQ_WRITE;
  400. req->openinfo = filep->f_priv;
  401. req->writelen = buflen;
  402. memcpy(req->wrdata, buffer, buflen);
  403. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  404. SIZEOF_USERFS_WRITE_REQUEST_S(buflen), 0,
  405. (FAR struct sockaddr *)&priv->server,
  406. sizeof(struct sockaddr_in));
  407. if (nsent < 0)
  408. {
  409. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  410. nxsem_post(&priv->exclsem);
  411. return (int)nsent;
  412. }
  413. /* Then get the response from the server */
  414. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  415. 0, NULL, NULL);
  416. nxsem_post(&priv->exclsem);
  417. if (nrecvd < 0)
  418. {
  419. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  420. return (int)nrecvd;
  421. }
  422. if (nrecvd != sizeof(struct userfs_write_response_s))
  423. {
  424. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  425. return -EIO;
  426. }
  427. resp = (FAR struct userfs_write_response_s *)priv->iobuffer;
  428. if (resp->resp != USERFS_RESP_WRITE)
  429. {
  430. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  431. return -EIO;
  432. }
  433. return resp->nwritten;
  434. }
  435. /****************************************************************************
  436. * Name: userfs_seek
  437. ****************************************************************************/
  438. static off_t userfs_seek(FAR struct file *filep, off_t offset, int whence)
  439. {
  440. FAR struct userfs_state_s *priv;
  441. FAR struct userfs_seek_request_s *req;
  442. FAR struct userfs_seek_response_s *resp;
  443. ssize_t nsent;
  444. ssize_t nrecvd;
  445. int ret;
  446. finfo("Offset %lu bytes to whence=%d\n", (unsigned long)offset, whence);
  447. DEBUGASSERT(filep != NULL &&
  448. filep->f_inode != NULL &&
  449. filep->f_inode->i_private != NULL);
  450. priv = filep->f_inode->i_private;
  451. /* Get exclusive access */
  452. ret = nxsem_wait(&priv->exclsem);
  453. if (ret < 0)
  454. {
  455. return ret;
  456. }
  457. /* Construct and send the request to the server */
  458. req = (FAR struct userfs_seek_request_s *)priv->iobuffer;
  459. req->req = USERFS_REQ_SEEK;
  460. req->openinfo = filep->f_priv;
  461. req->offset = offset;
  462. req->whence = whence;
  463. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  464. sizeof(struct userfs_seek_request_s), 0,
  465. (FAR struct sockaddr *)&priv->server,
  466. sizeof(struct sockaddr_in));
  467. if (nsent < 0)
  468. {
  469. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  470. nxsem_post(&priv->exclsem);
  471. return (int)nsent;
  472. }
  473. /* Then get the response from the server */
  474. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  475. 0, NULL, NULL);
  476. nxsem_post(&priv->exclsem);
  477. if (nrecvd < 0)
  478. {
  479. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  480. return (int)nrecvd;
  481. }
  482. if (nrecvd != sizeof(struct userfs_seek_response_s))
  483. {
  484. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  485. return -EIO;
  486. }
  487. resp = (FAR struct userfs_seek_response_s *)priv->iobuffer;
  488. if (resp->resp != USERFS_RESP_SEEK)
  489. {
  490. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  491. return -EIO;
  492. }
  493. return resp->ret;
  494. }
  495. /****************************************************************************
  496. * Name: userfs_ioctl
  497. ****************************************************************************/
  498. static int userfs_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
  499. {
  500. FAR struct userfs_state_s *priv;
  501. FAR struct userfs_ioctl_request_s *req;
  502. FAR struct userfs_ioctl_response_s *resp;
  503. ssize_t nsent;
  504. ssize_t nrecvd;
  505. int ret;
  506. finfo("cmd: %d arg: %08lx\n", cmd, arg);
  507. DEBUGASSERT(filep != NULL &&
  508. filep->f_inode != NULL &&
  509. filep->f_inode->i_private != NULL);
  510. priv = filep->f_inode->i_private;
  511. /* Get exclusive access */
  512. ret = nxsem_wait(&priv->exclsem);
  513. if (ret < 0)
  514. {
  515. return ret;
  516. }
  517. /* Construct and send the request to the server */
  518. req = (FAR struct userfs_ioctl_request_s *)priv->iobuffer;
  519. req->req = USERFS_REQ_IOCTL;
  520. req->openinfo = filep->f_priv;
  521. req->cmd = cmd;
  522. req->arg = arg;
  523. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  524. sizeof(struct userfs_ioctl_request_s), 0,
  525. (FAR struct sockaddr *)&priv->server,
  526. sizeof(struct sockaddr_in));
  527. if (nsent < 0)
  528. {
  529. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  530. nxsem_post(&priv->exclsem);
  531. return (int)nsent;
  532. }
  533. /* Then get the response from the server */
  534. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  535. 0, NULL, NULL);
  536. nxsem_post(&priv->exclsem);
  537. if (nrecvd < 0)
  538. {
  539. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  540. return (int)nrecvd;
  541. }
  542. if (nrecvd != sizeof(struct userfs_ioctl_response_s))
  543. {
  544. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  545. return -EIO;
  546. }
  547. resp = (FAR struct userfs_ioctl_response_s *)priv->iobuffer;
  548. if (resp->resp != USERFS_RESP_IOCTL)
  549. {
  550. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  551. return -EIO;
  552. }
  553. return resp->ret;
  554. }
  555. /****************************************************************************
  556. * Name: userfs_sync
  557. ****************************************************************************/
  558. static int userfs_sync(FAR struct file *filep)
  559. {
  560. FAR struct userfs_state_s *priv;
  561. FAR struct userfs_sync_request_s *req;
  562. FAR struct userfs_sync_response_s *resp;
  563. ssize_t nsent;
  564. ssize_t nrecvd;
  565. int ret;
  566. DEBUGASSERT(filep != NULL &&
  567. filep->f_inode != NULL &&
  568. filep->f_inode->i_private != NULL);
  569. priv = filep->f_inode->i_private;
  570. /* Get exclusive access */
  571. ret = nxsem_wait(&priv->exclsem);
  572. if (ret < 0)
  573. {
  574. return ret;
  575. }
  576. /* Construct and send the request to the server */
  577. req = (FAR struct userfs_sync_request_s *)priv->iobuffer;
  578. req->req = USERFS_REQ_SYNC;
  579. req->openinfo = filep->f_priv;
  580. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  581. sizeof(struct userfs_sync_request_s), 0,
  582. (FAR struct sockaddr *)&priv->server,
  583. sizeof(struct sockaddr_in));
  584. if (nsent < 0)
  585. {
  586. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  587. nxsem_post(&priv->exclsem);
  588. return (int)nsent;
  589. }
  590. /* Then get the response from the server */
  591. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  592. 0, NULL, NULL);
  593. nxsem_post(&priv->exclsem);
  594. if (nrecvd < 0)
  595. {
  596. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  597. return (int)nrecvd;
  598. }
  599. if (nrecvd != sizeof(struct userfs_sync_response_s))
  600. {
  601. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  602. return -EIO;
  603. }
  604. resp = (FAR struct userfs_sync_response_s *)priv->iobuffer;
  605. if (resp->resp != USERFS_RESP_SYNC)
  606. {
  607. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  608. return -EIO;
  609. }
  610. return resp->ret;
  611. }
  612. /****************************************************************************
  613. * Name: userfs_dup
  614. *
  615. * Description:
  616. * Duplicate open file data in the new file structure.
  617. *
  618. ****************************************************************************/
  619. static int userfs_dup(FAR const struct file *oldp, FAR struct file *newp)
  620. {
  621. FAR struct userfs_state_s *priv;
  622. FAR struct userfs_dup_request_s *req;
  623. FAR struct userfs_dup_response_s *resp;
  624. ssize_t nsent;
  625. ssize_t nrecvd;
  626. int ret;
  627. finfo("Dup %p->%p\n", oldp, newp);
  628. DEBUGASSERT(oldp != NULL &&
  629. oldp->f_inode != NULL &&
  630. oldp->f_inode->i_private != NULL);
  631. priv = oldp->f_inode->i_private;
  632. /* Get exclusive access */
  633. ret = nxsem_wait(&priv->exclsem);
  634. if (ret < 0)
  635. {
  636. return ret;
  637. }
  638. /* Construct and send the request to the server */
  639. req = (FAR struct userfs_dup_request_s *)priv->iobuffer;
  640. req->req = USERFS_REQ_DUP;
  641. req->openinfo = oldp->f_priv;
  642. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  643. sizeof(struct userfs_dup_request_s), 0,
  644. (FAR struct sockaddr *)&priv->server,
  645. sizeof(struct sockaddr_in));
  646. if (nsent < 0)
  647. {
  648. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  649. nxsem_post(&priv->exclsem);
  650. return (int)nsent;
  651. }
  652. /* Then get the response from the server */
  653. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  654. 0, NULL, NULL);
  655. nxsem_post(&priv->exclsem);
  656. if (nrecvd < 0)
  657. {
  658. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  659. return (int)nrecvd;
  660. }
  661. if (nrecvd != sizeof(struct userfs_dup_response_s))
  662. {
  663. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  664. return -EIO;
  665. }
  666. resp = (FAR struct userfs_dup_response_s *)priv->iobuffer;
  667. if (resp->resp != USERFS_RESP_DUP)
  668. {
  669. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  670. return -EIO;
  671. }
  672. newp->f_priv = resp->openinfo;
  673. return resp->ret;
  674. }
  675. /****************************************************************************
  676. * Name: userfs_fstat
  677. *
  678. * Description:
  679. * Obtain information about an open file associated with the file
  680. * descriptor 'fd', and will write it to the area pointed to by 'buf'.
  681. *
  682. ****************************************************************************/
  683. static int userfs_fstat(FAR const struct file *filep, FAR struct stat *buf)
  684. {
  685. FAR struct userfs_state_s *priv;
  686. FAR struct userfs_fstat_request_s *req;
  687. FAR struct userfs_fstat_response_s *resp;
  688. ssize_t nsent;
  689. ssize_t nrecvd;
  690. int ret;
  691. DEBUGASSERT(filep != NULL &&
  692. filep->f_inode != NULL &&
  693. filep->f_inode->i_private != NULL);
  694. priv = filep->f_inode->i_private;
  695. /* Get exclusive access */
  696. ret = nxsem_wait(&priv->exclsem);
  697. if (ret < 0)
  698. {
  699. return ret;
  700. }
  701. /* Construct and send the request to the server */
  702. req = (FAR struct userfs_fstat_request_s *)priv->iobuffer;
  703. req->req = USERFS_REQ_FSTAT;
  704. req->openinfo = filep->f_priv;
  705. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  706. sizeof(struct userfs_fstat_request_s), 0,
  707. (FAR struct sockaddr *)&priv->server,
  708. sizeof(struct sockaddr_in));
  709. if (nsent < 0)
  710. {
  711. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  712. nxsem_post(&priv->exclsem);
  713. return (int)nsent;
  714. }
  715. /* Then get the response from the server */
  716. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  717. 0, NULL, NULL);
  718. nxsem_post(&priv->exclsem);
  719. if (nrecvd < 0)
  720. {
  721. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  722. return (int)nrecvd;
  723. }
  724. if (nrecvd != sizeof(struct userfs_fstat_response_s))
  725. {
  726. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  727. return -EIO;
  728. }
  729. resp = (FAR struct userfs_fstat_response_s *)priv->iobuffer;
  730. if (resp->resp != USERFS_RESP_FSTAT)
  731. {
  732. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  733. return -EIO;
  734. }
  735. /* Return the status of the directory entry */
  736. DEBUGASSERT(buf != NULL);
  737. memcpy(buf, &resp->buf, sizeof(struct stat));
  738. return resp->ret;
  739. }
  740. /****************************************************************************
  741. * Name: userfs_truncate
  742. *
  743. * Description:
  744. * Set the size of the regular file referred to by 'filep' to 'length'
  745. *
  746. ****************************************************************************/
  747. static int userfs_truncate(FAR struct file *filep, off_t length)
  748. {
  749. FAR struct userfs_state_s *priv;
  750. FAR struct userfs_truncate_request_s *req;
  751. FAR struct userfs_truncate_response_s *resp;
  752. ssize_t nsent;
  753. ssize_t nrecvd;
  754. int ret;
  755. DEBUGASSERT(filep != NULL &&
  756. filep->f_inode != NULL &&
  757. filep->f_inode->i_private != NULL);
  758. priv = filep->f_inode->i_private;
  759. /* Get exclusive access */
  760. ret = nxsem_wait(&priv->exclsem);
  761. if (ret < 0)
  762. {
  763. return ret;
  764. }
  765. /* Construct and send the request to the server */
  766. req = (FAR struct userfs_truncate_request_s *)priv->iobuffer;
  767. req->req = USERFS_REQ_TRUNCATE;
  768. req->openinfo = filep->f_priv;
  769. req->length = length;
  770. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  771. sizeof(struct userfs_truncate_request_s), 0,
  772. (FAR struct sockaddr *)&priv->server,
  773. sizeof(struct sockaddr_in));
  774. if (nsent < 0)
  775. {
  776. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  777. nxsem_post(&priv->exclsem);
  778. return (int)nsent;
  779. }
  780. /* Then get the response from the server */
  781. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  782. 0, NULL, NULL);
  783. nxsem_post(&priv->exclsem);
  784. if (nrecvd < 0)
  785. {
  786. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  787. return (int)nrecvd;
  788. }
  789. if (nrecvd != sizeof(struct userfs_truncate_response_s))
  790. {
  791. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  792. return -EIO;
  793. }
  794. resp = (FAR struct userfs_truncate_response_s *)priv->iobuffer;
  795. if (resp->resp != USERFS_RESP_FSTAT)
  796. {
  797. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  798. return -EIO;
  799. }
  800. /* Return the result of truncate operation */
  801. return resp->ret;
  802. }
  803. /****************************************************************************
  804. * Name: userfs_opendir
  805. *
  806. * Description:
  807. * Open a directory
  808. *
  809. ****************************************************************************/
  810. static int userfs_opendir(FAR struct inode *mountpt, FAR const char *relpath,
  811. FAR struct fs_dirent_s *dir)
  812. {
  813. FAR struct userfs_state_s *priv;
  814. FAR struct userfs_opendir_request_s *req;
  815. FAR struct userfs_opendir_response_s *resp;
  816. ssize_t nsent;
  817. ssize_t nrecvd;
  818. int pathlen;
  819. int ret;
  820. finfo("relpath: \"%s\"\n", relpath ? relpath : "NULL");
  821. DEBUGASSERT(mountpt != NULL &&
  822. mountpt->i_private != NULL);
  823. priv = mountpt->i_private;
  824. /* Check the path length */
  825. DEBUGASSERT(relpath != NULL);
  826. pathlen = strlen(relpath);
  827. if (pathlen > priv->mxwrite)
  828. {
  829. return -E2BIG;
  830. }
  831. /* Get exclusive access */
  832. ret = nxsem_wait(&priv->exclsem);
  833. if (ret < 0)
  834. {
  835. return ret;
  836. }
  837. /* Construct and send the request to the server */
  838. req = (FAR struct userfs_opendir_request_s *)priv->iobuffer;
  839. req->req = USERFS_REQ_OPENDIR;
  840. strncpy(req->relpath, relpath, priv->mxwrite);
  841. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  842. SIZEOF_USERFS_OPENDIR_REQUEST_S(pathlen + 1), 0,
  843. (FAR struct sockaddr *)&priv->server,
  844. sizeof(struct sockaddr_in));
  845. if (nsent < 0)
  846. {
  847. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  848. nxsem_post(&priv->exclsem);
  849. return (int)nsent;
  850. }
  851. /* Then get the response from the server */
  852. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  853. 0, NULL, NULL);
  854. nxsem_post(&priv->exclsem);
  855. if (nrecvd < 0)
  856. {
  857. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  858. return (int)nrecvd;
  859. }
  860. if (nrecvd != sizeof(struct userfs_opendir_response_s))
  861. {
  862. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  863. return -EIO;
  864. }
  865. resp = (FAR struct userfs_opendir_response_s *)priv->iobuffer;
  866. if (resp->resp != USERFS_RESP_OPENDIR)
  867. {
  868. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  869. return -EIO;
  870. }
  871. /* Save the opaque dir reference in struct fs_dirent_s */
  872. DEBUGASSERT(dir != NULL);
  873. dir->u.userfs.fs_dir = resp->dir;
  874. return resp->ret;
  875. }
  876. /****************************************************************************
  877. * Name: userfs_closedir
  878. *
  879. * Description:
  880. * Close a directory
  881. *
  882. ****************************************************************************/
  883. static int userfs_closedir(FAR struct inode *mountpt,
  884. FAR struct fs_dirent_s *dir)
  885. {
  886. FAR struct userfs_state_s *priv;
  887. FAR struct userfs_closedir_request_s *req;
  888. FAR struct userfs_closedir_response_s *resp;
  889. ssize_t nsent;
  890. ssize_t nrecvd;
  891. int ret;
  892. DEBUGASSERT(mountpt != NULL &&
  893. mountpt->i_private != NULL);
  894. priv = mountpt->i_private;
  895. /* Get exclusive access */
  896. ret = nxsem_wait(&priv->exclsem);
  897. if (ret < 0)
  898. {
  899. return ret;
  900. }
  901. /* Construct and send the request to the server */
  902. req = (FAR struct userfs_closedir_request_s *)priv->iobuffer;
  903. req->req = USERFS_REQ_CLOSEDIR;
  904. req->dir = dir->u.userfs.fs_dir;
  905. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  906. sizeof(struct userfs_closedir_request_s), 0,
  907. (FAR struct sockaddr *)&priv->server,
  908. sizeof(struct sockaddr_in));
  909. if (nsent < 0)
  910. {
  911. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  912. nxsem_post(&priv->exclsem);
  913. return (int)nsent;
  914. }
  915. /* Then get the response from the server */
  916. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  917. 0, NULL, NULL);
  918. nxsem_post(&priv->exclsem);
  919. if (nrecvd < 0)
  920. {
  921. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  922. return (int)nrecvd;
  923. }
  924. if (nrecvd != sizeof(struct userfs_closedir_response_s))
  925. {
  926. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  927. return -EIO;
  928. }
  929. resp = (FAR struct userfs_closedir_response_s *)priv->iobuffer;
  930. if (resp->resp != USERFS_RESP_CLOSEDIR)
  931. {
  932. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  933. return -EIO;
  934. }
  935. return resp->ret;
  936. }
  937. /****************************************************************************
  938. * Name: userfs_readdir
  939. *
  940. * Description: Read the next directory entry
  941. *
  942. ****************************************************************************/
  943. static int userfs_readdir(FAR struct inode *mountpt,
  944. FAR struct fs_dirent_s *dir)
  945. {
  946. FAR struct userfs_state_s *priv;
  947. FAR struct userfs_readdir_request_s *req;
  948. FAR struct userfs_readdir_response_s *resp;
  949. ssize_t nsent;
  950. ssize_t nrecvd;
  951. int ret;
  952. DEBUGASSERT(mountpt != NULL &&
  953. mountpt->i_private != NULL);
  954. priv = mountpt->i_private;
  955. /* Get exclusive access */
  956. ret = nxsem_wait(&priv->exclsem);
  957. if (ret < 0)
  958. {
  959. return ret;
  960. }
  961. /* Construct and send the request to the server */
  962. req = (FAR struct userfs_readdir_request_s *)priv->iobuffer;
  963. req->req = USERFS_REQ_READDIR;
  964. req->dir = dir->u.userfs.fs_dir;
  965. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  966. sizeof(struct userfs_readdir_request_s), 0,
  967. (FAR struct sockaddr *)&priv->server,
  968. sizeof(struct sockaddr_in));
  969. if (nsent < 0)
  970. {
  971. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  972. nxsem_post(&priv->exclsem);
  973. return (int)nsent;
  974. }
  975. /* Then get the response from the server */
  976. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  977. 0, NULL, NULL);
  978. nxsem_post(&priv->exclsem);
  979. if (nrecvd < 0)
  980. {
  981. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  982. return (int)nrecvd;
  983. }
  984. if (nrecvd != sizeof(struct userfs_readdir_response_s))
  985. {
  986. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  987. return -EIO;
  988. }
  989. resp = (FAR struct userfs_readdir_response_s *)priv->iobuffer;
  990. if (resp->resp != USERFS_RESP_READDIR)
  991. {
  992. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  993. return -EIO;
  994. }
  995. /* Return the dirent */
  996. DEBUGASSERT(dir != NULL);
  997. memcpy(&dir->fd_dir, &resp->entry, sizeof(struct dirent));
  998. return resp->ret;
  999. }
  1000. /****************************************************************************
  1001. * Name: userfs_rewindir
  1002. *
  1003. * Description: Reset directory read to the first entry
  1004. *
  1005. ****************************************************************************/
  1006. static int userfs_rewinddir(FAR struct inode *mountpt,
  1007. FAR struct fs_dirent_s *dir)
  1008. {
  1009. FAR struct userfs_state_s *priv;
  1010. FAR struct userfs_rewinddir_request_s *req;
  1011. FAR struct userfs_rewinddir_response_s *resp;
  1012. ssize_t nsent;
  1013. ssize_t nrecvd;
  1014. int ret;
  1015. DEBUGASSERT(mountpt != NULL &&
  1016. mountpt->i_private != NULL);
  1017. priv = mountpt->i_private;
  1018. /* Get exclusive access */
  1019. ret = nxsem_wait(&priv->exclsem);
  1020. if (ret < 0)
  1021. {
  1022. return ret;
  1023. }
  1024. /* Construct and send the request to the server */
  1025. req = (FAR struct userfs_rewinddir_request_s *)priv->iobuffer;
  1026. req->req = USERFS_REQ_REWINDDIR;
  1027. req->dir = dir->u.userfs.fs_dir;
  1028. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  1029. sizeof(struct userfs_rewinddir_request_s), 0,
  1030. (FAR struct sockaddr *)&priv->server,
  1031. sizeof(struct sockaddr_in));
  1032. if (nsent < 0)
  1033. {
  1034. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  1035. nxsem_post(&priv->exclsem);
  1036. return (int)nsent;
  1037. }
  1038. /* Then get the response from the server */
  1039. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  1040. 0, NULL, NULL);
  1041. nxsem_post(&priv->exclsem);
  1042. if (nrecvd < 0)
  1043. {
  1044. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  1045. return (int)nrecvd;
  1046. }
  1047. if (nrecvd != sizeof(struct userfs_rewinddir_response_s))
  1048. {
  1049. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  1050. return -EIO;
  1051. }
  1052. resp = (FAR struct userfs_rewinddir_response_s *)priv->iobuffer;
  1053. if (resp->resp != USERFS_RESP_REWINDDIR)
  1054. {
  1055. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  1056. return -EIO;
  1057. }
  1058. return resp->ret;
  1059. }
  1060. /****************************************************************************
  1061. * Name: userfs_bind
  1062. *
  1063. * Description: This implements a portion of the mount operation. This
  1064. * function allocates and initializes the mountpoint private data and
  1065. * binds the blockdriver inode to the filesystem private data. The final
  1066. * binding of the private data (containing the blockdriver) to the
  1067. * mountpoint is performed by mount().
  1068. *
  1069. ****************************************************************************/
  1070. static int userfs_bind(FAR struct inode *blkdriver, FAR const void *data,
  1071. FAR void **handle)
  1072. {
  1073. FAR struct userfs_state_s *priv;
  1074. FAR const struct userfs_config_s *config;
  1075. struct sockaddr_in client;
  1076. unsigned int iolen;
  1077. int ret;
  1078. DEBUGASSERT(data != NULL && handle != NULL);
  1079. config = (FAR const struct userfs_config_s *)data;
  1080. /* Allocate an instance of the UserFS state structure */
  1081. iolen = USERFS_REQ_MAXSIZE + config->mxwrite;
  1082. priv = kmm_malloc(SIZEOF_USERFS_STATE_S(iolen));
  1083. if (priv == NULL)
  1084. {
  1085. ferr("ERROR: Failed to allocate state structure\n");
  1086. return -ENOMEM;
  1087. }
  1088. /* Initialize the semaphore that assures mutually exclusive access through
  1089. * the entire request-response sequence.
  1090. */
  1091. nxsem_init(&priv->exclsem, 0, 1);
  1092. /* Copy the configuration data into the allocated structure. Why? First
  1093. * we can't be certain of the life time of the memory underlying the config
  1094. * reference. Also, in the KERNEL build, the config data will like in
  1095. * process-specific memory and cannot be shared across processes.
  1096. */
  1097. priv->mxwrite = config->mxwrite;
  1098. /* Preset the server address */
  1099. priv->server.sin_family = AF_INET;
  1100. priv->server.sin_port = htons(config->portno);
  1101. priv->server.sin_addr.s_addr = HTONL(INADDR_LOOPBACK);
  1102. /* Create a LocalHost UDP client socket */
  1103. ret = psock_socket(PF_INET, SOCK_DGRAM, 0, &priv->psock);
  1104. if (ret < 0)
  1105. {
  1106. ferr("ERROR: socket() failed: %d\n", ret);
  1107. goto errout_with_alloc;
  1108. }
  1109. /* Bind the socket to the client address */
  1110. client.sin_family = AF_INET;
  1111. client.sin_port = 0;
  1112. client.sin_addr.s_addr = HTONL(INADDR_LOOPBACK);
  1113. ret = psock_bind(&priv->psock, (FAR struct sockaddr *)&client,
  1114. sizeof(struct sockaddr_in));
  1115. if (ret < 0)
  1116. {
  1117. ferr("ERROR: bind() failed: %d\n", ret);
  1118. goto errout_with_psock;
  1119. }
  1120. /* Mounted! */
  1121. *handle = (FAR void *)priv;
  1122. return OK;
  1123. errout_with_psock:
  1124. psock_close(&priv->psock);
  1125. errout_with_alloc:
  1126. kmm_free(priv);
  1127. return ret;
  1128. }
  1129. /****************************************************************************
  1130. * Name: userfs_unbind
  1131. *
  1132. * Description: This implements the filesystem portion of the umount
  1133. * operation.
  1134. *
  1135. ****************************************************************************/
  1136. static int userfs_unbind(FAR void *handle, FAR struct inode **blkdriver,
  1137. unsigned int flags)
  1138. {
  1139. FAR struct userfs_state_s *priv = (FAR struct userfs_state_s *)handle;
  1140. FAR struct userfs_destroy_request_s *req;
  1141. FAR struct userfs_destroy_response_s *resp;
  1142. ssize_t nsent;
  1143. ssize_t nrecvd;
  1144. int ret;
  1145. DEBUGASSERT(priv != NULL);
  1146. /* Get exclusive access */
  1147. ret = nxsem_wait(&priv->exclsem);
  1148. if (ret < 0)
  1149. {
  1150. return ret;
  1151. }
  1152. /* Construct and send the request to the server */
  1153. req = (FAR struct userfs_destroy_request_s *)priv->iobuffer;
  1154. req->req = USERFS_REQ_DESTROY;
  1155. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  1156. sizeof(struct userfs_destroy_request_s), 0,
  1157. (FAR struct sockaddr *)&priv->server,
  1158. sizeof(struct sockaddr_in));
  1159. if (nsent < 0)
  1160. {
  1161. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  1162. nxsem_post(&priv->exclsem);
  1163. return (int)nsent;
  1164. }
  1165. /* Then get the response from the server */
  1166. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  1167. 0, NULL, NULL);
  1168. nxsem_post(&priv->exclsem);
  1169. if (nrecvd < 0)
  1170. {
  1171. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  1172. return (int)nrecvd;
  1173. }
  1174. if (nrecvd != sizeof(struct userfs_destroy_response_s))
  1175. {
  1176. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  1177. return -EIO;
  1178. }
  1179. resp = (FAR struct userfs_destroy_response_s *)priv->iobuffer;
  1180. if (resp->resp != USERFS_RESP_DESTROY)
  1181. {
  1182. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  1183. return -EIO;
  1184. }
  1185. /* If the destruction failed, then refuse to unmount at this time */
  1186. if (resp->ret < 0)
  1187. {
  1188. return resp->ret;
  1189. }
  1190. /* Free resources and return success */
  1191. psock_close(&priv->psock);
  1192. kmm_free(priv);
  1193. return OK;
  1194. }
  1195. /****************************************************************************
  1196. * Name: userfs_statfs
  1197. *
  1198. * Description:
  1199. * Return filesystem statistics
  1200. *
  1201. ****************************************************************************/
  1202. static int userfs_statfs(FAR struct inode *mountpt, FAR struct statfs *buf)
  1203. {
  1204. FAR struct userfs_state_s *priv;
  1205. FAR struct userfs_statfs_request_s *req;
  1206. FAR struct userfs_statfs_response_s *resp;
  1207. ssize_t nsent;
  1208. ssize_t nrecvd;
  1209. int ret;
  1210. DEBUGASSERT(mountpt != NULL &&
  1211. mountpt->i_private != NULL);
  1212. priv = mountpt->i_private;
  1213. /* Get exclusive access */
  1214. ret = nxsem_wait(&priv->exclsem);
  1215. if (ret < 0)
  1216. {
  1217. return ret;
  1218. }
  1219. /* Construct and send the request to the server */
  1220. req = (FAR struct userfs_statfs_request_s *)priv->iobuffer;
  1221. req->req = USERFS_REQ_STATFS;
  1222. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  1223. sizeof(struct userfs_statfs_request_s), 0,
  1224. (FAR struct sockaddr *)&priv->server,
  1225. sizeof(struct sockaddr_in));
  1226. if (nsent < 0)
  1227. {
  1228. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  1229. nxsem_post(&priv->exclsem);
  1230. return (int)nsent;
  1231. }
  1232. /* Then get the response from the server */
  1233. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  1234. 0, NULL, NULL);
  1235. nxsem_post(&priv->exclsem);
  1236. if (nrecvd < 0)
  1237. {
  1238. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  1239. return (int)nrecvd;
  1240. }
  1241. if (nrecvd != sizeof(struct userfs_statfs_response_s))
  1242. {
  1243. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  1244. return -EIO;
  1245. }
  1246. resp = (FAR struct userfs_statfs_response_s *)priv->iobuffer;
  1247. if (resp->resp != USERFS_RESP_STATFS)
  1248. {
  1249. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  1250. return -EIO;
  1251. }
  1252. /* Return the status of the file system */
  1253. DEBUGASSERT(buf != NULL);
  1254. memcpy(buf, &resp->buf, sizeof(struct statfs));
  1255. return resp->ret;
  1256. }
  1257. /****************************************************************************
  1258. * Name: userfs_unlink
  1259. *
  1260. * Description:
  1261. * Remove a directory entry
  1262. *
  1263. ****************************************************************************/
  1264. static int userfs_unlink(FAR struct inode *mountpt,
  1265. FAR const char *relpath)
  1266. {
  1267. FAR struct userfs_state_s *priv;
  1268. FAR struct userfs_unlink_request_s *req;
  1269. FAR struct userfs_unlink_response_s *resp;
  1270. ssize_t nsent;
  1271. ssize_t nrecvd;
  1272. int pathlen;
  1273. int ret;
  1274. DEBUGASSERT(mountpt != NULL &&
  1275. mountpt->i_private != NULL);
  1276. priv = mountpt->i_private;
  1277. /* Check the path length */
  1278. DEBUGASSERT(relpath != NULL);
  1279. pathlen = strlen(relpath);
  1280. if (pathlen > priv->mxwrite)
  1281. {
  1282. return -E2BIG;
  1283. }
  1284. /* Get exclusive access */
  1285. ret = nxsem_wait(&priv->exclsem);
  1286. if (ret < 0)
  1287. {
  1288. return ret;
  1289. }
  1290. /* Construct and send the request to the server */
  1291. req = (FAR struct userfs_unlink_request_s *)priv->iobuffer;
  1292. req->req = USERFS_REQ_UNLINK;
  1293. strncpy(req->relpath, relpath, priv->mxwrite);
  1294. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  1295. SIZEOF_USERFS_UNLINK_REQUEST_S(pathlen + 1), 0,
  1296. (FAR struct sockaddr *)&priv->server,
  1297. sizeof(struct sockaddr_in));
  1298. if (nsent < 0)
  1299. {
  1300. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  1301. nxsem_post(&priv->exclsem);
  1302. return (int)nsent;
  1303. }
  1304. /* Then get the response from the server */
  1305. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  1306. 0, NULL, NULL);
  1307. nxsem_post(&priv->exclsem);
  1308. if (nrecvd < 0)
  1309. {
  1310. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  1311. return (int)nrecvd;
  1312. }
  1313. if (nrecvd != sizeof(struct userfs_unlink_response_s))
  1314. {
  1315. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  1316. return -EIO;
  1317. }
  1318. resp = (FAR struct userfs_unlink_response_s *)priv->iobuffer;
  1319. if (resp->resp != USERFS_RESP_UNLINK)
  1320. {
  1321. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  1322. return -EIO;
  1323. }
  1324. return resp->ret;
  1325. }
  1326. /****************************************************************************
  1327. * Name: userfs_mkdir
  1328. *
  1329. * Description:
  1330. * Create a new directory
  1331. *
  1332. ****************************************************************************/
  1333. static int userfs_mkdir(FAR struct inode *mountpt,
  1334. FAR const char *relpath, mode_t mode)
  1335. {
  1336. FAR struct userfs_state_s *priv;
  1337. FAR struct userfs_mkdir_request_s *req;
  1338. FAR struct userfs_mkdir_response_s *resp;
  1339. ssize_t nsent;
  1340. ssize_t nrecvd;
  1341. int pathlen;
  1342. int ret;
  1343. DEBUGASSERT(mountpt != NULL &&
  1344. mountpt->i_private != NULL);
  1345. priv = mountpt->i_private;
  1346. /* Check the path length */
  1347. DEBUGASSERT(relpath != NULL);
  1348. pathlen = strlen(relpath);
  1349. if (pathlen > priv->mxwrite)
  1350. {
  1351. return -E2BIG;
  1352. }
  1353. /* Get exclusive access */
  1354. ret = nxsem_wait(&priv->exclsem);
  1355. if (ret < 0)
  1356. {
  1357. return ret;
  1358. }
  1359. /* Construct and send the request to the server */
  1360. req = (FAR struct userfs_mkdir_request_s *)priv->iobuffer;
  1361. req->req = USERFS_REQ_MKDIR;
  1362. req->mode = mode;
  1363. strncpy(req->relpath, relpath, priv->mxwrite);
  1364. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  1365. SIZEOF_USERFS_MKDIR_REQUEST_S(pathlen + 1), 0,
  1366. (FAR struct sockaddr *)&priv->server,
  1367. sizeof(struct sockaddr_in));
  1368. if (nsent < 0)
  1369. {
  1370. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  1371. nxsem_post(&priv->exclsem);
  1372. return (int)nsent;
  1373. }
  1374. /* Then get the response from the server */
  1375. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  1376. 0, NULL, NULL);
  1377. nxsem_post(&priv->exclsem);
  1378. if (nrecvd < 0)
  1379. {
  1380. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  1381. return (int)nrecvd;
  1382. }
  1383. if (nrecvd != sizeof(struct userfs_mkdir_response_s))
  1384. {
  1385. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  1386. return -EIO;
  1387. }
  1388. resp = (FAR struct userfs_mkdir_response_s *)priv->iobuffer;
  1389. if (resp->resp != USERFS_RESP_MKDIR)
  1390. {
  1391. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  1392. return -EIO;
  1393. }
  1394. return resp->ret;
  1395. }
  1396. /****************************************************************************
  1397. * Name: userfs_rmdir
  1398. *
  1399. * Description:
  1400. * Remove a directory
  1401. *
  1402. ****************************************************************************/
  1403. static int userfs_rmdir(FAR struct inode *mountpt,
  1404. FAR const char *relpath)
  1405. {
  1406. FAR struct userfs_state_s *priv;
  1407. FAR struct userfs_rmdir_request_s *req;
  1408. FAR struct userfs_rmdir_response_s *resp;
  1409. ssize_t nsent;
  1410. ssize_t nrecvd;
  1411. int pathlen;
  1412. int ret;
  1413. DEBUGASSERT(mountpt != NULL &&
  1414. mountpt->i_private != NULL);
  1415. priv = mountpt->i_private;
  1416. /* Check the path length */
  1417. DEBUGASSERT(relpath != NULL);
  1418. pathlen = strlen(relpath);
  1419. if (pathlen > priv->mxwrite)
  1420. {
  1421. return -E2BIG;
  1422. }
  1423. /* Get exclusive access */
  1424. ret = nxsem_wait(&priv->exclsem);
  1425. if (ret < 0)
  1426. {
  1427. return ret;
  1428. }
  1429. /* Construct and send the request to the server */
  1430. req = (FAR struct userfs_rmdir_request_s *)priv->iobuffer;
  1431. req->req = USERFS_REQ_RMDIR;
  1432. strncpy(req->relpath, relpath, priv->mxwrite);
  1433. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  1434. SIZEOF_USERFS_RMDIR_REQUEST_S(pathlen + 1), 0,
  1435. (FAR struct sockaddr *)&priv->server,
  1436. sizeof(struct sockaddr_in));
  1437. if (nsent < 0)
  1438. {
  1439. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  1440. nxsem_post(&priv->exclsem);
  1441. return (int)nsent;
  1442. }
  1443. /* Then get the response from the server */
  1444. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  1445. 0, NULL, NULL);
  1446. nxsem_post(&priv->exclsem);
  1447. if (nrecvd < 0)
  1448. {
  1449. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  1450. return (int)nrecvd;
  1451. }
  1452. if (nrecvd != sizeof(struct userfs_rmdir_response_s))
  1453. {
  1454. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  1455. return -EIO;
  1456. }
  1457. resp = (FAR struct userfs_rmdir_response_s *)priv->iobuffer;
  1458. if (resp->resp != USERFS_RESP_RMDIR)
  1459. {
  1460. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  1461. return -EIO;
  1462. }
  1463. return resp->ret;
  1464. }
  1465. /****************************************************************************
  1466. * Name: userfs_rename
  1467. *
  1468. * Description:
  1469. * Rename a directory entry
  1470. *
  1471. ****************************************************************************/
  1472. static int userfs_rename(FAR struct inode *mountpt,
  1473. FAR const char *oldrelpath,
  1474. FAR const char *newrelpath)
  1475. {
  1476. FAR struct userfs_state_s *priv;
  1477. FAR struct userfs_rename_request_s *req;
  1478. FAR struct userfs_rename_response_s *resp;
  1479. int oldpathlen;
  1480. int newpathlen;
  1481. ssize_t nsent;
  1482. ssize_t nrecvd;
  1483. int ret;
  1484. DEBUGASSERT(mountpt != NULL &&
  1485. mountpt->i_private != NULL);
  1486. priv = mountpt->i_private;
  1487. /* Check the path lengths */
  1488. DEBUGASSERT(oldrelpath != NULL && newrelpath != NULL);
  1489. oldpathlen = strlen(oldrelpath) + 1;
  1490. newpathlen = strlen(newrelpath) + 1;
  1491. if ((oldpathlen + newpathlen) > priv->mxwrite)
  1492. {
  1493. return -E2BIG;
  1494. }
  1495. /* Get exclusive access */
  1496. ret = nxsem_wait(&priv->exclsem);
  1497. if (ret < 0)
  1498. {
  1499. return ret;
  1500. }
  1501. /* Construct and send the request to the server */
  1502. req = (FAR struct userfs_rename_request_s *)priv->iobuffer;
  1503. req->req = USERFS_REQ_RENAME;
  1504. req->newoffset = oldpathlen;
  1505. strncpy(req->oldrelpath, oldrelpath, oldpathlen);
  1506. strncpy(&req->oldrelpath[oldpathlen], newrelpath, newpathlen);
  1507. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  1508. SIZEOF_USERFS_RENAME_REQUEST_S(oldpathlen, newpathlen),
  1509. 0, (FAR struct sockaddr *)&priv->server,
  1510. sizeof(struct sockaddr_in));
  1511. if (nsent < 0)
  1512. {
  1513. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  1514. nxsem_post(&priv->exclsem);
  1515. return (int)nsent;
  1516. }
  1517. /* Then get the response from the server */
  1518. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  1519. 0, NULL, NULL);
  1520. nxsem_post(&priv->exclsem);
  1521. if (nrecvd < 0)
  1522. {
  1523. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  1524. return (int)nrecvd;
  1525. }
  1526. if (nrecvd != sizeof(struct userfs_rename_response_s))
  1527. {
  1528. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  1529. return -EIO;
  1530. }
  1531. resp = (FAR struct userfs_rename_response_s *)priv->iobuffer;
  1532. if (resp->resp != USERFS_RESP_RENAME)
  1533. {
  1534. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  1535. return -EIO;
  1536. }
  1537. return resp->ret;
  1538. }
  1539. /****************************************************************************
  1540. * Name: userfs_stat
  1541. *
  1542. * Description:
  1543. * Return information about a file or directory
  1544. *
  1545. ****************************************************************************/
  1546. static int userfs_stat(FAR struct inode *mountpt, FAR const char *relpath,
  1547. FAR struct stat *buf)
  1548. {
  1549. FAR struct userfs_state_s *priv;
  1550. FAR struct userfs_stat_request_s *req;
  1551. FAR struct userfs_stat_response_s *resp;
  1552. ssize_t nsent;
  1553. ssize_t nrecvd;
  1554. int pathlen;
  1555. int ret;
  1556. DEBUGASSERT(mountpt != NULL &&
  1557. mountpt->i_private != NULL);
  1558. priv = mountpt->i_private;
  1559. /* Check the path length */
  1560. DEBUGASSERT(relpath != NULL);
  1561. pathlen = strlen(relpath);
  1562. if (pathlen > priv->mxwrite)
  1563. {
  1564. return -E2BIG;
  1565. }
  1566. /* Get exclusive access */
  1567. ret = nxsem_wait(&priv->exclsem);
  1568. if (ret < 0)
  1569. {
  1570. return ret;
  1571. }
  1572. /* Construct and send the request to the server */
  1573. req = (FAR struct userfs_stat_request_s *)priv->iobuffer;
  1574. req->req = USERFS_REQ_STAT;
  1575. strncpy(req->relpath, relpath, priv->mxwrite);
  1576. nsent = psock_sendto(&priv->psock, priv->iobuffer,
  1577. SIZEOF_USERFS_STAT_REQUEST_S(pathlen + 1), 0,
  1578. (FAR struct sockaddr *)&priv->server,
  1579. sizeof(struct sockaddr_in));
  1580. if (nsent < 0)
  1581. {
  1582. ferr("ERROR: psock_sendto failed: %d\n", (int)nsent);
  1583. nxsem_post(&priv->exclsem);
  1584. return (int)nsent;
  1585. }
  1586. /* Then get the response from the server */
  1587. nrecvd = psock_recvfrom(&priv->psock, priv->iobuffer, IOBUFFER_SIZE(priv),
  1588. 0, NULL, NULL);
  1589. nxsem_post(&priv->exclsem);
  1590. if (nrecvd < 0)
  1591. {
  1592. ferr("ERROR: psock_recvfrom failed: %d\n", (int)nrecvd);
  1593. return (int)nrecvd;
  1594. }
  1595. if (nrecvd != sizeof(struct userfs_stat_response_s))
  1596. {
  1597. ferr("ERROR: Response size incorrect: %u\n", (unsigned int)nrecvd);
  1598. return -EIO;
  1599. }
  1600. resp = (FAR struct userfs_stat_response_s *)priv->iobuffer;
  1601. if (resp->resp != USERFS_RESP_STAT)
  1602. {
  1603. ferr("ERROR: Incorrect response: %u\n", resp->resp);
  1604. return -EIO;
  1605. }
  1606. /* Return the directory entry status */
  1607. DEBUGASSERT(buf != NULL);
  1608. memcpy(buf, &resp->buf, sizeof(struct stat));
  1609. return resp->ret;
  1610. }
  1611. /****************************************************************************
  1612. * Public Functions
  1613. ****************************************************************************/