net_fileroute.c 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849
  1. /****************************************************************************
  2. * net/route/net_fileroute.c
  3. *
  4. * Copyright (C) 2017 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/stat.h>
  40. #include <unistd.h>
  41. #include <fcntl.h>
  42. #include <semaphore.h>
  43. #include <errno.h>
  44. #include <assert.h>
  45. #include <debug.h>
  46. #include <nuttx/semaphore.h>
  47. #include <nuttx/fs/fs.h>
  48. #include "route/fileroute.h"
  49. #include "route/route.h"
  50. #if defined(CONFIG_ROUTE_IPv4_FILEROUTE) || defined(CONFIG_ROUTE_IPv6_FILEROUTE)
  51. /****************************************************************************
  52. * Pre-processor Defintions
  53. ****************************************************************************/
  54. /* Special "impossible" PID value used to indicate that there is no holder
  55. * of the lock.
  56. */
  57. #define NO_HOLDER ((pid_t)-1)
  58. /****************************************************************************
  59. * Private Data
  60. ****************************************************************************/
  61. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  62. /* Semaphore used to lock a routing table for exclusive write-only access */
  63. static sem_t g_ipv4_exclsem;
  64. static pid_t g_ipv4_holder = NO_HOLDER;
  65. static int g_ipv4_count;
  66. #endif
  67. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  68. /* Semaphore used to lock a routing table for exclusive write-only access */
  69. static sem_t g_ipv6_exclsem;
  70. static pid_t g_ipv6_holder = NO_HOLDER;
  71. static int g_ipv6_count;
  72. #endif
  73. /****************************************************************************
  74. * Public Functions
  75. ****************************************************************************/
  76. /****************************************************************************
  77. * Name: net_openroute_detached
  78. *
  79. * Description:
  80. * Open and detach the routing table.
  81. *
  82. * Input Parameters:
  83. * pathname - The full path to the routing table entry
  84. * oflags - Open flags
  85. * filep - Location in which to return the detached file instance.
  86. *
  87. * Returned Value:
  88. * A non-negative file descriptor is returned on success. A negated errno
  89. * value is returned on any failure.
  90. *
  91. ****************************************************************************/
  92. int net_openroute_detached(FAR const char *pathname, int oflags,
  93. FAR struct file *filep)
  94. {
  95. int ret;
  96. /* Open the file for read/write access. */
  97. ret = file_open(filep, pathname, oflags, 0644);
  98. if (ret < 0)
  99. {
  100. nerr("ERROR: Failed to open %s: %d\n", pathname, ret);
  101. return ret;
  102. }
  103. return OK;
  104. }
  105. /****************************************************************************
  106. * Name: net_routesize
  107. *
  108. * Description:
  109. * Return the size of a routing table in terms of the number of entries in
  110. * the routing table.
  111. *
  112. * Input Parameters:
  113. * path - The path to the routing table
  114. * entrysize - The size of one entry in the routing table
  115. *
  116. * Returned Value:
  117. * A non-negative count of the number of entries in the routing table is
  118. * returned on success; a negated errno value is returned on and failure.
  119. *
  120. ****************************************************************************/
  121. int net_routesize(FAR const char *path, size_t entrysize)
  122. {
  123. struct stat buf;
  124. int ret;
  125. /* Get information about the file */
  126. ret = stat(path, &buf);
  127. if (ret < 0)
  128. {
  129. int errcode;
  130. /* stat() failed, but is that because the routing table has not been
  131. * created yet?
  132. */
  133. errcode = get_errno();
  134. if (errcode == ENOENT)
  135. {
  136. /* The routing table file has not been created. Return size zero. */
  137. return 0;
  138. }
  139. /* Some other error */
  140. return -errcode;
  141. }
  142. /* The directory entry at this path must be a regular file */
  143. if (S_ISREG(buf.st_mode))
  144. {
  145. unsigned int nentries = buf.st_size / entrysize;
  146. #ifdef CONFIG_DEBUG_NET_WARN
  147. if (nentries * entrysize != buf.st_size)
  148. {
  149. nwarn("WARNING: Size of routing table is not an even multiple of entries\n");
  150. nwarn(" %lu != %lu / %lu\n",
  151. (unsigned long)nentries,
  152. (unsigned long)buf.st_size,
  153. (unsigned long)entrysize);
  154. }
  155. #endif
  156. return nentries;
  157. }
  158. /* It is probably a directory (should check for sure) */
  159. return -EISDIR;
  160. }
  161. /****************************************************************************
  162. * Public Functions
  163. ****************************************************************************/
  164. /****************************************************************************
  165. * Name: net_init_fileroute
  166. *
  167. * Description:
  168. * Initialize the in-memory, RAM routing table
  169. *
  170. * Input Parameters:
  171. * None
  172. *
  173. * Returned Value:
  174. * None
  175. *
  176. * Assumptions:
  177. * Called early in initialization so that no special protection is needed.
  178. *
  179. ****************************************************************************/
  180. void net_init_fileroute(void)
  181. {
  182. /* Initialize semaphores */
  183. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  184. nxsem_init(&g_ipv4_exclsem, 0, 1);
  185. #endif
  186. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  187. nxsem_init(&g_ipv6_exclsem, 0, 1);
  188. #endif
  189. }
  190. /****************************************************************************
  191. * Name: net_openroute_ipv4/net_openroute_ipv6
  192. *
  193. * Description:
  194. * Open the IPv4/IPv6 routing table with the specified access privileges.
  195. *
  196. * Input Parameters:
  197. * oflags - Open flags
  198. * filep - Location in which to return the detached file instance.
  199. *
  200. * Returned Value:
  201. * A non-negative file descriptor is returned on success. A negated errno
  202. * value is returned on any failure.
  203. *
  204. ****************************************************************************/
  205. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  206. int net_openroute_ipv4(int oflags, FAR struct file *filep)
  207. {
  208. int ret;
  209. /* Lock the route.. we don't want to open it while it is subject to
  210. * modification.
  211. */
  212. ret = net_lockroute_ipv4();
  213. if (ret < 0)
  214. {
  215. nerr("ERROR: net_lockroute_ipv4() failed: %d\n", ret);
  216. }
  217. else
  218. {
  219. /* Open the file for read/write access. */
  220. ret = net_openroute_detached(IPv4_ROUTE_PATH, oflags, filep);
  221. if (ret < 0)
  222. {
  223. nerr("ERROR: net_openroute_detached() failed: %d\n", ret);
  224. }
  225. }
  226. (void)net_unlockroute_ipv4();
  227. return ret;
  228. }
  229. #endif
  230. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  231. int net_openroute_ipv6(int oflags, FAR struct file *filep)
  232. {
  233. int ret;
  234. /* Lock the route.. we don't want to open it while it is subject to
  235. * modification.
  236. */
  237. ret = net_lockroute_ipv6();
  238. if (ret < 0)
  239. {
  240. nerr("ERROR: net_lockroute_ipv6() failed: %d\n", ret);
  241. }
  242. else
  243. {
  244. /* Open the file for read/write access. */
  245. ret = net_openroute_detached(IPv6_ROUTE_PATH, oflags, filep);
  246. if (ret < 0)
  247. {
  248. nerr("ERROR: net_openroute_detached() failed: %d\n", ret);
  249. }
  250. }
  251. (void)net_unlockroute_ipv6();
  252. return ret;
  253. }
  254. #endif
  255. /****************************************************************************
  256. * Name: net_readroute_ipv4/net_readroute_ipv6
  257. *
  258. * Description:
  259. * Read one route entry from the IPv4/IPv6 routing table.
  260. *
  261. * Input Parameters:
  262. * filep - Detached file instance obtained by net_openroute_ipv{4|6}[_rdonly]
  263. * route - Location to return the next route read from the file
  264. *
  265. * Returned Value:
  266. * The number of bytes read on success. The special return valud of zero
  267. * indiates that the endof of file was encountered (and nothing was read).
  268. * A negated errno value is returned on any failure.
  269. *
  270. ****************************************************************************/
  271. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  272. ssize_t net_readroute_ipv4(FAR struct file *filep,
  273. FAR struct net_route_ipv4_s *route)
  274. {
  275. FAR uint8_t *dest;
  276. ssize_t ntotal;
  277. ssize_t ret;
  278. /* Lock the route.. we don't want to read from it while it is subject to
  279. * modification.
  280. */
  281. ret = (ssize_t)net_lockroute_ipv4();
  282. if (ret < 0)
  283. {
  284. nerr("ERROR: net_lockroute_ipv4() failed: %d\n", ret);
  285. return ret;
  286. }
  287. /* Read one record from the current position in the routing table */
  288. dest = (FAR uint8_t *)route;
  289. ntotal = 0;
  290. do
  291. {
  292. size_t nbytes = sizeof(struct net_route_ipv4_s) - ntotal;
  293. ssize_t nread;
  294. nread = file_read(filep, dest, nbytes);
  295. if (nread <= 0)
  296. {
  297. /* Read error or end of file */
  298. ntotal = nread;
  299. break;
  300. }
  301. ntotal += nread;
  302. dest += nread;
  303. }
  304. while (ntotal < sizeof(struct net_route_ipv4_s));
  305. (void)net_unlockroute_ipv4();
  306. return ntotal;
  307. }
  308. #endif
  309. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  310. ssize_t net_readroute_ipv6(FAR struct file *filep,
  311. FAR struct net_route_ipv6_s *route)
  312. {
  313. FAR uint8_t *dest;
  314. ssize_t ntotal;
  315. ssize_t ret;
  316. /* Lock the route.. we don't want to read from it while it is subject to
  317. * modification.
  318. */
  319. ret = (ssize_t)net_lockroute_ipv6();
  320. if (ret < 0)
  321. {
  322. nerr("ERROR: net_lockroute_ipv6() failed: %d\n", ret);
  323. return ret;
  324. }
  325. /* Read one record from the current position in the routing table */
  326. dest = (FAR uint8_t *)route;
  327. ntotal = 0;
  328. do
  329. {
  330. size_t nbytes = sizeof(struct net_route_ipv6_s) - ntotal;
  331. ssize_t nread;
  332. nread = file_read(filep, dest, nbytes);
  333. if (nread <= 0)
  334. {
  335. /* Read error or end of file */
  336. ret = nread;
  337. break;
  338. }
  339. ntotal += nread;
  340. dest += nread;
  341. }
  342. while (ntotal < sizeof(struct net_route_ipv6_s));
  343. (void)net_unlockroute_ipv6();
  344. return ntotal;
  345. }
  346. #endif
  347. /****************************************************************************
  348. * Name: net_writeroute_ipv4/net_writeroute_ipv6
  349. *
  350. * Description:
  351. * Write one route entry to the IPv4/IPv6 routing table.
  352. *
  353. * Input Parameters:
  354. * filep - Detached file instance obtained by net_openroute_ipv{4|6}[_rdonly]
  355. * route - Location to return the next route read from the file
  356. *
  357. * Returned Value:
  358. * The number of bytes written on success. A negated errno value is
  359. * returned on any failure.
  360. *
  361. ****************************************************************************/
  362. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  363. ssize_t net_writeroute_ipv4(FAR struct file *filep,
  364. FAR const struct net_route_ipv4_s *route)
  365. {
  366. FAR const uint8_t *src;
  367. ssize_t ntotal;
  368. ssize_t ret;
  369. /* Lock the route.. we don't want to write to it while it is subject to
  370. * modification.
  371. */
  372. ret = (ssize_t)net_lockroute_ipv4();
  373. if (ret < 0)
  374. {
  375. nerr("ERROR: net_lockroute_ipv4() failed: %d\n", ret);
  376. return ret;
  377. }
  378. /* Write one record at the current position in the routing table */
  379. src = (FAR const uint8_t *)route;
  380. ntotal = 0;
  381. do
  382. {
  383. size_t nbytes = sizeof(struct net_route_ipv4_s) - ntotal;
  384. ssize_t nwritten;
  385. nwritten = file_write(filep, src, nbytes);
  386. if (nwritten <= 0)
  387. {
  388. /* Write error (zero is not a valid return value for write) */
  389. ret = nwritten;
  390. break;
  391. }
  392. ntotal += nwritten;
  393. src += nwritten;
  394. }
  395. while (ntotal < sizeof(struct net_route_ipv4_s));
  396. (void)net_unlockroute_ipv4();
  397. return ntotal;
  398. }
  399. #endif
  400. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  401. ssize_t net_writeroute_ipv6(FAR struct file *filep,
  402. FAR const struct net_route_ipv6_s *route)
  403. {
  404. FAR const uint8_t *src;
  405. ssize_t ntotal;
  406. ssize_t ret;
  407. /* Lock the route.. we don't want to write to it while it is subject to
  408. * modification.
  409. */
  410. ret = (ssize_t)net_lockroute_ipv6();
  411. if (ret < 0)
  412. {
  413. nerr("ERROR: net_lockroute_ipv6() failed: %d\n", ret);
  414. return ret;
  415. }
  416. /* Write one record at the current position in the routing table */
  417. src = (FAR const uint8_t *)route;
  418. ntotal = 0;
  419. do
  420. {
  421. size_t nbytes = sizeof(struct net_route_ipv6_s) - ntotal;
  422. ssize_t nwritten;
  423. nwritten = file_write(filep, src, nbytes);
  424. if (nwritten <= 0)
  425. {
  426. /* Write error (zero is not a valid return value for write) */
  427. ntotal = nwritten;
  428. break;
  429. }
  430. ntotal += nwritten;
  431. src += nwritten;
  432. }
  433. while (ntotal < sizeof(struct net_route_ipv6_s));
  434. (void)net_unlockroute_ipv6();
  435. return ret;
  436. }
  437. #endif
  438. /****************************************************************************
  439. * Name: net_seekroute_ipv4/net_seekroute_ipv6
  440. *
  441. * Description:
  442. * Seek to a specific entry entry to the IPv4/IPv6 routing table.
  443. *
  444. * Input Parameters:
  445. * filep - Detached file instance obtained by net_openroute_ipv{4|6}[_rdonly]
  446. * index - The index of the routing table entry to seek to.
  447. *
  448. * Returned Value:
  449. * Zero (OK) is returned on success; a negated errno value is returned on
  450. * failure.
  451. *
  452. ****************************************************************************/
  453. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  454. off_t net_seekroute_ipv4(FAR struct file *filep, unsigned int index)
  455. {
  456. off_t offset;
  457. off_t ret;
  458. /* Convert the index to a file offset */
  459. offset = (off_t)index * sizeof(struct net_route_ipv4_s);
  460. /* Then seek to that position */
  461. ret = file_seek(filep, offset, SEEK_SET);
  462. if (ret < 0)
  463. {
  464. nerr("ERROR: file_seek() failed: %ld\n", (long)ret);
  465. return (int)ret;
  466. }
  467. return OK;
  468. }
  469. #endif
  470. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  471. off_t net_seekroute_ipv6(FAR struct file *filep, unsigned int index)
  472. {
  473. off_t offset;
  474. off_t ret;
  475. /* Convert the index to a file offset */
  476. offset = (off_t)index * sizeof(struct net_route_ipv6_s);
  477. /* Then seek to that position */
  478. ret = file_seek(filep, offset, SEEK_SET);
  479. if (ret < 0)
  480. {
  481. nerr("ERROR: file_seek() failed: %ld\n", (long)ret);
  482. return (int)ret;
  483. }
  484. return OK;
  485. }
  486. #endif
  487. /****************************************************************************
  488. * Name: net_routesize_ipv4/net_routesize_ipv6
  489. *
  490. * Description:
  491. * Return the size of a routing table in terms of the number of entries in
  492. * the routing table.
  493. *
  494. * Input Parameters:
  495. * None
  496. *
  497. * Returned Value:
  498. * A non-negative count of the number of entries in the routing table is
  499. * returned on success; a negated errno value is returned on and failure.
  500. *
  501. * Assumptions:
  502. * The size of the routing table may change after this size is returned
  503. * unless the routing table is locked to prevent any modification to the
  504. * routing table.
  505. *
  506. ****************************************************************************/
  507. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  508. int net_routesize_ipv4(void)
  509. {
  510. return net_routesize(IPv4_ROUTE_PATH, sizeof(struct net_route_ipv4_s));
  511. }
  512. #endif
  513. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  514. int net_routesize_ipv6(void)
  515. {
  516. return net_routesize(IPv6_ROUTE_PATH, sizeof(struct net_route_ipv6_s));
  517. }
  518. #endif
  519. /****************************************************************************
  520. * Name: net_lockroute_ipv4/net_lockroute_ipv6
  521. *
  522. * Description:
  523. * Lock access to the routing table. Necessary when a routing table is
  524. * being reorganized due to deletion of a route.
  525. *
  526. * Input Parameters:
  527. * None
  528. *
  529. * Returned Value:
  530. * Zero (OK) is returned on success; a negated errno value is returned on
  531. * any failure.
  532. *
  533. ****************************************************************************/
  534. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  535. int net_lockroute_ipv4(void)
  536. {
  537. pid_t me = getpid();
  538. int ret;
  539. /* Are we already the holder of the lock? */
  540. if (g_ipv4_holder == me)
  541. {
  542. /* Yes.. just increment the count of locks held */
  543. g_ipv4_count++;
  544. ret = OK;
  545. }
  546. else
  547. {
  548. /* No.. wait to get the lock */
  549. ret = nxsem_wait(&g_ipv4_exclsem);
  550. if (ret < 0)
  551. {
  552. nerr("ERROR: nxsem_wait() failed: %d\n", ret);
  553. }
  554. else
  555. {
  556. DEBUGASSERT(g_ipv4_holder == NO_HOLDER && g_ipv4_count == 0);
  557. /* We are now the holder with one count */
  558. g_ipv4_holder = me;
  559. g_ipv4_count = 1;
  560. }
  561. }
  562. return ret;
  563. }
  564. #endif
  565. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  566. int net_lockroute_ipv6(void)
  567. {
  568. pid_t me = getpid();
  569. int ret;
  570. /* Are we already the holder of the lock? */
  571. if (g_ipv6_holder == me)
  572. {
  573. /* Yes.. just increment the count of locks held */
  574. g_ipv6_count++;
  575. ret = OK;
  576. }
  577. else
  578. {
  579. /* No.. wait to get the lock */
  580. ret = nxsem_wait(&g_ipv6_exclsem);
  581. if (ret < 0)
  582. {
  583. nerr("ERROR: nxsem_wait() failed: %d\n", ret);
  584. }
  585. else
  586. {
  587. DEBUGASSERT(g_ipv6_holder == NO_HOLDER && g_ipv6_count == 0);
  588. /* We are now the holder with one count */
  589. g_ipv6_holder = me;
  590. g_ipv6_count = 1;
  591. }
  592. }
  593. return ret;
  594. }
  595. #endif
  596. /****************************************************************************
  597. * Name: net_unlockroute_ipv4/net_unlockroute_ipv6
  598. *
  599. * Description:
  600. * Release the read lock.
  601. *
  602. * Input Parameters:
  603. * None
  604. *
  605. * Returned Value:
  606. * Zero (OK) is returned on success; a negated errno value is returned on
  607. * any failure.
  608. *
  609. ****************************************************************************/
  610. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  611. int net_unlockroute_ipv4(void)
  612. {
  613. pid_t me = getpid();
  614. int ret;
  615. /* If would be an error if we are called with on a thread that does not
  616. * hold the lock.
  617. */
  618. DEBUGASSERT(me == g_ipv4_holder && g_ipv4_count > 0);
  619. /* Release the count on the lock. If this is the last count, then release
  620. * the lock.
  621. */
  622. if (g_ipv4_count > 1)
  623. {
  624. /* Not the last count... just decrement the count and return success */
  625. g_ipv4_count--;
  626. ret = OK;
  627. }
  628. else
  629. {
  630. /* This is the last count. Release the lock */
  631. g_ipv4_holder = NO_HOLDER;
  632. g_ipv4_count = 0;
  633. ret = nxsem_post(&g_ipv4_exclsem);
  634. if (ret < 0)
  635. {
  636. nerr("ERROR: nxsem_post() failed: %d\n", ret);
  637. }
  638. }
  639. return ret;
  640. }
  641. #endif
  642. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  643. int net_unlockroute_ipv6(void)
  644. {
  645. pid_t me = getpid();
  646. int ret;
  647. /* If would be an error if we are called with on a thread that does not
  648. * hold the lock.
  649. */
  650. DEBUGASSERT(me == g_ipv6_holder && g_ipv6_count > 0);
  651. /* Release the count on the lock. If this is the last count, then release
  652. * the lock.
  653. */
  654. if (g_ipv6_count > 1)
  655. {
  656. /* Not the last count... just decrement the count and return success */
  657. g_ipv6_count--;
  658. ret = OK;
  659. }
  660. else
  661. {
  662. /* This is the last count. Release the lock */
  663. g_ipv6_holder = NO_HOLDER;
  664. g_ipv6_count = 0;
  665. ret = nxsem_post(&g_ipv6_exclsem);
  666. if (ret < 0)
  667. {
  668. nerr("ERROR: nxsem_post() failed: %d\n", ret);
  669. }
  670. }
  671. return ret;
  672. }
  673. #endif
  674. /****************************************************************************
  675. * Name: net_closeroute_ipv4/net_closeroute_ipv6
  676. *
  677. * Description:
  678. * Close the IPv4/IPv6 routing table.
  679. *
  680. * Input Parameters:
  681. * filep - Detached file instance obtained by net_openroute_ipv{4|6}[_rdonly]
  682. *
  683. * Returned Value:
  684. * Zero (OK) is returned on success. A negated errno value is returned on
  685. * any failure.
  686. *
  687. ****************************************************************************/
  688. #ifdef CONFIG_ROUTE_IPv4_FILEROUTE
  689. int net_closeroute_ipv4(FAR struct file *filep)
  690. {
  691. return file_close(filep);
  692. }
  693. #endif
  694. #ifdef CONFIG_ROUTE_IPv6_FILEROUTE
  695. int net_closeroute_ipv6(FAR struct file *filep)
  696. {
  697. return file_close(filep);
  698. }
  699. #endif
  700. #endif /* CONFIG_ROUTE_IPv4_FILEROUTE || CONFIG_ROUTE_IPv6_FILEROUTE */