summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-17 09:35:27 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-17 09:35:27 -0600
commitf8df646dc75e62be61822713419d9447aac2419f (patch)
tree9a3eb8a956f1b51863f25d4c6df0aee710f3e5eb /nuttx
parentf631eadcb3564f39e1832932ae1c5f4277b4db86 (diff)
downloadpx4-nuttx-f8df646dc75e62be61822713419d9447aac2419f.tar.gz
px4-nuttx-f8df646dc75e62be61822713419d9447aac2419f.tar.bz2
px4-nuttx-f8df646dc75e62be61822713419d9447aac2419f.zip
Networking: Oops. Forgot to add a couple of files that were part of an earlier commit
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/net/tcp/tcp_ipselect.c110
-rw-r--r--nuttx/net/udp/udp_ipselect.c111
2 files changed, 221 insertions, 0 deletions
diff --git a/nuttx/net/tcp/tcp_ipselect.c b/nuttx/net/tcp/tcp_ipselect.c
new file mode 100644
index 000000000..9fa907052
--- /dev/null
+++ b/nuttx/net/tcp/tcp_ipselect.c
@@ -0,0 +1,110 @@
+/****************************************************************************
+ * net/tcp/tcp_ipselect.c
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <nuttx/net/netdev.h>
+#include <nuttx/net/tcp.h>
+
+#include "tcp/tcp.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: tcp_ipv4_select
+ *
+ * Description:
+ * Configure to send or receive an TCP IPv4 packet
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv4
+void tcp_ipv4_select(FAR struct net_driver_s *dev)
+{
+#ifdef CONFIG_NET_IPv6
+ /* Clear a bit in the d_flags to distinguish this from an IPv6 packet */
+
+ IFF_SET_IPv4(dev->dflags);
+#endif
+
+ /* Set the offset to the beginning of the TCP data payload */
+
+ dev->d_appdata = &dev->d_buf[IPv4TCP_HDRLEN + NET_LL_HDRLEN(dev)];
+}
+#endif /* CONFIG_NET_IPv4 */
+
+/****************************************************************************
+ * Function: tcp_ipv6_select
+ *
+ * Description:
+ * Configure to send or receive an TCP IPv6 packet
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+void tcp_ipv6_select(FAR struct net_driver_s *dev)
+{
+#ifdef CONFIG_NET_IPv4
+ /* Set a bit in the d_flags to distinguish this from an IPv6 packet */
+
+ IFF_SET_IPv6(dev->dflags);
+#endif
+
+ /* Set the offset to the beginning of the TCP data payload */
+
+ dev->d_appdata = &dev->d_buf[IPv6TCP_HDRLEN + NET_LL_HDRLEN(dev)];
+}
+#endif /* CONFIG_NET_IPv6 */
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/udp/udp_ipselect.c b/nuttx/net/udp/udp_ipselect.c
new file mode 100644
index 000000000..835e814eb
--- /dev/null
+++ b/nuttx/net/udp/udp_ipselect.c
@@ -0,0 +1,111 @@
+/****************************************************************************
+ * net/udp/udp_ipselect.c
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <nuttx/net/netdev.h>
+#include <nuttx/net/ip.h>
+#include <nuttx/net/udp.h>
+
+#include "udp/udp.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: udp_ipv4_select
+ *
+ * Description:
+ * Configure to send or receive an UDP IPv4 packet
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv4
+void udp_ipv4_select(FAR struct net_driver_s *dev)
+{
+#ifdef CONFIG_NET_IPv6
+ /* Clear a bit in the d_flags to distinguish this from an IPv6 packet */
+
+ IFF_SET_IPv4(dev->dflags);
+#endif
+
+ /* Set the offset to the beginning of the UDP data payload */
+
+ dev->d_appdata = &dev->d_buf[IPv4UDP_HDRLEN + NET_LL_HDRLEN(dev)];
+}
+#endif /* CONFIG_NET_IPv4 */
+
+/****************************************************************************
+ * Function: udp_ipv6_select
+ *
+ * Description:
+ * Configure to send or receive an UDP IPv6 packet
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+void udp_ipv6_select(FAR struct net_driver_s *dev)
+{
+#ifdef CONFIG_NET_IPv4
+ /* Set a bit in the d_flags to distinguish this from an IPv6 packet */
+
+ IFF_SET_IPv6(dev->dflags);
+#endif
+
+ /* Set the offset to the beginning of the UDP data payload */
+
+ dev->d_appdata = &dev->d_buf[IPv6UDP_HDRLEN + NET_LL_HDRLEN(dev)];
+}
+#endif /* CONFIG_NET_IPv6 */
+
+#endif /* CONFIG_NET */