summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-07-05 15:15:40 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-07-05 15:15:40 -0600
commit23d9b568365824d3814793aa5c8b379184fa0101 (patch)
tree737ee7fd2f2c8dbe1e4c48e8d6b8400c2e84154f /nuttx
parentf825004170beb88dec1993ae6514e8307b9ef0fa (diff)
downloadpx4-nuttx-23d9b568365824d3814793aa5c8b379184fa0101.tar.gz
px4-nuttx-23d9b568365824d3814793aa5c8b379184fa0101.tar.bz2
px4-nuttx-23d9b568365824d3814793aa5c8b379184fa0101.zip
NET: Move most of the contents of include/nuttx/net/igmp.h moved to net/igmp/igmp.h
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/include/nuttx/net/igmp.h39
-rw-r--r--nuttx/net/igmp/igmp.h303
-rw-r--r--nuttx/net/igmp/igmp_input.c7
-rw-r--r--nuttx/net/igmp/igmp_timer.c27
-rw-r--r--nuttx/net/netdev/netdev_ioctl.c1
-rw-r--r--nuttx/net/netdev/netdev_register.c1
-rw-r--r--nuttx/net/utils/Make.defs3
-rw-r--r--nuttx/net/utils/utils.h20
8 files changed, 331 insertions, 70 deletions
diff --git a/nuttx/include/nuttx/net/igmp.h b/nuttx/include/nuttx/net/igmp.h
index f15aa23b9..4c09cdeef 100644
--- a/nuttx/include/nuttx/net/igmp.h
+++ b/nuttx/include/nuttx/net/igmp.h
@@ -119,7 +119,7 @@
/* IGMPv2 packet structure as defined by RFC 2236.
*
- * The Max Respone Time (maxresp) specifies the time limit for the
+ * The Max Response Time (maxresp) specifies the time limit for the
* corresponding report. The field has a resolution of 100 miliseconds, the
* value is taken directly. This field is meaningful only in Membership Query
* (0x11); in other messages it is set to 0 and ignored by the receiver.
@@ -199,25 +199,6 @@ struct igmp_stats_s
# define IGMP_STATINCR(p)
#endif
-/* This structure represents one group member. There is a list of groups
- * for each device interface structure.
- *
- * There will be a group for the all systems group address but this
- * will not run the state machine as it is used to kick off reports
- * from all the other groups
- */
-
-typedef FAR struct wdog_s *WDOG_ID;
-struct igmp_group_s
-{
- struct igmp_group_s *next; /* Implements a singly-linked list */
- net_ipaddr_t grpaddr; /* Group IP address */
- WDOG_ID wdog; /* WDOG used to detect timeouts */
- sem_t sem; /* Used to wait for message transmission */
- volatile uint8_t flags; /* See IGMP_ flags definitions */
- uint8_t msgid; /* Pending message ID (if non-zero) */
-};
-
/****************************************************************************
* Public Data
****************************************************************************/
@@ -231,28 +212,10 @@ extern "C"
#define EXTERN extern
#endif
-EXTERN net_ipaddr_t g_allsystems;
-EXTERN net_ipaddr_t g_allrouters;
-
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
-/****************************************************************************
- * Name: igmp_devinit
- *
- * Description:
- * Called when a new network device is registered to configure that device
- * for IGMP support.
- *
- ****************************************************************************/
-
-void igmp_devinit(FAR struct net_driver_s *dev);
-int igmp_joingroup(FAR struct net_driver_s *dev,
- FAR const struct in_addr *grpaddr);
-int igmp_leavegroup(FAR struct net_driver_s *dev,
- FAR const struct in_addr *grpaddr);
-
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/net/igmp/igmp.h b/nuttx/net/igmp/igmp.h
index 0bd5edd2d..795478413 100644
--- a/nuttx/net/igmp/igmp.h
+++ b/nuttx/net/igmp/igmp.h
@@ -32,6 +32,39 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
+/*
+ * ________________
+ * | |
+ * | |
+ * | |
+ * | |
+ * +--------->| Non-Member |<---------+
+ * | | | |
+ * | | | |
+ * | | | |
+ * | |________________| |
+ * | | |
+ * | leave group | join group | leave group
+ * | (stop timer, |(send report, | (send leave
+ * | send leave if | set flag, | if flag set)
+ * | flag set) | start timer) |
+ * ________|________ | ________|________
+ * | |<---------+ | |
+ * | | | |
+ * | |<-------------------| |
+ * | | query received | |
+ * | Delaying Member | (start timer) | Idle Member |
+ * +---->| |------------------->| |
+ * | | | report received | |
+ * | | | (stop timer, | |
+ * | | | clear flag) | |
+ * | |_________________|------------------->|_________________|
+ * | query received | timer expired
+ * | (reset timer if | (send report,
+ * | Max Resp Time | set flag)
+ * | < current timer) |
+ * +-------------------+
+ */
#ifndef _NET_IGMP_IGMP_H
#define _NET_IGMP_IGMP_H
@@ -56,6 +89,25 @@
* Public Type Definitions
****************************************************************************/
+/* This structure represents one group member. There is a list of groups
+ * for each device interface structure.
+ *
+ * There will be a group for the all systems group address but this
+ * will not run the state machine as it is used to kick off reports
+ * from all the other groups
+ */
+
+typedef FAR struct wdog_s *WDOG_ID;
+struct igmp_group_s
+{
+ struct igmp_group_s *next; /* Implements a singly-linked list */
+ net_ipaddr_t grpaddr; /* Group IP address */
+ WDOG_ID wdog; /* WDOG used to detect timeouts */
+ sem_t sem; /* Used to wait for message transmission */
+ volatile uint8_t flags; /* See IGMP_ flags definitions */
+ uint8_t msgid; /* Pending message ID (if non-zero) */
+};
+
/****************************************************************************
* Public Data
****************************************************************************/
@@ -68,54 +120,301 @@ extern "C"
# define EXTERN extern
#endif
+EXTERN net_ipaddr_t g_allsystems;
+EXTERN net_ipaddr_t g_allrouters;
+
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/* Defined in igmp_init.c ***************************************************/
+/****************************************************************************
+ * Name: igmp_initialize
+ *
+ * Description:
+ * Perform one-time IGMP initialization.
+ *
+ ****************************************************************************/
void igmp_initialize(void);
+/****************************************************************************
+ * Name: igmp_devinit
+ *
+ * Description:
+ * Called when a new network device is registered to configure that device
+ * for IGMP support.
+ *
+ ****************************************************************************/
+
+void igmp_devinit(FAR struct net_driver_s *dev);
+
/* Defined in igmp_input.c **************************************************/
+/****************************************************************************
+ * Name: igmp_input
+ *
+ * Description:
+ * An IGMP packet has been received.
+ *
+ * NOTE: This is most likely executing from an interrupt handler.
+ *
+ ****************************************************************************/
void igmp_input(struct net_driver_s *dev);
/* Defined in igmp_group.c **************************************************/
+/****************************************************************************
+ * Name: igmp_grpinit
+ *
+ * Description:
+ * One-time initialization of group data.
+ *
+ * Assumptions:
+ * Called only during early boot phases (pre-multitasking).
+ *
+ ****************************************************************************/
void igmp_grpinit(void);
+
+/****************************************************************************
+ * Name: igmp_grpalloc
+ *
+ * Description:
+ * Allocate a new group from heap memory.
+ *
+ * Assumptions:
+ * May be called from either user or interrupt level processing.
+ *
+ ****************************************************************************/
+
FAR struct igmp_group_s *igmp_grpalloc(FAR struct net_driver_s *dev,
FAR const net_ipaddr_t *addr);
+
+/****************************************************************************
+ * Name: igmp_grpfind
+ *
+ * Description:
+ * Find an existing group.
+ *
+ * Assumptions:
+ * May be called from either user or interrupt level processing.
+ *
+ ****************************************************************************/
+
FAR struct igmp_group_s *igmp_grpfind(FAR struct net_driver_s *dev,
FAR const net_ipaddr_t *addr);
+
+/****************************************************************************
+ * Name: igmp_grpallocfind
+ *
+ * Description:
+ * Find an existing group. If not found, create a new group for the
+ * address.
+ *
+ * Assumptions:
+ * May be called from either user or interrupt level processing.
+ *
+ ****************************************************************************/
+
FAR struct igmp_group_s *igmp_grpallocfind(FAR struct net_driver_s *dev,
FAR const net_ipaddr_t *addr);
+
+/****************************************************************************
+ * Name: igmp_grpfree
+ *
+ * Description:
+ * Release a previously allocated group.
+ *
+ * Assumptions:
+ * May be called from either user or interrupt level processing.
+ *
+ ****************************************************************************/
+
void igmp_grpfree(FAR struct net_driver_s *dev,
FAR struct igmp_group_s *group);
/* Defined in igmp_msg.c ****************************************************/
+/****************************************************************************
+ * Name: igmp_schedmsg
+ *
+ * Description:
+ * Schedule a message to be send at the next driver polling interval.
+ *
+ * Assumptions:
+ * This function may be called in most any context.
+ *
+ ****************************************************************************/
void igmp_schedmsg(FAR struct igmp_group_s *group, uint8_t msgid);
+
+/****************************************************************************
+ * Name: igmp_waitmsg
+ *
+ * Description:
+ * Schedule a message to be send at the next driver polling interval and
+ * block, waiting for the message to be sent.
+ *
+ * Assumptions:
+ * This function cannot be called from an interrupt handler (if you try it,
+ * net_lockedwait will assert).
+ *
+ ****************************************************************************/
+
void igmp_waitmsg(FAR struct igmp_group_s *group, uint8_t msgid);
/* Defined in igmp_poll.c ***************************************************/
+/****************************************************************************
+ * Name: igmp_poll
+ *
+ * Description:
+ * Poll the groups associated with the device to see if any IGMP messages
+ * are pending transfer.
+ *
+ * Returned Value:
+ * Returns a non-zero value if a IGP message is sent.
+ *
+ * Assumptions:
+ * This function is called from the driver polling logic... probably within
+ * an interrupt handler.
+ *
+ ****************************************************************************/
void igmp_poll(FAR struct net_driver_s *dev);
/* Defined in igmp_send.c ***************************************************/
+/****************************************************************************
+ * Name: igmp_send
+ *
+ * Description:
+ * Sends an IGMP IP packet on a network interface. This function constructs
+ * the IP header and calculates the IP header checksum.
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation.
+ * group - Describes the multicast group member and identifies the
+ * message to be sent.
+ * destipaddr - The IP address of the recipient of the message
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
void igmp_send(FAR struct net_driver_s *dev, FAR struct igmp_group_s *group,
FAR net_ipaddr_t *dest);
+/* Defined in igmp_join.c ***************************************************/
+/****************************************************************************
+ * Name: igmp_joingroup
+ *
+ * Description:
+ * Add the specified group address to the group.
+ *
+ * RFC 2236, 3. Protocol Description:
+ *
+ * "When a host joins a multicast group, it should immediately transmit
+ * an unsolicited Version 2 Membership Report for that group, in case it
+ * is the first member of that group on the network. To cover the
+ * possibility of the initial Membership Report being lost or damaged,
+ * it is recommended that it be repeated once or twice after short
+ * delays [Unsolicited Report Interval]. (A simple way to accomplish
+ * this is to send the initial Version 2 Membership Report and then act
+ * as if a Group-Specific Query was received for that group, and set a
+ * timer appropriately)."
+ *
+ * Assumptions:
+ * This function cannot be called from interrupt handling logic!
+ *
+ ****************************************************************************/
+
+int igmp_joingroup(FAR struct net_driver_s *dev,
+ FAR const struct in_addr *grpaddr);
+
+/* Defined in igmp_leave.c **************************************************/
+/****************************************************************************
+ * Name: igmp_leavegroup
+ *
+ * Description:
+ * Remove the specified group address to the group.
+ *
+ * RFC 2236, 3. Protocol Description:
+ *
+ * "When a host leaves a multicast group, if it was the last host to
+ * reply to a Query with a Membership Report for that group, it SHOULD
+ * send a Leave Group message to the all-routers multicast group
+ * (224.0.0.2). If it was not the last host to reply to a Query, it MAY
+ * send nothing as there must be another member on the subnet. This is
+ * an optimization to reduce traffic; a host without sufficient storage
+ * to remember whether or not it was the last host to reply MAY always
+ * send a Leave Group message when it leaves a group. Routers SHOULD
+ * accept a Leave Group message addressed to the group being left, in
+ * order to accommodate implementations of an earlier version of this
+ * standard. Leave Group messages are addressed to the all-routers
+ * group because other group members have no need to know that a host
+ * has left the group, but it does no harm to address the message to the
+ * group."
+ *
+ * Assumptions:
+ * This function cannot be called from interrupt handling logic!
+ *
+ ****************************************************************************/
+
+int igmp_leavegroup(FAR struct net_driver_s *dev,
+ FAR const struct in_addr *grpaddr);
+
/* Defined in igmp_timer.c **************************************************/
+/****************************************************************************
+ * Name: igmp_startticks and igmp_starttimer
+ *
+ * Description:
+ * Start the IGMP timer with differing time units (ticks or deciseconds).
+ *
+ * Assumptions:
+ * This function may be called from most any context.
+ *
+ ****************************************************************************/
-int igmp_decisec2tick(int decisecs);
-void igmp_startticks(FAR struct igmp_group_s *group, int ticks);
+void igmp_startticks(FAR struct igmp_group_s *group, unsigned int ticks);
void igmp_starttimer(FAR struct igmp_group_s *group, uint8_t decisecs);
+
+/****************************************************************************
+ * Name: igmp_cmptimer
+ *
+ * Description:
+ * Compare the timer remaining on the watching timer to the deci-second
+ * value. If maxticks > ticks-remaining, then (1) cancel the timer (to
+ * avoid race conditions) and return true.
+ *
+ * Assumptions:
+ * This function may be called from most any context. If true is returned
+ * then the caller must call igmp_startticks() to restart the timer
+ *
+ ****************************************************************************/
+
bool igmp_cmptimer(FAR struct igmp_group_s *group, int maxticks);
/* Defined in igmp_mcastmac *************************************************/
+/****************************************************************************
+ * Name: igmp_addmcastmac
+ *
+ * Description:
+ * Add an IGMP MAC address to the device's MAC filter table.
+ *
+ ****************************************************************************/
void igmp_addmcastmac(FAR struct net_driver_s *dev, FAR net_ipaddr_t *ip);
+
+/****************************************************************************
+ * Name: igmp_removemcastmac
+ *
+ * Description:
+ * Remove an IGMP MAC address from the device's MAC filter table.
+ *
+ ****************************************************************************/
+
void igmp_removemcastmac(FAR struct net_driver_s *dev, FAR net_ipaddr_t *ip);
#undef EXTERN
diff --git a/nuttx/net/igmp/igmp_input.c b/nuttx/net/igmp/igmp_input.c
index 886282569..93087b07e 100644
--- a/nuttx/net/igmp/igmp_input.c
+++ b/nuttx/net/igmp/igmp_input.c
@@ -54,6 +54,7 @@
#include "devif/devif.h"
#include "igmp/igmp.h"
+#include "utils/utils.h"
#ifdef CONFIG_NET_IGMP
@@ -207,7 +208,7 @@ void igmp_input(struct net_driver_s *dev)
if (!net_ipaddr_cmp(member->grpaddr, g_allsystems))
{
- ticks = igmp_decisec2tick((int)IGMPBUF->maxresp);
+ ticks = net_dsec2tick((int)IGMPBUF->maxresp);
if (IS_IDLEMEMBER(member->flags) ||
igmp_cmptimer(member, ticks))
{
@@ -228,7 +229,7 @@ void igmp_input(struct net_driver_s *dev)
IGMP_STATINCR(g_netstats.igmp.ucast_query);
grpaddr = net_ip4addr_conv32(IGMPBUF->grpaddr);
group = igmp_grpallocfind(dev, &grpaddr);
- ticks = igmp_decisec2tick((int)IGMPBUF->maxresp);
+ ticks = net_dsec2tick((int)IGMPBUF->maxresp);
if (IS_IDLEMEMBER(group->flags) || igmp_cmptimer(group, ticks))
{
igmp_startticks(group, ticks);
@@ -246,7 +247,7 @@ void igmp_input(struct net_driver_s *dev)
nlldbg("Query to a specific group with the group address as destination\n");
- ticks = igmp_decisec2tick((int)IGMPBUF->maxresp);
+ ticks = net_dsec2tick((int)IGMPBUF->maxresp);
if (IS_IDLEMEMBER(group->flags) || igmp_cmptimer(group, ticks))
{
igmp_startticks(group, ticks);
diff --git a/nuttx/net/igmp/igmp_timer.c b/nuttx/net/igmp/igmp_timer.c
index 59b5f9f95..b257204c4 100644
--- a/nuttx/net/igmp/igmp_timer.c
+++ b/nuttx/net/igmp/igmp_timer.c
@@ -55,6 +55,7 @@
#include "devif/devif.h"
#include "igmp/igmp.h"
+#include "utils/utils.h"
#ifdef CONFIG_NET_IGMP
@@ -153,28 +154,6 @@ static void igmp_timeout(int argc, uint32_t arg, ...)
****************************************************************************/
/****************************************************************************
- * Name: igmp_decisec2tick
- *
- * Description:
- * Convert the deci-second value to units of system clock ticks.
- *
- * Assumptions:
- * This function may be called from most any context.
- *
- ****************************************************************************/
-
-int igmp_decisec2tick(int decisecs)
-{
- /* Convert the deci-second comparison value to clock ticks. The CLK_TCK
- * value is the number of clock ticks per second; decisecs argument is the
- * maximum delay in 100's of milliseconds. CLK_TCK/10 is then the number
- * of clock ticks in 100 milliseconds.
- */
-
- return CLK_TCK * decisecs / 10;
-}
-
-/****************************************************************************
* Name: igmp_startticks and igmp_starttimer
*
* Description:
@@ -185,7 +164,7 @@ int igmp_decisec2tick(int decisecs)
*
****************************************************************************/
-void igmp_startticks(FAR struct igmp_group_s *group, int ticks)
+void igmp_startticks(FAR struct igmp_group_s *group, unsigned int ticks)
{
int ret;
@@ -206,7 +185,7 @@ void igmp_starttimer(FAR struct igmp_group_s *group, uint8_t decisecs)
*/
gtmrdbg("decisecs: %d\n", decisecs);
- igmp_startticks(group, igmp_decisec2tick(decisecs));
+ igmp_startticks(group, net_dsec2tick(decisecs));
}
/****************************************************************************
diff --git a/nuttx/net/netdev/netdev_ioctl.c b/nuttx/net/netdev/netdev_ioctl.c
index af32a8052..3a6fa4d3e 100644
--- a/nuttx/net/netdev/netdev_ioctl.c
+++ b/nuttx/net/netdev/netdev_ioctl.c
@@ -65,6 +65,7 @@
#include "socket/socket.h"
#include "netdev/netdev.h"
+#include "igmp/igmp.h"
#include "route/route.h"
/****************************************************************************
diff --git a/nuttx/net/netdev/netdev_register.c b/nuttx/net/netdev/netdev_register.c
index 6ed760ec8..c3bb4b61d 100644
--- a/nuttx/net/netdev/netdev_register.c
+++ b/nuttx/net/netdev/netdev_register.c
@@ -53,6 +53,7 @@
#include <nuttx/net/netdev.h>
#include "netdev/netdev.h"
+#include "igmp/igmp.h"
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/net/utils/Make.defs b/nuttx/net/utils/Make.defs
index dd3ad35a5..c8bf78e6b 100644
--- a/nuttx/net/utils/Make.defs
+++ b/nuttx/net/utils/Make.defs
@@ -33,7 +33,8 @@
#
############################################################################
-NET_CSRCS += net_dsec2timeval.c net_timeval2dsec.c net_chksum.c
+NET_CSRCS += net_dsec2tick.c net_dsec2timeval.c net_timeval2dsec.c
+NET_CSRCS += net_chksum.c
# Non-interrupt level support required?
diff --git a/nuttx/net/utils/utils.h b/nuttx/net/utils/utils.h
index 094a0a837..e3e640c1d 100644
--- a/nuttx/net/utils/utils.h
+++ b/nuttx/net/utils/utils.h
@@ -89,8 +89,8 @@ void net_lockinitialize(void);
* Function: net_dsec2timeval
*
* Description:
- * Convert a decisecond timeout value to a struct timeval. Needed by
- * getsockopt() to report timeout values.
+ * Convert a decisecond value to a struct timeval. Needed by getsockopt()
+ * to report timeout values.
*
* Parameters:
* dsec The decisecond value to convert
@@ -108,6 +108,22 @@ void net_dsec2timeval(uint16_t dsec, FAR struct timeval *tv);
#endif
/****************************************************************************
+ * Function: net_dsec2tick
+ *
+ * Description:
+ * Convert a decisecond value to a system clock ticks. Used by IGMP logic.
+ *
+ * Parameters:
+ * dsec The decisecond value to convert
+ *
+ * Returned Value:
+ * The decisecond value expressed as system clock ticks
+ *
+ ****************************************************************************/
+
+unsigned int net_dsec2tick(int dsec);
+
+/****************************************************************************
* Function: net_timeval2dsec
*
* Description: