summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-10-31 00:13:07 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-10-31 00:13:07 +0000
commitc6824dd08a9683fdaa29717fd72da457f41d268a (patch)
tree63b02e283abbe45f867db179b03e9fb1c3db1a66 /nuttx/net
parent1e60556b89305022b6cefe9bb28badb51dc15620 (diff)
downloadpx4-nuttx-c6824dd08a9683fdaa29717fd72da457f41d268a.tar.gz
px4-nuttx-c6824dd08a9683fdaa29717fd72da457f41d268a.tar.bz2
px4-nuttx-c6824dd08a9683fdaa29717fd72da457f41d268a.zip
dhcpc debug
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@357 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/connect.c2
-rw-r--r--nuttx/net/recvfrom.c2
-rw-r--r--nuttx/net/uip/uip-arp.c6
-rw-r--r--nuttx/net/uip/uip-udpconn.c79
-rw-r--r--nuttx/net/uip/uip.c40
5 files changed, 82 insertions, 47 deletions
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index 786a0e4e7..579972d99 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -217,7 +217,7 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
/* Get the connection reference from the socket */
conn = psock->s_conn;
- if (conn) /* Should alwasy be non-NULL */
+ if (conn) /* Should always be non-NULL */
{
/* Perform the uIP connection operation */
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 8548924ec..c13ada6e6 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -516,7 +516,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
if (_SS_ISCONNECTED(psock->s_flags))
{
- /* The SOCK_STREAM must be connect in order to recive */
+ /* The SOCK_STREAM must be connected in order to receive */
return -ENOTCONN;
}
diff --git a/nuttx/net/uip/uip-arp.c b/nuttx/net/uip/uip-arp.c
index 90ff6047e..87e48a609 100644
--- a/nuttx/net/uip/uip-arp.c
+++ b/nuttx/net/uip/uip-arp.c
@@ -74,8 +74,8 @@ struct ethip_hdr
uint8 ttl;
uint8 proto;
uint16 ipchksum;
- in_addr_t srcipaddr;
- in_addr_t destipaddr;
+ uint16 srcipaddr[2];
+ uint16 destipaddr[2];
};
#define ARP_REQUEST 1
@@ -352,7 +352,7 @@ void uip_arp_out(struct uip_driver_s *dev)
/* First check if destination is a local broadcast. */
- if (uip_ipaddr_cmp(IPBUF->destipaddr, broadcast_ipaddr))
+ if (uiphdr_ipaddr_cmp(IPBUF->destipaddr, broadcast_ipaddr))
{
memcpy(IPBUF->ethhdr.dest.addr, broadcast_ethaddr.addr, IFHWADDRLEN);
}
diff --git a/nuttx/net/uip/uip-udpconn.c b/nuttx/net/uip/uip-udpconn.c
index 329852499..e1cb17418 100644
--- a/nuttx/net/uip/uip-udpconn.c
+++ b/nuttx/net/uip/uip-udpconn.c
@@ -118,16 +118,15 @@ static inline void _uip_semtake(sem_t *sem)
*
****************************************************************************/
-static inline struct uip_udp_conn *uip_find_conn( uint16 portno )
+static struct uip_udp_conn *uip_find_conn( uint16 portno )
{
- uint16 nlastport = htons(g_last_udp_port);
int i;
/* Now search each connection structure.*/
for (i = 0; i < UIP_UDP_CONNS; i++)
{
- if (g_udp_connections[ i ].lport == nlastport)
+ if (g_udp_connections[ i ].lport == portno)
{
return &g_udp_connections[ i ];
}
@@ -289,6 +288,35 @@ void uip_udppoll(struct uip_driver_s *dev, unsigned int conn)
}
/****************************************************************************
+ * Name: uip_udpbind()
+ *
+ * Description:
+ * This function implements the UIP specific parts of the standard UDP
+ * bind() operation.
+ *
+ * Assumptions:
+ * This function is called from normal user level code.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr)
+#else
+int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
+#endif
+{
+ int ret = -EADDRINUSE;
+ irqstate_t flags = irqsave();
+ if (!uip_find_conn(g_last_udp_port))
+ {
+ conn->lport = HTONS(g_last_udp_port);
+ ret = OK;
+ }
+ irqrestore(flags);
+ return ret;
+}
+
+/****************************************************************************
* Name: uip_udpconnect()
*
* Description:
@@ -314,33 +342,39 @@ int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr)
int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
#endif
{
- irqstate_t flags;
+ /* Has this structure already been bound to a local port? */
- /* Find an unused local port number. Loop until we find a valid listen port
- * number that is not being used by any other connection.
- */
-
- flags = irqsave();
- do
+ if (!conn->lport)
{
- /* Guess that the next available port number will be the one after
- * the last port number assigned.
+ /* No..Find an unused local port number. Loop until we find a valid
+ * listen port number that is not being used by any other connection.
*/
- ++g_last_udp_port;
-
- /* Make sure that the port number is within range */
- if (g_last_udp_port >= 32000)
+ irqstate_t flags = irqsave();
+ do
{
- g_last_udp_port = 4096;
+ /* Guess that the next available port number will be the one after
+ * the last port number assigned.
+ */
+
+ ++g_last_udp_port;
+
+ /* Make sure that the port number is within range */
+
+ if (g_last_udp_port >= 32000)
+ {
+ g_last_udp_port = 4096;
+ }
}
- }
- while (uip_find_conn(g_last_udp_port));
+ while (uip_find_conn(g_last_udp_port));
- /* Initialize and return the connection structure, bind it to the port number */
+ /* Initialize and return the connection structure, bind it to the
+ * port number
+ */
- conn->lport = HTONS(g_last_udp_port);
- irqrestore(flags);
+ conn->lport = HTONS(g_last_udp_port);
+ irqrestore(flags);
+ }
if (addr)
{
@@ -352,6 +386,7 @@ int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
conn->rport = 0;
uip_ipaddr_copy(conn->ripaddr, all_zeroes_addr);
}
+
conn->ttl = UIP_TTL;
return OK;
}
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index 3c8e8001e..279140067 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -340,7 +340,7 @@ uint16 uip_ipchksum(struct uip_driver_s *dev)
uint16 sum;
sum = chksum(0, &dev->d_buf[UIP_LLH_LEN], UIP_IPH_LEN);
- dbg("uip_ipchksum: sum 0x%04x\n", sum);
+ dbg("Checksum 0x%04x\n", sum);
return (sum == 0) ? 0xffff : htons(sum);
}
#endif
@@ -420,8 +420,8 @@ static uint8 uip_reass(void)
* fragment into the buffer.
*/
- if (uip_addr_cmp(BUF->srcipaddr, FBUF->srcipaddr) &&
- uip_addr_cmp(BUF->destipaddr == FBUF->destipaddr) &&
+ if (uiphdr_addr_cmp(BUF->srcipaddr, FBUF->srcipaddr) &&
+ uiphdr_addr_cmp(BUF->destipaddr == FBUF->destipaddr) &&
BUF->ipid[0] == FBUF->ipid[0] && BUF->ipid[1] == FBUF->ipid[1])
{
len = (BUF->len[0] << 8) + BUF->len[1] - (BUF->vhl & 0x0f) * 4;
@@ -871,7 +871,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
/* Check if the packet is destined for our IP address. */
#ifndef CONFIG_NET_IPv6
- if (!uip_ipaddr_cmp(BUF->destipaddr, dev->d_ipaddr))
+ if (!uip_ipaddr_cmp(uip_ip4addr_conv(BUF->destipaddr), dev->d_ipaddr))
{
UIP_STAT(++uip_stat.ip.drop);
goto drop;
@@ -970,8 +970,8 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
/* Swap IP addresses. */
- uip_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
- uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
+ uiphdr_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
+ uiphdr_ipaddr_copy(BUF->srcipaddr, &dev->d_ipaddr);
UIP_STAT(++uip_stat.icmp.sent);
goto send;
@@ -980,7 +980,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
#else /* !CONFIG_NET_IPv6 */
/* This is IPv6 ICMPv6 processing code. */
- dbg("icmp6_input: length %d\n", dev->d_len);
+ dbg("ICMP6 input length %d\n", dev->d_len);
if (BUF->proto != UIP_PROTO_ICMP6)
{
@@ -1003,7 +1003,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
if (ICMPBUF->options[0] == ICMP6_OPTION_SOURCE_LINK_ADDRESS)
{
/* Save the sender's address in our neighbor list. */
- uip_neighbor_add(ICMPBUF->srcipaddr, &(ICMPBUF->options[2]));
+ uiphdr_neighbor_add(ICMPBUF->srcipaddr, &(ICMPBUF->options[2]));
}
/* We should now send a neighbor advertisement back to where the
@@ -1013,8 +1013,8 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
ICMPBUF->reserved1 = ICMPBUF->reserved2 = ICMPBUF->reserved3 = 0;
- uip_ipaddr_copy(ICMPBUF->destipaddr, ICMPBUF->srcipaddr);
- uip_ipaddr_copy(ICMPBUF->srcipaddr, dev->d_ipaddr);
+ uiphdr_ipaddr_copy(ICMPBUF->destipaddr, ICMPBUF->srcipaddr);
+ uiphdr_ipaddr_copy(ICMPBUF->srcipaddr, dev->d_ipaddr);
ICMPBUF->options[0] = ICMP6_OPTION_TARGET_LINK_ADDRESS;
ICMPBUF->options[1] = 1; /* Options length, 1 = 8 bytes. */
memcpy(&(ICMPBUF->options[2]), &dev->d_mac, IFHWADDRLEN);
@@ -1032,8 +1032,8 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
ICMPBUF->type = ICMP6_ECHO_REPLY;
- uip_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
- uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
+ uiphdr_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
+ uiphdr_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
ICMPBUF->icmpchksum = 0;
ICMPBUF->icmpchksum = ~uip_icmp6chksum(dev);
@@ -1042,7 +1042,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
}
else
{
- dbg("Unknown icmp6 message type %d\n", ICMPBUF->type);
+ dbg("Unknown ICMP6 message: %d\n", ICMPBUF->type);
UIP_STAT(++uip_stat.icmp.drop);
UIP_STAT(++uip_stat.icmp.typeerr);
UIP_LOG("icmp: unknown ICMP message.");
@@ -1118,8 +1118,8 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
BUF->srcport = uip_udp_conn->lport;
BUF->destport = uip_udp_conn->rport;
- uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
- uip_ipaddr_copy(BUF->destipaddr, uip_udp_conn->ripaddr);
+ uiphdr_ipaddr_copy(BUF->srcipaddr, &dev->d_ipaddr);
+ uiphdr_ipaddr_copy(BUF->destipaddr, &uip_udp_conn->ripaddr);
dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPTCPH_LEN];
@@ -1231,8 +1231,8 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
BUF->destport = tmp16;
/* Swap IP addresses. */
- uip_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
- uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
+ uiphdr_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
+ uiphdr_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
/* And send out the RST packet! */
goto tcp_send_noconn;
@@ -1850,8 +1850,8 @@ tcp_send_synack:
BUF->srcport = uip_connr->lport;
BUF->destport = uip_connr->rport;
- uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
- uip_ipaddr_copy(BUF->destipaddr, uip_connr->ripaddr);
+ uiphdr_ipaddr_copy(BUF->srcipaddr, &dev->d_ipaddr);
+ uiphdr_ipaddr_copy(BUF->destipaddr, &uip_connr->ripaddr);
if (uip_connr->tcpstateflags & UIP_STOPPED)
{
@@ -1902,7 +1902,7 @@ tcp_send_synack:
/* Calculate IP checksum. */
BUF->ipchksum = 0;
BUF->ipchksum = ~(uip_ipchksum(dev));
- dbg("uip ip_send_nolen: chkecum 0x%04x\n", uip_ipchksum(dev));
+ dbg("ip_send_nolen checksum: 0x%04x\n", uip_ipchksum(dev));
#endif /* CONFIG_NET_IPv6 */
UIP_STAT(++uip_stat.tcp.sent);