First check-in of Lazlo's PF_PACKET 'raw' socket implementation

This commit is contained in:
Gregory Nutt 2014-06-12 11:52:06 -06:00
parent 96c6f34825
commit faaf641490
17 changed files with 1720 additions and 204 deletions

View File

@ -56,6 +56,9 @@
#include <nuttx/net/uip/uip.h>
#include <nuttx/net/arp.h>
#include <nuttx/net/uip/uip-arch.h>
#if defined(CONFIG_NET_PKT)
# include <nuttx/net/uip/uip-pkt.h>
#endif
#include "up_internal.h"
@ -1589,6 +1592,12 @@ static void stm32_receive(FAR struct stm32_ethmac_s *priv)
while (stm32_recvframe(priv) == OK)
{
#ifdef CONFIG_NET_PKT
/* When packet sockets are enabled, feed the frame into the packet tap */
uip_pktinput(&priv->dev);
#endif
/* Check if the packet is a valid size for the uIP buffer configuration
* (this should not happen)
*/

View File

@ -0,0 +1,61 @@
/****************************************************************************
* include/netpacket/netpacket.h
* Definitions for use with AF_PACKET sockets
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Author: Lazlo <dlsitzer@gmail.comg>
*
* Includes some definitions that a compatible with the LGPL GNU C Library
* header file of the same name.
*
* 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.
*
****************************************************************************/
#ifndef __INCLUDE_NETPACKET_PACKET_H
#define __INCLUDE_NETPACKET_PACKET_H 1
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
/****************************************************************************
* Public Types
****************************************************************************/
struct sockaddr_ll
{
uint16_t sll_family;
uint16_t sll_protocol;
sint16_t sll_ifindex;
};
#endif /* __INCLUDE_NETPACKET_PACKET_H */

View File

@ -0,0 +1,106 @@
/****************************************************************************
* include/netpacket/netpacket.h
* Definitions for use with AF_PACKET sockets
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Author: Lazlo <dlsitzer@gmail.comg>
*
* Includes some definitions that a compatible with the LGPL GNU C Library
* header file of the same name.
*
* 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.
*
****************************************************************************/
#ifndef __INCLUDE_NUTTX_NET_UIP_UIP_PKT_H
#define __INCLUDE_NUTTX_NET_UIP_UIP_PKT_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <nuttx/net/uip/uipopt.h>
/****************************************************************************
* Public Type Definitions
****************************************************************************/
/* Representation of a uIP packet socket connection */
struct uip_pkt_conn
{
dq_entry_t node; /* Supports a double linked list */
uint8_t lmac[6]; /* The local Ethernet address in network byte order */
uint8_t ifindex;
uint16_t proto;
uint8_t crefs; /* Reference counts on this instance */
/* Defines the list of packet callbacks */
struct uip_callback_s *list;
};
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/* uIP application functions
*
* Functions used by an application running of top of uIP. This includes
* functions for opening and closing connections, sending and receiving
* data, etc.
*
* Find a free connection structure and allocate it for use. This is
* normally something done by the implementation of the socket() API
*/
struct uip_pkt_conn *uip_pktalloc(void);
/* Allocate a new packet socket data callback */
#define uip_pktcallbackalloc(conn) uip_callbackalloc(&conn->list)
#define uip_pktcallbackfree(conn,cb) uip_callbackfree(cb, &conn->list)
/* Free a connection structure that is no longer in use. This should
* be done by the implementation of close()
*/
void uip_pktfree(struct uip_pkt_conn *conn);
void uip_pktpoll(struct uip_driver_s *dev, struct uip_pkt_conn *conn);
int uip_pktinput(struct uip_driver_s *dev);
#endif /* __INCLUDE_NUTTX_NET_UIP_UIP_PKT_H */

View File

@ -227,6 +227,9 @@ struct uip_callback_s
/* Protocol-specific support */
#ifdef CONFIG_NET_PKT
# include <nuttx/net/uip/uip-pkt.h>
#endif
#ifdef CONFIG_NET_TCP
# include <nuttx/net/uip/uip-tcp.h>
#endif

View File

@ -83,6 +83,25 @@ config NET_SOLINGER
endif # NET_SOCKOPTS
config NET_PKT
bool "Socket packet socket support"
default n
---help---
Enable or disbale support for packet sockets.
Packet sockets allow receiving and transmitting frames without
a transport protocol in between. Frames received are copied into
a packet socket tap before they enter uIP. Data written into a
packet socket will bypass uIP altogether and be placed in the
transmission buffer of the network interface driver.
if NET_PKT
config NET_PKT_CONNS
int "Max packet sockets"
default 1
endif # NET_PKT
config NET_BUFSIZE
int "Network packet buffer size (MTU)"
default 1294 if !NET_SLIP && NET_IPv6

View File

@ -1,7 +1,7 @@
/****************************************************************************
* net/bind.c
*
* Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
* Copyright (C) 2007-2009, 2012, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -43,11 +43,64 @@
#include <sys/types.h>
#include <sys/socket.h>
#include <errno.h>
#include <string.h>
#ifdef CONFIG_NET_PKT
# include <netpacket/packet.h>
#endif
#include "net_internal.h"
/****************************************************************************
* Global Functions
* Private Functions
****************************************************************************/
/****************************************************************************
* Function: pkt_rawbind
*
* Description:
* Bind a raw socket to an network device.
*
* Parameters:
* conn AF_PACKET connection structure
* addr Peer address information
*
* Returned Value:
* 0 on success; -1 on error with errno set appropriately
*
****************************************************************************/
#ifdef CONFIG_NET_PKT
static int pkt_rawbind(FAR struct uip_pkt_conn *conn,
FAR const struct sockaddr_ll *addr)
{
int ifindex;
#if 0
char hwaddr[6] = {0x00, 0xa1, 0xb1, 0xc1, 0xd1, 0xe1}; /* our MAC for debugging */
#endif
char hwaddr[6] = {0x00, 0xe0, 0xde, 0xad, 0xbe, 0xef}; /* MAC from ifconfig */
/* Look at the addr and identify network interface */
ifindex = addr->sll_ifindex;
#if 0
/* Get the MAC address of that interface */
memcpy(hwaddr, g_netdevices->d_mac, 6);
#endif
/* Put ifindex and mac address into connection */
conn->ifindex = ifindex;
memcpy(conn->lmac, hwaddr, 6);
return OK;
}
#endif /* CONFIG_NET_PKT */
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
@ -83,6 +136,9 @@
int psock_bind(FAR struct socket *psock, const struct sockaddr *addr,
socklen_t addrlen)
{
#ifdef CONFIG_NET_PKT
FAR const struct sockaddr_ll *lladdr = (const struct sockaddr_ll *)addr;
#endif
#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
#ifdef CONFIG_NET_IPv6
FAR const struct sockaddr_in6 *inaddr = (const struct sockaddr_in6 *)addr;
@ -105,9 +161,13 @@ int psock_bind(FAR struct socket *psock, const struct sockaddr *addr,
/* Verify that a valid address has been provided */
#ifdef CONFIG_NET_IPv6
if (addr->sa_family != AF_INET6 || addrlen < sizeof(struct sockaddr_in6))
if ((addr->sa_family != AF_PACKET && addr->sa_family != AF_INET6) ||
(addr->sa_family == AF_PACKET && addrlen < sizeof(struct sockaddr_ll)) ||
(addr->sa_family == AF_INET6 && addrlen < sizeof(struct sockaddr_in6)))
#else
if (addr->sa_family != AF_INET || addrlen < sizeof(struct sockaddr_in))
if ((addr->sa_family != AF_PACKET && addr->sa_family != AF_INET) ||
(addr->sa_family == AF_PACKET && addrlen < sizeof(struct sockaddr_ll)) ||
(addr->sa_family == AF_INET && addrlen < sizeof(struct sockaddr_in)))
#endif
{
err = EBADF;
@ -118,6 +178,12 @@ int psock_bind(FAR struct socket *psock, const struct sockaddr *addr,
switch (psock->s_type)
{
#ifdef CONFIG_NET_PKT
case SOCK_RAW:
ret = pkt_rawbind(psock->s_conn, lladdr);
break;
#endif
#ifdef CONFIG_NET_TCP
case SOCK_STREAM:
ret = uip_tcpbind(psock->s_conn, inaddr);

View File

@ -55,6 +55,10 @@
#include <nuttx/net/arp.h>
#include <nuttx/net/uip/uip-arch.h>
#ifdef CONFIG_NET_PKT
# include <nuttx/net/uip/uip-pkt.h>
#endif
#include "net_internal.h"
#include "uip/uip_internal.h"
@ -115,7 +119,9 @@ struct send_s
*
****************************************************************************/
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
#if defined(CONFIG_NET_TCP) && defined(CONFIG_NET_SOCKOPTS) && \
!defined(CONFIG_DISABLE_CLOCK)
static inline int send_timeout(FAR struct send_s *pstate)
{
FAR struct socket *psock = 0;
@ -139,7 +145,191 @@ static inline int send_timeout(FAR struct send_s *pstate)
#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
/****************************************************************************
* Function: send_interrupt
* Function: pktsend_interrupt
****************************************************************************/
#if defined(CONFIG_NET_PKT)
static uint16_t pktsend_interrupt(FAR struct uip_driver_s *dev,
FAR void *pvconn,
FAR void *pvpriv, uint16_t flags)
{
FAR struct send_s *pstate = (FAR struct send_s *)pvpriv;
nllvdbg("flags: %04x sent: %d\n", flags, pstate->snd_sent);
if (pstate)
{
/* Check if the outgoing packet is available. If my have been claimed
* by a send interrupt serving a different thread -OR- if the output
* buffer currently contains unprocessed incoming data. In these cases
* we will just have to wait for the next polling cycle.
*/
if (dev->d_sndlen > 0 || (flags & UIP_NEWDATA) != 0)
{
/* Another thread has beat us sending data or the buffer is busy,
* Check for a timeout. If not timed out, wait for the next
* polling cycle and check again.
*/
/* No timeout. Just wait for the next polling cycle */
return flags;
}
/* It looks like we are good to send the data */
else
{
/* Copy the user data into d_snddata and send it */
#if 0
uip_send(dev, pstate->snd_buffer, pstate->snd_buflen);
pstate->snd_sent = pstate->snd_buflen;
#else
/* NOTE: This is almost identical to calling uip_send() while
* the data from the sent operation buffer is copied into dev->d_buf
* instead of dev->d_snddata
*/
if (pstate->snd_buflen > 0 && pstate->snd_buflen < CONFIG_NET_BUFSIZE)
{
memcpy(dev->d_buf, pstate->snd_buffer, pstate->snd_buflen);
dev->d_sndlen = pstate->snd_buflen;
}
pstate->snd_sent = pstate->snd_buflen;
#endif
}
/* Don't allow any further call backs. */
pstate->snd_cb->flags = 0;
pstate->snd_cb->priv = NULL;
pstate->snd_cb->event = NULL;
/* Wake up the waiting thread */
sem_post(&pstate->snd_sem);
}
return flags;
}
#endif /* CONFIG_NET_PKT */
/****************************************************************************
* Function: pktsend
****************************************************************************/
#if defined(CONFIG_NET_PKT)
static ssize_t pktsend(FAR struct socket *psock, FAR const void *buf,
size_t len, int flags)
{
struct send_s state;
uip_lock_t save;
int err;
int ret;
/* Verify that the sockfd corresponds to valid, allocated socket */
if (!psock || psock->s_crefs <= 0)
{
err = EBADF;
goto errout;
}
/* Set the socket state to sending */
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND);
/* Perform the send operation */
/* Initialize the state structure. This is done with interrupts
* disabled because we don't want anything to happen until we
* are ready.
*/
save = uip_lock();
memset(&state, 0, sizeof(struct send_s));
(void)sem_init(&state.snd_sem, 0, 0); /* Doesn't really fail */
state.snd_sock = psock; /* Socket descriptor to use */
state.snd_buflen = len; /* Number of bytes to send */
state.snd_buffer = buf; /* Buffer to send from */
if (len > 0)
{
struct uip_pkt_conn *conn = (struct uip_pkt_conn*)psock->s_conn;
/* Allocate resource to receive a callback */
state.snd_cb = uip_pktcallbackalloc(conn);
if (state.snd_cb)
{
/* Set the initial time for calculating timeouts */
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
state.snd_time = clock_systimer();
#endif
/* Set up the callback in the connection */
state.snd_cb->flags = UIP_POLL;
state.snd_cb->priv = (void*)&state;
state.snd_cb->event = pktsend_interrupt;
/* Wait for the send to complete or an error to occure: NOTES: (1)
* uip_lockedwait will also terminate if a signal is received, (2)
* interrupts may be disabled! They will be re-enabled while the
* task sleeps and automatically re-enabled when the task restarts.
*/
ret = uip_lockedwait(&state.snd_sem);
/* Make sure that no further interrupts are processed */
uip_pktcallbackfree(conn, state.snd_cb);
}
}
sem_destroy(&state.snd_sem);
uip_unlock(save);
/* Set the socket state to idle */
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
/* Check for a errors, Errors are signalled by negative errno values
* for the send length
*/
if (state.snd_sent < 0)
{
err = state.snd_sent;
goto errout;
}
/* If uip_lockedwait failed, then we were probably reawakened by a signal. In
* this case, uip_lockedwait will have set errno appropriately.
*/
if (ret < 0)
{
err = -ret;
goto errout;
}
/* Return the number of bytes actually sent */
return state.snd_sent;
errout:
set_errno(err);
return ERROR;
}
#endif /* CONFIG_NET_PKT */
/****************************************************************************
* Function: tcpsend_interrupt
*
* Description:
* This function is called from the interrupt level to perform the actual
@ -158,8 +348,10 @@ static inline int send_timeout(FAR struct send_s *pstate)
*
****************************************************************************/
static uint16_t send_interrupt(FAR struct uip_driver_s *dev, FAR void *pvconn,
FAR void *pvpriv, uint16_t flags)
#if defined(CONFIG_NET_TCP)
static uint16_t tcpsend_interrupt(FAR struct uip_driver_s *dev,
FAR void *pvconn,
FAR void *pvpriv, uint16_t flags)
{
FAR struct uip_conn *conn = (FAR struct uip_conn*)pvconn;
FAR struct send_s *pstate = (FAR struct send_s *)pvpriv;
@ -358,7 +550,7 @@ static uint16_t send_interrupt(FAR struct uip_driver_s *dev, FAR void *pvconn,
if ((pstate->snd_sent - pstate->snd_acked + sndlen) < conn->winsize)
{
/* Set the sequence number for this packet. NOTE: uIP updates
* sndseq on recept of ACK *before* this function is called. In that
* sndseq on receipt of ACK *before* this function is called. In that
* case sndseq will point to the next unacknowledged byte (which might
* have already been sent). We will overwrite the value of sndseq
* here before the packet is sent.
@ -436,6 +628,139 @@ end_wait:
sem_post(&pstate->snd_sem);
return flags;
}
#endif
/****************************************************************************
* Function: tcpsend
****************************************************************************/
#if defined(CONFIG_NET_TCP)
ssize_t tcpsend(FAR struct socket *psock, FAR const void *buf, size_t len,
int flags)
{
struct send_s state;
uip_lock_t save;
int err;
int ret = OK;
/* Verify that the sockfd corresponds to valid, allocated socket */
if (!psock || psock->s_crefs <= 0)
{
err = EBADF;
goto errout;
}
/* If this is an un-connected socket, then return ENOTCONN */
if (psock->s_type != SOCK_STREAM || !_SS_ISCONNECTED(psock->s_flags))
{
err = ENOTCONN;
goto errout;
}
/* Set the socket state to sending */
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND);
/* Perform the TCP send operation */
/* Initialize the state structure. This is done with interrupts
* disabled because we don't want anything to happen until we
* are ready.
*/
save = uip_lock();
memset(&state, 0, sizeof(struct send_s));
(void)sem_init(&state. snd_sem, 0, 0); /* Doesn't really fail */
state.snd_sock = psock; /* Socket descriptor to use */
state.snd_buflen = len; /* Number of bytes to send */
state.snd_buffer = buf; /* Buffer to send from */
if (len > 0)
{
struct uip_conn *conn = (struct uip_conn*)psock->s_conn;
/* Allocate resources to receive a callback */
state.snd_cb = uip_tcpcallbackalloc(conn);
if (state.snd_cb)
{
/* Get the initial sequence number that will be used */
state.snd_isn = uip_tcpgetsequence(conn->sndseq);
/* There is no outstanding, unacknowledged data after this
* initial sequence number.
*/
conn->unacked = 0;
/* Set the initial time for calculating timeouts */
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
state.snd_time = clock_systimer();
#endif
/* Set up the callback in the connection */
state.snd_cb->flags = UIP_ACKDATA|UIP_REXMIT|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
state.snd_cb->priv = (void*)&state;
state.snd_cb->event = tcpsend_interrupt;
/* Notify the device driver of the availability of TX data */
netdev_txnotify(conn->ripaddr);
/* Wait for the send to complete or an error to occur: NOTES: (1)
* uip_lockedwait will also terminate if a signal is received, (2) interrupts
* may be disabled! They will be re-enabled while the task sleeps and
* automatically re-enabled when the task restarts.
*/
ret = uip_lockedwait(&state. snd_sem);
/* Make sure that no further interrupts are processed */
uip_tcpcallbackfree(conn, state.snd_cb);
}
}
sem_destroy(&state. snd_sem);
uip_unlock(save);
/* Set the socket state to idle */
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
/* Check for a errors. Errors are signalled by negative errno values
* for the send length
*/
if (state.snd_sent < 0)
{
err = state.snd_sent;
goto errout;
}
/* If uip_lockedwait failed, then we were probably reawakened by a signal. In
* this case, uip_lockedwait will have set errno appropriately.
*/
if (ret < 0)
{
err = -ret;
goto errout;
}
/* Return the number of bytes actually sent */
return state.snd_sent;
errout:
set_errno(err);
return ERROR;
}
#endif
/****************************************************************************
* Public Functions
@ -508,127 +833,33 @@ end_wait:
ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len,
int flags)
{
struct send_s state;
uip_lock_t save;
int err;
int ret = OK;
int ret;
/* Verify that the sockfd corresponds to valid, allocated socket */
if (!psock || psock->s_crefs <= 0)
switch (psock->s_type)
{
err = EBADF;
goto errout;
}
/* If this is an un-connected socket, then return ENOTCONN */
if (psock->s_type != SOCK_STREAM || !_SS_ISCONNECTED(psock->s_flags))
{
err = ENOTCONN;
goto errout;
}
/* Set the socket state to sending */
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND);
/* Perform the TCP send operation */
/* Initialize the state structure. This is done with interrupts
* disabled because we don't want anything to happen until we
* are ready.
*/
save = uip_lock();
memset(&state, 0, sizeof(struct send_s));
(void)sem_init(&state. snd_sem, 0, 0); /* Doesn't really fail */
state.snd_sock = psock; /* Socket descriptor to use */
state.snd_buflen = len; /* Number of bytes to send */
state.snd_buffer = buf; /* Buffer to send from */
if (len > 0)
{
struct uip_conn *conn = (struct uip_conn*)psock->s_conn;
/* Allocate resources to receive a callback */
state.snd_cb = uip_tcpcallbackalloc(conn);
if (state.snd_cb)
#if defined(CONFIG_NET_PKT)
case SOCK_RAW:
{
/* Get the initial sequence number that will be used */
state.snd_isn = uip_tcpgetsequence(conn->sndseq);
/* There is no outstanding, unacknowledged data after this
* initial sequence number.
*/
conn->unacked = 0;
/* Set the initial time for calculating timeouts */
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
state.snd_time = clock_systimer();
ret = pktsend(psock, buf, len, flags);
break;
}
#endif
/* Set up the callback in the connection */
state.snd_cb->flags = UIP_ACKDATA|UIP_REXMIT|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
state.snd_cb->priv = (void*)&state;
state.snd_cb->event = send_interrupt;
#if defined(CONFIG_NET_TCP)
case SOCK_STREAM:
{
ret = tcpsend(psock, buf, len, flags);
break;
}
#endif
/* Notify the device driver of the availability of TX data */
netdev_txnotify(conn->ripaddr);
/* Wait for the send to complete or an error to occur: NOTES: (1)
* uip_lockedwait will also terminate if a signal is received, (2) interrupts
* may be disabled! They will be re-enabled while the task sleeps and
* automatically re-enabled when the task restarts.
*/
ret = uip_lockedwait(&state. snd_sem);
/* Make sure that no further interrupts are processed */
uip_tcpcallbackfree(conn, state.snd_cb);
default:
{
ret = ERROR;
}
}
sem_destroy(&state. snd_sem);
uip_unlock(save);
/* Set the socket state to idle */
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
/* Check for a errors. Errors are signalled by negative errno values
* for the send length
*/
if (state.snd_sent < 0)
{
err = state.snd_sent;
goto errout;
}
/* If uip_lockedwait failed, then we were probably reawakened by a signal. In
* this case, uip_lockedwait will have set errno appropriately.
*/
if (ret < 0)
{
err = -ret;
goto errout;
}
/* Return the number of bytes actually sent */
return state.snd_sent;
errout:
set_errno(err);
return ERROR;
return ret;
}
#endif /* CONFIG_NET && CONFIG_NET_TCP && !CONFIG_NET_TCP_WRITE_BUFFERS */

View File

@ -48,6 +48,10 @@
#include <errno.h>
#include <debug.h>
#ifdef CONFIG_NET_PKT
# include <netpacket/packet.h>
#endif
#include <arch/irq.h>
#include <nuttx/clock.h>
#include <nuttx/net/uip/uip-arch.h>
@ -141,6 +145,52 @@ static size_t recvfrom_newdata(FAR struct uip_driver_s *dev,
}
#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
/****************************************************************************
* Function: recvfrom_newpktdata
*
* Description:
* Copy the read data from the packet
*
* Parameters:
* dev The structure of the network driver that caused the interrupt
* pstate recvfrom state structure
*
* Returned Value:
* None.
*
* Assumptions:
* Running at the interrupt level
*
****************************************************************************/
#ifdef CONFIG_NET_PKT
static void recvfrom_newpktdata(FAR struct uip_driver_s *dev,
FAR struct recvfrom_s *pstate)
{
size_t recvlen;
if (dev->d_len > pstate->rf_buflen)
{
recvlen = pstate->rf_buflen;
}
else
{
recvlen = dev->d_len;
}
/* Copy the new packet data into the user buffer */
memcpy(pstate->rf_buffer, dev->d_buf, recvlen);
nllvdbg("Received %d bytes (of %d)\n", (int)recvlen, (int)dev->d_len);
/* Update the accumulated size of the data read */
pstate->rf_recvlen += recvlen;
pstate->rf_buffer += recvlen;
pstate->rf_buffer -= recvlen;
}
#endif /* CONFIG_NET_PKT */
/****************************************************************************
* Function: recvfrom_newtcpdata
*
@ -252,7 +302,7 @@ static inline void recvfrom_newudpdata(FAR struct uip_driver_s *dev,
* Copy the read data from the packet
*
* Parameters:
* dev The sructure of the network driver that caused the interrupt
* dev The structure of the network driver that caused the interrupt
* pstate recvfrom state structure
*
* Returned Value:
@ -406,6 +456,89 @@ static int recvfrom_timeout(struct recvfrom_s *pstate)
#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
/****************************************************************************
* Function: recvfrom_pktsender
*
* Description:
*
* Parameters:
*
* Returned Values:
*
* Assumptions:
*
****************************************************************************/
#ifdef CONFIG_NET_PKT
static inline void recvfrom_pktsender(FAR struct uip_driver_s *dev,
FAR struct recvfrom_s *pstate)
{
}
#endif /* CONFIG_NET_PKT */
/****************************************************************************
* Function: recvfrom_pktinterrupt
*
* Description:
*
* Parameters:
*
* Returned Values:
*
* Assumptions:
*
****************************************************************************/
#ifdef CONFIG_NET_PKT
static uint16_t recvfrom_pktinterrupt(FAR struct uip_driver_s *dev,
FAR void *conn, FAR void *pvpriv,
uint16_t flags)
{
struct recvfrom_s *pstate = (struct recvfrom_s *)pvpriv;
nllvdbg("flags: %04x\n", flags);
/* 'priv' might be null in some race conditions (?) */
if (pstate)
{
/* If a new packet is available, then complete the read action. */
if ((flags & UIP_NEWDATA) != 0)
{
/* Copy the packet */
recvfrom_newpktdata(dev, pstate);
/* We are finished. */
nllvdbg("PKT done\n");
/* Don't allow any further call backs. */
pstate->rf_cb->flags = 0;
pstate->rf_cb->priv = NULL;
pstate->rf_cb->event = NULL;
#if 0
/* Save the sender's address in the caller's 'from' location */
recvfrom_pktsender(dev, pstate);
#endif
/* indicate that the data has been consumed */
flags &= ~UIP_NEWDATA;
/* Wake up the waiting thread, returning the number of bytes
* actually read.
*/
sem_post(&pstate->rf_sem);
}
}
return flags;
}
#endif /* CONFIG_NET_PKT */
/****************************************************************************
* Function: recvfrom_tcpsender
*
@ -647,6 +780,7 @@ static uint16_t recvfrom_tcpinterrupt(FAR struct uip_driver_s *dev,
}
#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
}
return flags;
}
#endif /* CONFIG_NET_TCP */
@ -700,7 +834,7 @@ static inline void recvfrom_udpsender(struct uip_driver_s *dev, struct recvfrom_
* UDP receive operation via by the uIP layer.
*
* Parameters:
* dev The sructure of the network driver that caused the interrupt
* dev The structure of the network driver that caused the interrupt
* conn The connection structure associated with the socket
* flags Set of events describing why the callback was invoked
*
@ -746,11 +880,11 @@ static uint16_t recvfrom_udpinterrupt(struct uip_driver_s *dev, void *pvconn,
recvfrom_udpsender(dev, pstate);
/* Indicate that the data has been consumed */
/* Indicate that the data has been consumed */
flags &= ~UIP_NEWDATA;
/* Wake up the waiting thread, returning the number of bytes
/* Wake up the waiting thread, returning the number of bytes
* actually read.
*/
@ -786,6 +920,7 @@ static uint16_t recvfrom_udpinterrupt(struct uip_driver_s *dev, void *pvconn,
}
#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
}
return flags;
}
#endif /* CONFIG_NET_UDP */
@ -890,6 +1025,89 @@ static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate)
}
#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
/****************************************************************************
* Function: pkt_recvfrom
*
* Description:
* Perform the recvfrom operation for packet socket
*
* Parameters:
*
* Returned Value:
*
* Assumptions:
*
****************************************************************************/
#ifdef CONFIG_NET_PKT
static ssize_t pkt_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
FAR struct sockaddr_ll *from)
{
struct uip_pkt_conn *conn = (struct uip_pkt_conn *)psock->s_conn;
struct recvfrom_s state;
uip_lock_t save;
int ret;
/* Perform the packet recvfrom() operation */
/* Initialize the state structure. This is done with interrupts
* disabled because we don't want anything to happen until we
* are ready.
*/
save = uip_lock();
recvfrom_init(psock, buf, len, (struct sockaddr_in *)from, &state);
/* TODO recvfrom_init() expects from to be of type sockaddr_in, but
* in our case is sockaddr_ll
*/
#if 0
ret = uip_pktconnect(conn, NULL);
if (ret < 0)
{
goto errout_with_state;
}
#endif
/* Set up the callback in the connection */
state.rf_cb = uip_pktcallbackalloc(conn);
if (state.rf_cb)
{
state.rf_cb->flags = UIP_NEWDATA|UIP_POLL;
state.rf_cb->priv = (void*)&state;
state.rf_cb->event = recvfrom_pktinterrupt;
/* Notify the device driver of the receive call */
/* netdev_rxnotify(conn->ripaddr); */
/* Wait for either the receive to complete or for an error/timeout to occur.
* NOTES: (1) uip_lockedwait will also terminate if a signal is received, (2)
* interrupts are disabled! They will be re-enabled while the task sleeps
* and automatically re-enabled when the task restarts.
*/
ret = uip_lockedwait(&state.rf_sem);
/* Make sure that no further interrupts are processed */
uip_pktcallbackfree(conn, state.rf_cb);
ret = recvfrom_result(ret, &state);
}
else
{
ret = -EBUSY;
}
errout_with_state:
uip_unlock(save);
recvfrom_uninit(&state);
return ret;
}
#endif /* CONFIG_NET_PKT */
/****************************************************************************
* Function: udp_recvfrom
*
@ -900,7 +1118,7 @@ static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate)
* psock Pointer to the socket structure for the SOCK_DRAM socket
* buf Buffer to receive data
* len Length of buffer
* infrom INET ddress of source (may be NULL)
* infrom INET address of source (may be NULL)
*
* Returned Value:
* On success, returns the number of characters sent. On error,
@ -992,7 +1210,7 @@ errout_with_state:
* psock Pointer to the socket structure for the SOCK_DRAM socket
* buf Buffer to receive data
* len Length of buffer
* infrom INET ddress of source (may be NULL)
* infrom INET address of source (may be NULL)
*
* Returned Value:
* On success, returns the number of characters sent. On error,
@ -1113,7 +1331,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
* 1) Make sure thet there is buffer space to receive additional data
* (state.rf_buflen > 0). This could be zero, for example, if read-ahead
* buffering was enabled and we filled the user buffer with data from
* the read-ahead buffers. Aand
* the read-ahead buffers. And
* 2) if read-ahead buffering is enabled (CONFIG_NET_TCP_READAHEAD)
* and delay logic is disabled (CONFIG_NET_TCP_RECVDELAY == 0), then we
* not want to wait if we already obtained some data from the read-ahead
@ -1190,7 +1408,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
* Returned Value:
* On success, returns the number of characters sent. If no data is
* available to be received and the peer has performed an orderly shutdown,
* recv() will return 0. Othwerwise, on errors, -1 is returned, and errno
* recv() will return 0. Otherwise, on errors, -1 is returned, and errno
* is set appropriately:
*
* EAGAIN
@ -1225,6 +1443,9 @@ ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
int flags,FAR struct sockaddr *from,
FAR socklen_t *fromlen)
{
#if defined(CONFIG_NET_PKT)
FAR struct sockaddr_ll *llfrom = (struct sockaddr_ll *)from;
#endif
#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP)
#ifdef CONFIG_NET_IPv6
FAR struct sockaddr_in6 *infrom = (struct sockaddr_in6 *)from;
@ -1275,24 +1496,34 @@ ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_RECV);
/* Perform the TCP/IP or UDP recv() operation */
/* Read from the network interface driver buffer */
/* Or perform the TCP/IP or UDP recv() operation */
#if defined(CONFIG_NET_UDP) && defined(CONFIG_NET_TCP)
#if defined(CONFIG_NET_PKT)
if (psock->s_type == SOCK_RAW)
{
ret = pkt_recvfrom(psock, buf, len, llfrom);
}
else
#endif
#if defined(CONFIG_NET_TCP)
if (psock->s_type == SOCK_STREAM)
{
ret = tcp_recvfrom(psock, buf, len, infrom);
}
else
#endif
#if defined(CONFIG_NET_UDP)
if (psock->s_type == SOCK_DGRAM)
{
ret = udp_recvfrom(psock, buf, len, infrom);
}
#elif defined(CONFIG_NET_TCP)
ret = tcp_recvfrom(psock, buf, len, infrom);
#elif defined(CONFIG_NET_UDP)
ret = udp_recvfrom(psock, buf, len, infrom);
#else
ret = -ENOSYS;
else
#endif
{
ndbg("ERROR: Unsupported socket type: %d\n", psock->s_type
ret = -ENOSYS;
}
/* Set the socket state to idle */

View File

@ -91,33 +91,54 @@
int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
{
int err = ENFILE;
int err;
/* Only PF_INET or PF_INET6 domains supported */
/* Only PF_INET, PF_INET6 or PF_PACKET domains supported */
#ifdef CONFIG_NET_IPv6
if ( domain != PF_INET6)
if (
#if defined(CONFIG_NET_IPv6)
domain != PF_INET6
#else
if ( domain != PF_INET)
domain != PF_INET
#endif
#if defined(CONFIG_NET_PKT)
&& domain != PF_PACKET
#endif
)
{
err = EAFNOSUPPORT;
goto errout;
}
/* Only SOCK_STREAM and possible SOCK_DRAM are supported */
/* Only SOCK_STREAM, SOCK_DGRAM and possible SOCK_RAW are supported */
#if defined(CONFIG_NET_TCP) && defined(CONFIG_NET_UDP)
if ((type == SOCK_STREAM && protocol != 0 && protocol != IPPROTO_TCP) ||
(type == SOCK_DGRAM && protocol != 0 && protocol != IPPROTO_UDP) ||
(type != SOCK_STREAM && type != SOCK_DGRAM))
#elif defined(CONFIG_NET_TCP)
if ((type == SOCK_STREAM && protocol != 0 && protocol != IPPROTO_TCP) ||
(type != SOCK_STREAM))
#elif defined(CONFIG_NET_UDP)
if ((type == SOCK_DGRAM && protocol != 0 && protocol != IPPROTO_UDP) ||
(type != SOCK_DGRAM))
if (
#if defined(CONFIG_NET_TCP)
(type == SOCK_STREAM && protocol != 0 && protocol != IPPROTO_TCP) ||
#endif
#if defined(CONFIG_NET_UDP)
(type == SOCK_DGRAM && protocol != 0 && protocol != IPPROTO_UDP) ||
#endif
(
#if defined(CONFIG_NET_TCP)
#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_PKT)
type != SOCK_STREAM &&
#else
type != SOCK_STREAM
#endif
#endif
#if defined(CONFIG_NET_UDP)
#if defined(CONFIG_NET_PKT)
type != SOCK_DGRAM &&
#else
type != SOCK_DGRAM
#endif
#endif
#if defined(CONFIG_NET_PKT)
type != SOCK_RAW
#endif
)
)
{
err = EPROTONOSUPPORT;
goto errout;
@ -140,6 +161,20 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
err = ENOMEM; /* Assume failure to allocate connection instance */
switch (type)
{
#ifdef CONFIG_NET_PKT
case SOCK_RAW:
{
struct uip_pkt_conn *conn = uip_pktalloc();
if (conn)
{
DEBUGASSERT(conn->crefs == 0);
psock->s_conn = conn;
conn->crefs = 1;
}
}
break;
#endif
#ifdef CONFIG_NET_TCP
case SOCK_STREAM:
{
@ -148,17 +183,21 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
*/
struct uip_conn *conn = uip_tcpalloc();
if (conn)
if (!conn)
{
/* Set the reference count on the connection structure. This
* reference count will be increment only if the socket is
* dup'ed
*/
/* Failed to reserve a connection structure */
DEBUGASSERT(conn->crefs == 0);
psock->s_conn = conn;
conn->crefs = 1;
goto errout; /* With err == ENFILE or ENOMEM */
}
/* Set the reference count on the connection structure. This
* reference count will be increment only if the socket is
* dup'ed
*/
DEBUGASSERT(conn->crefs == 0);
psock->s_conn = conn;
conn->crefs = 1;
}
break;
#endif
@ -171,17 +210,21 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
*/
struct uip_udp_conn *conn = uip_udpalloc();
if (conn)
if (!conn)
{
/* Set the reference count on the connection structure. This
* reference count will be increment only if the socket is
* dup'ed
*/
/* Failed to reserve a connection structure */
DEBUGASSERT(conn->crefs == 0);
psock->s_conn = conn;
conn->crefs = 1;
goto errout; /* With err == ENFILE or ENOMEM */
}
/* Set the reference count on the connection structure. This
* reference count will be increment only if the socket is
* dup'ed
*/
DEBUGASSERT(conn->crefs == 0);
psock->s_conn = conn;
conn->crefs = 1;
}
break;
#endif
@ -190,15 +233,6 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
break;
}
/* Did we successfully allocate some kind of connection structure? */
if (!psock->s_conn)
{
/* Failed to reserve a connection structure */
goto errout; /* With err == ENFILE or ENOMEM */
}
return OK;
errout:

View File

@ -46,6 +46,15 @@ ifeq ($(CONFIG_NET_NOINTS),y)
NET_CSRCS += uip_lock.c
endif
# Packet socket support
ifeq ($(CONFIG_NET_PKT),y)
NET_CSRCS += uip_pktconn.c
NET_CSRCS += uip_pktinput.c
NET_CSRCS += uip_pktcallback.c
NET_CSRCS += uip_pktpoll.c
endif
# IPv6-specific logic
ifeq ($(CONFIG_NET_IPv6),y)

View File

@ -123,6 +123,12 @@ void uip_initialize(void)
uip_callbackinit();
/* Initialize packet socket suport */
#ifdef CONFIG_NET_PKT
uip_pktinit();
#endif
/* Initialize the listening port structures */
#ifdef CONFIG_NET_TCP

View File

@ -51,6 +51,7 @@
#include <errno.h>
#include <arch/irq.h>
#include <nuttx/net/uip/uip.h>
#include <nuttx/net/arp.h>
/****************************************************************************
* Pre-processor Definitions
@ -102,6 +103,28 @@ void uip_callbackfree(FAR struct uip_callback_s *cb, struct uip_callback_s **lis
uint16_t uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn,
uint16_t flags, FAR struct uip_callback_s *list);
#ifdef CONFIG_NET_PKT
/* Defined in uip_pktconn.c *************************************************/
void uip_pktinit(void);
struct uip_pkt_conn *uip_pktalloc(void);
void uip_pktfree(struct uip_pkt_conn *conn);
struct uip_pkt_conn *uip_pktactive(struct uip_eth_hdr *buf);
struct uip_pkt_conn *uip_nextpktconn(struct uip_pkt_conn *conn);
/* Defined in uip_pktcallback.c *********************************************/
uint16_t uip_pktcallback(struct uip_driver_s *dev, struct uip_pkt_conn *conn,
uint16_t flags);
/* Defined in uip_pktinput.c ************************************************/
/* Defined in uip_pktpoll.c *************************************************/
void uip_pktpoll(struct uip_driver_s *dev, struct uip_pkt_conn *conn);
#endif /* CONFIG_NET_PKT */
#ifdef CONFIG_NET_TCP
/* Defined in uip_tcpconn.c *************************************************/

95
net/uip/uip_pktcallback.c Normal file
View File

@ -0,0 +1,95 @@
/****************************************************************************
* net/uip/uip_pktcallback.c
*
* Copyright (C) 2014 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>
#if defined(CONFIG_NET) && defined(CONFIG_NET_PKT)
#include <stdint.h>
#include <debug.h>
#include <nuttx/net/uip/uipopt.h>
#include <nuttx/net/uip/uip.h>
#include <nuttx/net/uip/uip-arch.h>
#include "uip_internal.h"
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Function: uip_pktcallback
*
* Description:
* Inform the application holding the packet socket of a change in state.
*
* Returned Value:
* OK if packet has been processed, otherwise ERROR.
*
* Assumptions:
* This function is called at the interrupt level with interrupts disabled.
*
****************************************************************************/
uint16_t uip_pktcallback(FAR struct uip_driver_s *dev,
FAR struct uip_pkt_conn *conn, uint16_t flags)
{
nllvdbg("flags: %04x\n", flags);
/* Some sanity checking */
if (conn)
{
/* Perform the callback */
flags = uip_callbackexecute(dev, conn, flags, conn->list);
}
return flags;
}
#endif /* CONFIG_NET && CONFIG_NET_PKT */

290
net/uip/uip_pktconn.c Normal file
View File

@ -0,0 +1,290 @@
/****************************************************************************
* net/uip/uip_pktconn.c
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Large parts of this file were leveraged from uIP logic:
*
* Copyright (c) 2001-2003, Adam Dunkels.
* All rights reserved.
*
* 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. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
#if defined(CONFIG_NET) && defined(CONFIG_NET_PKT)
#include <semaphore.h>
#include <assert.h>
#include <errno.h>
#include <debug.h>
#include <arch/irq.h>
#include <nuttx/net/uip/uipopt.h>
#include <nuttx/net/uip/uip.h>
#include <nuttx/net/uip/uip-arch.h>
#include <nuttx/net/arp.h>
#include "uip_internal.h"
/****************************************************************************
* Private Data
****************************************************************************/
/* The array containing all packet socket connections */
static struct uip_pkt_conn g_pkt_connections[CONFIG_NET_PKT_CONNS];
/* A list of all free packet socket connections */
static dq_queue_t g_free_pkt_connections;
static sem_t g_free_sem;
/* A list of all allocated packet scoket connections */
static dq_queue_t g_active_pkt_connections;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: _uip_semtake() and _uip_semgive()
*
* Description:
* Take/give semaphore
*
****************************************************************************/
static inline void _uip_semtake(sem_t *sem)
{
/* Take the semaphore (perhaps waiting) */
while (uip_lockedwait(sem) != 0)
{
/* The only case that an error should occur here is if
* the wait was awakened by a signal.
*/
ASSERT(*get_errno_ptr() == EINTR);
}
}
#define _uip_semgive(sem) sem_post(sem)
/****************************************************************************
* Name: uip_find_conn()
*
* Description:
* Find the packet socket connection that uses this interface index
* number. Called only from user user level code, but with interrupts
* disabled.
*
****************************************************************************/
static struct uip_pkt_conn *uip_find_conn(uint8_t ifindex)
{
int i;
/* Now search each connection structure. */
for (i = 0; i < CONFIG_NET_PKT_CONNS; i++)
{
if (g_pkt_connections[ i ].ifindex == ifindex)
{
return &g_pkt_connections[ i ];
}
}
return NULL;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: uip_pktinit()
*
* Description:
* Initialize the packet socket connection structures. Called once and
* only from the UIP layer.
*
****************************************************************************/
void uip_pktinit(void)
{
int i;
/* Initialize the queues */
dq_init(&g_free_pkt_connections);
dq_init(&g_active_pkt_connections);
sem_init(&g_free_sem, 0, 1);
for (i = 0; i < CONFIG_NET_PKT_CONNS; i++)
{
/* Mark the connection closed and move it to the free list */
g_pkt_connections[i].ifindex = 0;
dq_addlast(&g_pkt_connections[i].node, &g_free_pkt_connections);
}
}
/****************************************************************************
* Name: uip_pktpalloc()
*
* Description:
* Alloc a new, uninitialized packet socket connection structure.
*
****************************************************************************/
struct uip_pkt_conn *uip_pktalloc(void)
{
struct uip_pkt_conn *conn;
/* The free list is only accessed from user, non-interrupt level and
* is protected by a semaphore (that behaves like a mutex).
*/
_uip_semtake(&g_free_sem);
conn = (struct uip_pkt_conn *)dq_remfirst(&g_free_pkt_connections);
if (conn)
{
/* Make sure that the connection is marked as uninitialized */
conn->ifindex = 0;
/* Enqueue the connection into the active list */
dq_addlast(&conn->node, &g_active_pkt_connections);
}
_uip_semgive(&g_free_sem);
return conn;
}
/****************************************************************************
* Name: uip_pktfree()
*
* Description:
* Free a packet socket connection structure that is no longer in use.
* This should be done by the implementation of close().
*
****************************************************************************/
void uip_pktfree(struct uip_pkt_conn *conn)
{
/* The free list is only accessed from user, non-interrupt level and
* is protected by a semaphore (that behaves like a mutex).
*/
DEBUGASSERT(conn->crefs == 0);
_uip_semtake(&g_free_sem);
/* Remove the connection from the active list */
dq_rem(&conn->node, &g_active_pkt_connections);
/* Free the connection */
dq_addlast(&conn->node, &g_free_pkt_connections);
_uip_semgive(&g_free_sem);
}
/****************************************************************************
* Name: uip_pktactive()
*
* Description:
* Find a connection structure that is the appropriate
* connection to be used with the provided Ethernet header
*
* Assumptions:
* This function is called from UIP logic at interrupt level
*
****************************************************************************/
struct uip_pkt_conn *uip_pktactive(struct uip_eth_hdr *buf)
{
#define uip_ethaddr_cmp(addr1, addr2) \
((addr1[0] == addr2[0]) && (addr1[1] == addr2[1]) && \
(addr1[2] == addr2[2]) && (addr1[3] == addr2[3]) && \
(addr1[4] == addr2[4]) && (addr1[5] == addr2[5]))
FAR struct uip_pkt_conn *conn =
(struct uip_pkt_conn *)g_active_pkt_connections.head;
while (conn)
{
/* FIXME lmac in conn should have been set by pkt_rawbind() */
if (uip_ethaddr_cmp(buf->dest, conn->lmac))
{
/* Matching connection found.. return a reference to it */
break;
}
/* Look at the next active connection */
conn = (struct uip_pkt_conn *)conn->node.flink;
}
return conn;
}
/****************************************************************************
* Name: uip_nextpktconn()
*
* Description:
* Traverse the list of allocated packet connections
*
* Assumptions:
* This function is called from UIP logic at interrupt level (or with
* interrupts disabled).
*
****************************************************************************/
struct uip_pkt_conn *uip_nextpktconn(struct uip_pkt_conn *conn)
{
if (!conn)
{
return (struct uip_pkt_conn *)g_active_pkt_connections.head;
}
else
{
return (struct uip_pkt_conn *)conn->node.flink;
}
}
#endif /* CONFIG_NET && CONFIG_NET_PKT */

140
net/uip/uip_pktinput.c Normal file
View File

@ -0,0 +1,140 @@
/****************************************************************************
* net/uip/uip_pktinput.c
* Handling incoming packet input
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Adapted for NuttX from logic in uIP which also has a BSD-like license:
*
* Original author Adam Dunkels <adam@dunkels.com>
* Copyright () 2001-2003, Adam Dunkels.
* All rights reserved.
*
* 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. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
#if defined(CONFIG_NET) && defined(CONFIG_NET_PKT)
#include <debug.h>
#include <nuttx/net/uip/uip.h>
#include <nuttx/net/uip/uip-arch.h>
#include <nuttx/net/uip/uip-pkt.h>
#include <nuttx/net/arp.h>
#include "uip_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define PKTBUF ((struct uip_eth_hdr *)&dev->d_buf)
/****************************************************************************
* Public Variables
****************************************************************************/
/****************************************************************************
* Private Variables
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: uip_pktinput
*
* Description:
* Handle incoming packet input
*
* Parameters:
* dev - The device driver structure containing the received packet
*
* Return:
* OK The packet has been processed and can be deleted
* ERROR Hold the packet and try again later. There is a listening socket
* but no recv in place to catch the packet yet.
*
* Assumptions:
* Called from the interrupt level or with interrupts disabled.
*
****************************************************************************/
int uip_pktinput(struct uip_driver_s *dev)
{
struct uip_pkt_conn *conn;
struct uip_eth_hdr *pbuf = (struct uip_eth_hdr *)dev->d_buf;
int ret = OK;
conn = uip_pktactive(pbuf);
if (conn)
{
uint16_t flags;
/* Setup for the application callback */
dev->d_appdata = dev->d_buf;
dev->d_snddata = dev->d_buf;
dev->d_sndlen = 0;
/* Perform the application callback */
flags = uip_pktcallback(dev, conn, UIP_NEWDATA);
/* If the operation was successful, the UIP_NEWDATA flag is removed
* and thus the packet can be deleted (OK will be returned).
*/
if ((flags & UIP_NEWDATA) != 0)
{
/* No.. the packet was not processed now. Return ERROR so
* that the driver may retry again later.
*/
ret = ERROR;
}
}
else
{
nlldbg("No listener\n");
}
return ret;
}
#endif /* CONFIG_NET && CONFIG_NET_PKT */

129
net/uip/uip_pktpoll.c Normal file
View File

@ -0,0 +1,129 @@
/****************************************************************************
* net/uip/uip_pktpoll.c
* Poll for the availability of packet TX data
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Adapted for NuttX from logic in uIP which also has a BSD-like license:
*
* Original author Adam Dunkels <adam@dunkels.com>
* Copyright () 2001-2003, Adam Dunkels.
* All rights reserved.
*
* 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. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
#if defined(CONFIG_NET) && defined(CONFIG_NET_PKT)
#include <debug.h>
#include <nuttx/net/uip/uipopt.h>
#include <nuttx/net/uip/uip.h>
#include <nuttx/net/uip/uip-arch.h>
#include <nuttx/net/uip/uip-pkt.h>
#include "uip_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Variables
****************************************************************************/
/****************************************************************************
* Private Variables
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: uip_pktpoll
*
* Description:
* Poll a packet "connection" structure for availability of TX data
*
* Parameters:
* dev - The device driver structure to use in the send operation
* conn - The packet "connection" to poll for TX data
*
* Return:
* None
*
* Assumptions:
* Called from the interrupt level or with interrupts disabled.
*
****************************************************************************/
void uip_pktpoll(struct uip_driver_s *dev, struct uip_pkt_conn *conn)
{
nlldbg("IN\n");
/* Verify that the packet connection is valid */
if (conn)
{
/* Setup for the application callback */
dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
dev->d_len = 0;
dev->d_sndlen = 0;
/* Perform the application callback */
(void)uip_pktcallback(dev, conn, UIP_POLL);
/* If the application has data to send, setup the UDP/IP header */
if (dev->d_sndlen > 0)
{
// uip_pktsend(dev, conn);
return;
}
}
/* Make sure that d_len is zero meaning that there is nothing to be sent */
dev->d_len = 0;
}
#endif /* CONFIG_NET && CONFIG_NET_PKT */

View File

@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_poll.c
*
* Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
* Copyright (C) 2007-2010, 2012, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -56,6 +56,42 @@
* Private Functions
****************************************************************************/
/****************************************************************************
* Function: uip_pollpktconnections
*
* Description:
* Poll all packet connections for available packets to send.
*
* Assumptions:
* This function is called from the MAC device driver and may be called from
* the timer interrupt/watchdog handle level.
*
****************************************************************************/
#if defined(CONFIG_NET_PKT)
static int uip_pollpktconnections(struct uip_driver_s *dev,
uip_poll_callback_t callback)
{
struct uip_pkt_conn *pkt_conn = NULL;
int bstop = 0;
/* Traverse all of the allocated packet connections and perform the poll action */
while (!bstop && (pkt_conn = uip_nextpktconn(pkt_conn)))
{
/* Perform the packet TX poll */
uip_pktpoll(dev, pkt_conn);
/* Call back into the driver */
callback(dev);
}
return bstop;
}
#endif /* CONFIG_NET_PKT */
/****************************************************************************
* Function: uip_pollicmp
*
@ -254,34 +290,46 @@ int uip_poll(FAR struct uip_driver_s *dev, uip_poll_callback_t callback)
{
int bstop;
/* Check for pending IGMP messages */
/* Traverse all of the active packet connections and perform the poll
* action.
*/
#ifdef CONFIG_NET_IGMP
bstop = uip_polligmp(dev, callback);
#ifdef CONFIG_NET_PKT
bstop = uip_pollpktconnections(dev, callback);
if (!bstop)
#endif
{
/* Traverse all of the active TCP connections and perform the poll action */
/* Check for pendig IGMP messages */
bstop = uip_polltcpconnections(dev, callback);
#ifdef CONFIG_NET_IGMP
bstop = uip_polligmp(dev, callback);
if (!bstop)
#endif
{
#ifdef CONFIG_NET_UDP
/* Traverse all of the allocated UDP connections and perform the
* poll action.
/* Traverse all of the active TCP connections and perform the poll
* action.
*/
bstop = uip_polludpconnections(dev, callback);
bstop = uip_polltcpconnections(dev, callback);
if (!bstop)
#endif
{
#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
/* Traverse all of the tasks waiting to send an ICMP ECHO
* request
#ifdef CONFIG_NET_UDP
/* Traverse all of the allocated UDP connections and perform
* the poll action
*/
bstop = uip_pollicmp(dev, callback);
bstop = uip_polludpconnections(dev, callback);
if (!bstop)
#endif
{
#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
/* Traverse all of the tasks waiting to send an ICMP ECHO
* request.
*/
bstop = uip_pollicmp(dev, callback);
#endif
}
}
}
}
@ -327,30 +375,46 @@ int uip_timer(FAR struct uip_driver_s *dev, uip_poll_callback_t callback,
}
#endif /* UIP_REASSEMBLY */
/* Check for pendig IGMP messages */
/* Traverse all of the active packet connections and perform the poll
* action.
*/
#ifdef CONFIG_NET_IGMP
bstop = uip_polligmp(dev, callback);
#ifdef CONFIG_NET_PKT
bstop = uip_pollpktconnections(dev, callback);
if (!bstop)
#endif
{
/* Traverse all of the active TCP connections and perform the timer action */
/* Check for pending IGMP messages */
bstop = uip_polltcptimer(dev, callback, hsec);
#ifdef CONFIG_NET_IGMP
bstop = uip_polligmp(dev, callback);
if (!bstop)
#endif
{
/* Traverse all of the allocated UDP connections and perform the poll action */
/* Traverse all of the active TCP connections and perform the
* timer action.
*/
bstop = uip_polltcptimer(dev, callback, hsec);
if (!bstop)
{
/* Traverse all of the allocated UDP connections and perform
* the poll action.
*/
#ifdef CONFIG_NET_UDP
bstop = uip_polludpconnections(dev, callback);
if (!bstop)
bstop = uip_polludpconnections(dev, callback);
if (!bstop)
#endif
{
{
#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
/* Traverse all of the tasks waiting to send an ICMP ECHO request */
/* Traverse all of the tasks waiting to send an ICMP ECHO
* request.
*/
bstop = uip_pollicmp(dev, callback);
bstop = uip_pollicmp(dev, callback);
#endif
}
}
}
}