usrsock_getsockopt.c 7.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253
  1. /****************************************************************************
  2. * net/usrsock/usrsock_getsockopt.c
  3. *
  4. * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved.
  5. * Author: Jussi Kivilinna <jussi.kivilinna@haltian.com>
  6. *
  7. * Redistribution and use in source and binary forms, with or without
  8. * modification, are permitted provided that the following conditions
  9. * are met:
  10. *
  11. * 1. Redistributions of source code must retain the above copyright
  12. * notice, this list of conditions and the following disclaimer.
  13. * 2. Redistributions in binary form must reproduce the above copyright
  14. * notice, this list of conditions and the following disclaimer in
  15. * the documentation and/or other materials provided with the
  16. * distribution.
  17. * 3. Neither the name NuttX nor the names of its contributors may be
  18. * used to endorse or promote products derived from this software
  19. * without specific prior written permission.
  20. *
  21. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  22. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  23. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  24. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  25. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  26. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  27. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  28. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  29. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  30. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  31. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  32. * POSSIBILITY OF SUCH DAMAGE.
  33. *
  34. ****************************************************************************/
  35. /****************************************************************************
  36. * Included Files
  37. ****************************************************************************/
  38. #include <nuttx/config.h>
  39. #if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) && \
  40. defined(CONFIG_NET_SOCKOPTS)
  41. #include <stdint.h>
  42. #include <string.h>
  43. #include <assert.h>
  44. #include <errno.h>
  45. #include <debug.h>
  46. #include <arch/irq.h>
  47. #include <sys/socket.h>
  48. #include <nuttx/semaphore.h>
  49. #include <nuttx/net/net.h>
  50. #include <nuttx/net/usrsock.h>
  51. #include "usrsock/usrsock.h"
  52. /****************************************************************************
  53. * Private Functions
  54. ****************************************************************************/
  55. static uint16_t getsockopt_event(FAR struct net_driver_s *dev, FAR void *pvconn,
  56. FAR void *pvpriv, uint16_t flags)
  57. {
  58. FAR struct usrsock_data_reqstate_s *pstate = pvpriv;
  59. FAR struct usrsock_conn_s *conn = pvconn;
  60. if (flags & USRSOCK_EVENT_ABORT)
  61. {
  62. ninfo("socket aborted.\n");
  63. pstate->reqstate.result = -ECONNABORTED;
  64. pstate->valuelen = 0;
  65. /* Stop further callbacks */
  66. pstate->reqstate.cb->flags = 0;
  67. pstate->reqstate.cb->priv = NULL;
  68. pstate->reqstate.cb->event = NULL;
  69. /* Wake up the waiting thread */
  70. nxsem_post(&pstate->reqstate.recvsem);
  71. }
  72. else if (flags & USRSOCK_EVENT_REQ_COMPLETE)
  73. {
  74. ninfo("request completed.\n");
  75. pstate->reqstate.result = conn->resp.result;
  76. if (pstate->reqstate.result < 0)
  77. {
  78. pstate->valuelen = 0;
  79. }
  80. else
  81. {
  82. pstate->valuelen = conn->resp.valuelen;
  83. }
  84. /* Stop further callbacks */
  85. pstate->reqstate.cb->flags = 0;
  86. pstate->reqstate.cb->priv = NULL;
  87. pstate->reqstate.cb->event = NULL;
  88. /* Wake up the waiting thread */
  89. nxsem_post(&pstate->reqstate.recvsem);
  90. }
  91. return flags;
  92. }
  93. /****************************************************************************
  94. * Name: do_getsockopt_request
  95. ****************************************************************************/
  96. static int do_getsockopt_request(FAR struct usrsock_conn_s *conn, int level,
  97. int option, socklen_t value_len)
  98. {
  99. struct usrsock_request_getsockopt_s req = {};
  100. struct iovec bufs[1];
  101. if (level < INT16_MIN || level > INT16_MAX)
  102. {
  103. return -EINVAL;
  104. }
  105. if (option < INT16_MIN || option > INT16_MAX)
  106. {
  107. return -EINVAL;
  108. }
  109. if (value_len > UINT16_MAX)
  110. {
  111. value_len = UINT16_MAX;
  112. }
  113. /* Prepare request for daemon to read. */
  114. req.head.reqid = USRSOCK_REQUEST_GETSOCKOPT;
  115. req.usockid = conn->usockid;
  116. req.level = level;
  117. req.option = option;
  118. req.max_valuelen = value_len;
  119. bufs[0].iov_base = (FAR void *)&req;
  120. bufs[0].iov_len = sizeof(req);
  121. return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs));
  122. }
  123. /****************************************************************************
  124. * Public Functions
  125. ****************************************************************************/
  126. /****************************************************************************
  127. * Name: usrsock_getsockopt
  128. *
  129. * Description:
  130. * getsockopt() retrieve thse value for the option specified by the
  131. * 'option' argument for the socket specified by the 'psock' argument. If
  132. * the size of the option value is greater than 'value_len', the value
  133. * stored in the object pointed to by the 'value' argument will be silently
  134. * truncated. Otherwise, the length pointed to by the 'value_len' argument
  135. * will be modified to indicate the actual length of the'value'.
  136. *
  137. * The 'level' argument specifies the protocol level of the option. To
  138. * retrieve options at the socket level, specify the level argument as
  139. * SOL_SOCKET.
  140. *
  141. * See <sys/socket.h> a complete list of values for the 'option' argument.
  142. *
  143. * Input Parameters:
  144. * conn usrsock socket connection structure
  145. * level Protocol level to set the option
  146. * option identifies the option to get
  147. * value Points to the argument value
  148. * value_len The length of the argument value
  149. *
  150. ****************************************************************************/
  151. int usrsock_getsockopt(FAR struct usrsock_conn_s *conn, int level, int option,
  152. FAR void *value, FAR socklen_t *value_len)
  153. {
  154. struct usrsock_data_reqstate_s state = {};
  155. struct iovec inbufs[1];
  156. ssize_t ret;
  157. net_lock();
  158. if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED ||
  159. conn->state == USRSOCK_CONN_STATE_ABORTED)
  160. {
  161. /* Invalid state or closed by daemon. */
  162. ninfo("usockid=%d; connect() with uninitialized usrsock.\n",
  163. conn->usockid);
  164. ret = (conn->state == USRSOCK_CONN_STATE_ABORTED) ? -EPIPE : -ECONNRESET;
  165. goto errout_unlock;
  166. }
  167. /* Set up event callback for usrsock. */
  168. ret = usrsock_setup_data_request_callback(
  169. conn, &state, getsockopt_event,
  170. USRSOCK_EVENT_ABORT | USRSOCK_EVENT_REQ_COMPLETE);
  171. if (ret < 0)
  172. {
  173. nwarn("usrsock_setup_request_callback failed: %d\n", ret);
  174. goto errout_unlock;
  175. }
  176. inbufs[0].iov_base = (FAR void *)value;
  177. inbufs[0].iov_len = *value_len;
  178. usrsock_setup_datain(conn, inbufs, ARRAY_SIZE(inbufs));
  179. /* Request user-space daemon to close socket. */
  180. ret = do_getsockopt_request(conn, level, option, *value_len);
  181. if (ret >= 0)
  182. {
  183. /* Wait for completion of request. */
  184. while ((ret = net_lockedwait(&state.reqstate.recvsem)) < 0)
  185. {
  186. DEBUGASSERT(ret == -EINTR || ret == -ECANCELED);
  187. }
  188. ret = state.reqstate.result;
  189. DEBUGASSERT(state.valuelen <= *value_len);
  190. if (ret >= 0)
  191. {
  192. /* Store length of data that was written to 'value' buffer. */
  193. *value_len = state.valuelen;
  194. }
  195. }
  196. usrsock_teardown_datain(conn);
  197. usrsock_teardown_data_request_callback(&state);
  198. errout_unlock:
  199. net_unlock();
  200. return ret;
  201. }
  202. #endif /* CONFIG_NET && CONFIG_NET_USRSOCK && CONFIG_NET_SOCKOPTS */