summaryrefslogtreecommitdiff
path: root/nuttx/netutils/dhcpc/dhcpc.c
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-01 18:06:15 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-01 18:06:15 +0000
commit5d303ec17efc511d8cfe0919a790b44e24a8aad9 (patch)
tree76c519b5903e6d1e2880f7fb0d403838f7acddac /nuttx/netutils/dhcpc/dhcpc.c
parent0cab5d84f146c0f6105192db5593aa4019edcdcf (diff)
downloadpx4-nuttx-5d303ec17efc511d8cfe0919a790b44e24a8aad9.tar.gz
px4-nuttx-5d303ec17efc511d8cfe0919a790b44e24a8aad9.tar.bz2
px4-nuttx-5d303ec17efc511d8cfe0919a790b44e24a8aad9.zip
Added support for socket descriptors
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@318 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/netutils/dhcpc/dhcpc.c')
-rw-r--r--nuttx/netutils/dhcpc/dhcpc.c246
1 files changed, 142 insertions, 104 deletions
diff --git a/nuttx/netutils/dhcpc/dhcpc.c b/nuttx/netutils/dhcpc/dhcpc.c
index 096649b68..1fc64cf1b 100644
--- a/nuttx/netutils/dhcpc/dhcpc.c
+++ b/nuttx/netutils/dhcpc/dhcpc.c
@@ -1,4 +1,4 @@
-/************************************************************
+/****************************************************************************
* dhcpc.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
@@ -9,55 +9,56 @@
* Copyright (c) 2005, Swedish Institute of Computer Science
* All rights reserved.
*
+ * Copyright (c) 2005, Swedish Institute of Computer Science
+ * 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. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * 3. Neither the name of the Institute 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.
+ * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE 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 INSTITUTE 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 <sys/types.h>
-#include <stdio.h>
+#include <stdlib.h>
#include <string.h>
#include <pthread.h>
+#include <semaphore.h>
#include <time.h>
#include <debug.h>
#include <net/uip/uip.h>
+#include <net/uip/dhcpc.h>
-#include "dhcpc.h"
-
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
/* CLK_TCK is the frequency of the system clock (typically 100Hz) */
+
#define CLOCK_SECOND CLK_TCK
#define STATE_INITIAL 0
@@ -94,9 +95,20 @@
#define DHCP_OPTION_REQ_LIST 55
#define DHCP_OPTION_END 255
-/************************************************************
+/****************************************************************************
* Private Types
- ************************************************************/
+ ****************************************************************************/
+
+struct dhcpc_state_internal
+{
+ char state;
+ sem_t sem;
+ struct uip_udp_conn *conn;
+ uint16 ticks;
+ const void *mac_addr;
+ int mac_len;
+ struct dhcpc_state *result;
+};
struct dhcp_msg
{
@@ -108,25 +120,24 @@ struct dhcp_msg
uint8 siaddr[4];
uint8 giaddr[4];
uint8 chaddr[16];
-#ifndef CONFIG_UIP_DHCP_LIGHT
+#ifndef CONFIG_NET_DHCP_LIGHT
uint8 sname[64];
uint8 file[128];
#endif
uint8 options[312];
};
-/************************************************************
+/****************************************************************************
* Private Data
- ************************************************************/
-
-static struct dhcpc_state s;
+ ****************************************************************************/
static const uint8 xid[4] = {0xad, 0xde, 0x12, 0x23};
static const uint8 magic_cookie[4] = {99, 130, 83, 99};
+static volatile struct dhcpc_state_internal *gpdhcpc;
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
static uint8 *add_msg_type(uint8 *optptr, uint8 type)
{
@@ -136,19 +147,19 @@ static uint8 *add_msg_type(uint8 *optptr, uint8 type)
return optptr;
}
-static uint8 *add_server_id(uint8 *optptr)
+static uint8 *add_server_id(struct dhcpc_state *presult, uint8 *optptr)
{
*optptr++ = DHCP_OPTION_SERVER_ID;
*optptr++ = 4;
- memcpy(optptr, s.serverid, 4);
+ memcpy(optptr, presult->serverid, 4);
return optptr + 4;
}
-static uint8 *add_req_ipaddr(uint8 *optptr)
+static uint8 *add_req_ipaddr(struct dhcpc_state *presult, uint8 *optptr)
{
*optptr++ = DHCP_OPTION_REQ_IPADDR;
*optptr++ = 4;
- memcpy(optptr, s.ipaddr, 4);
+ memcpy(optptr, presult->ipaddr, 4);
return optptr + 4;
}
@@ -168,11 +179,11 @@ static uint8 *add_end(uint8 *optptr)
return optptr;
}
-static void create_msg(register struct dhcp_msg *m)
+static void create_msg(struct dhcpc_state_internal *pdhcpc, struct dhcp_msg *m)
{
m->op = DHCP_REQUEST;
m->htype = DHCP_HTYPE_ETHERNET;
- m->hlen = s.mac_len;
+ m->hlen = pdhcpc->mac_len;
m->hops = 0;
memcpy(m->xid, xid, sizeof(m->xid));
m->secs = 0;
@@ -182,9 +193,9 @@ static void create_msg(register struct dhcp_msg *m)
memset(m->yiaddr, 0, sizeof(m->yiaddr));
memset(m->siaddr, 0, sizeof(m->siaddr));
memset(m->giaddr, 0, sizeof(m->giaddr));
- memcpy(m->chaddr, s.mac_addr, s.mac_len);
- memset(&m->chaddr[s.mac_len], 0, sizeof(m->chaddr) - s.mac_len);
-#ifndef CONFIG_UIP_DHCP_LIGHT
+ memcpy(m->chaddr, pdhcpc->mac_addr, pdhcpc->mac_len);
+ memset(&m->chaddr[pdhcpc->mac_len], 0, sizeof(m->chaddr) - pdhcpc->mac_len);
+#ifndef CONFIG_NET_DHCP_LIGHT
memset(m->sname, 0, sizeof(m->sname));
memset(m->file, 0, sizeof(m->file));
#endif
@@ -192,12 +203,12 @@ static void create_msg(register struct dhcp_msg *m)
memcpy(m->options, magic_cookie, sizeof(magic_cookie));
}
-static void send_discover(void)
+static void send_discover(struct dhcpc_state_internal *pdhcpc)
{
uint8 *end;
struct dhcp_msg *m = (struct dhcp_msg *)uip_appdata;
- create_msg(m);
+ create_msg(pdhcpc, m);
end = add_msg_type(&m->options[4], DHCPDISCOVER);
end = add_req_options(end);
@@ -206,22 +217,22 @@ static void send_discover(void)
uip_send(uip_appdata, end - (uint8 *)uip_appdata);
}
-static void send_request(void)
+static void send_request(struct dhcpc_state_internal *pdhcpc)
{
uint8 *end;
struct dhcp_msg *m = (struct dhcp_msg *)uip_appdata;
- create_msg(m);
+ create_msg(pdhcpc, m);
end = add_msg_type(&m->options[4], DHCPREQUEST);
- end = add_server_id(end);
- end = add_req_ipaddr(end);
+ end = add_server_id(pdhcpc->result, end);
+ end = add_req_ipaddr(pdhcpc->result, end);
end = add_end(end);
uip_send(uip_appdata, end - (uint8 *)uip_appdata);
}
-static uint8 parse_options(uint8 *optptr, int len)
+static uint8 parse_options(struct dhcpc_state *presult, uint8 *optptr, int len)
{
uint8 *end = optptr + len;
uint8 type = 0;
@@ -231,22 +242,22 @@ static uint8 parse_options(uint8 *optptr, int len)
switch(*optptr)
{
case DHCP_OPTION_SUBNET_MASK:
- memcpy(s.netmask, optptr + 2, 4);
+ memcpy(presult->netmask, optptr + 2, 4);
break;
case DHCP_OPTION_ROUTER:
- memcpy(s.default_router, optptr + 2, 4);
+ memcpy(presult->default_router, optptr + 2, 4);
break;
case DHCP_OPTION_DNS_SERVER:
- memcpy(s.dnsaddr, optptr + 2, 4);
+ memcpy(presult->dnsaddr, optptr + 2, 4);
break;
case DHCP_OPTION_MSG_TYPE:
type = *(optptr + 2);
break;
case DHCP_OPTION_SERVER_ID:
- memcpy(s.serverid, optptr + 2, 4);
+ memcpy(presult->serverid, optptr + 2, 4);
break;
case DHCP_OPTION_LEASE_TIME:
- memcpy(s.lease_time, optptr + 2, 4);
+ memcpy(presult->lease_time, optptr + 2, 4);
break;
case DHCP_OPTION_END:
return type;
@@ -257,115 +268,131 @@ static uint8 parse_options(uint8 *optptr, int len)
return type;
}
-static uint8 parse_msg(void)
+static uint8 parse_msg(struct dhcpc_state_internal *pdhcpc)
{
+ struct dhcpc_state *presult = pdhcpc->result;
struct dhcp_msg *m = (struct dhcp_msg *)uip_appdata;
if (m->op == DHCP_REPLY &&
- memcmp(m->xid, xid, sizeof(xid)) == 0 &&
- memcmp(m->chaddr, s.mac_addr, s.mac_len) == 0)
+ memcmp(m->xid, xid, sizeof(xid)) == 0 &&
+ memcmp(m->chaddr, pdhcpc->mac_addr, pdhcpc->mac_len) == 0)
{
- memcpy(s.ipaddr, m->yiaddr, 4);
- return parse_options(&m->options[4], uip_datalen());
+ memcpy(presult->ipaddr, m->yiaddr, 4);
+ return parse_options(presult, &m->options[4], uip_datalen());
}
return 0;
}
-static void handle_dhcp(void)
+static void handle_dhcp(struct dhcpc_state_internal *pdhcpc)
{
+ struct dhcpc_state *presult = pdhcpc->result;
+
restart:
- s.state = STATE_SENDING;
- s.ticks = CLOCK_SECOND;
+ pdhcpc->state = STATE_SENDING;
+ pdhcpc->ticks = CLOCK_SECOND;
do
{
/* Send the command */
- send_discover();
+ send_discover(pdhcpc);
/* Wait for the response */
uip_event_timedwait(UIP_NEWDATA, CLOCK_SECOND);
- if (uip_newdata() && parse_msg() == DHCPOFFER)
+ if (uip_newdata() && parse_msg(pdhcpc) == DHCPOFFER)
{
- s.state = STATE_OFFER_RECEIVED;
+ pdhcpc->state = STATE_OFFER_RECEIVED;
break;
}
- if (s.ticks < CLOCK_SECOND * 60)
+ if (pdhcpc->ticks < CLOCK_SECOND * 60)
{
- s.ticks *= 2;
+ pdhcpc->ticks *= 2;
}
}
- while(s.state != STATE_OFFER_RECEIVED);
+ while(pdhcpc->state != STATE_OFFER_RECEIVED);
- s.ticks = CLOCK_SECOND;
+ pdhcpc->ticks = CLOCK_SECOND;
do
{
/* Send the request */
- send_request();
+ send_request(pdhcpc);
/* Then wait to received the response */
uip_event_timedwait(UIP_NEWDATA, CLOCK_SECOND);
- if (uip_newdata() && parse_msg() == DHCPACK)
+ if (uip_newdata() && parse_msg(pdhcpc) == DHCPACK)
{
- s.state = STATE_CONFIG_RECEIVED;
+ pdhcpc->state = STATE_CONFIG_RECEIVED;
break;
}
- if (s.ticks <= CLOCK_SECOND * 10)
+ if (pdhcpc->ticks <= CLOCK_SECOND * 10)
{
- s.ticks += CLOCK_SECOND;
+ pdhcpc->ticks += CLOCK_SECOND;
}
else
{
goto restart;
}
}
- while(s.state != STATE_CONFIG_RECEIVED);
+ while(pdhcpc->state != STATE_CONFIG_RECEIVED);
dbg("Got IP address %d.%d.%d.%d\n",
- uip_ipaddr1(s.ipaddr), uip_ipaddr2(s.ipaddr),
- uip_ipaddr3(s.ipaddr), uip_ipaddr4(s.ipaddr));
+ uip_ipaddr1(presult->ipaddr), uip_ipaddr2(presult->ipaddr),
+ uip_ipaddr3(presult->ipaddr), uip_ipaddr4(presult->ipaddr));
dbg("Got netmask %d.%d.%d.%d\n",
- uip_ipaddr1(s.netmask), uip_ipaddr2(s.netmask),
- uip_ipaddr3(s.netmask), uip_ipaddr4(s.netmask));
+ uip_ipaddr1(presult->netmask), uip_ipaddr2(presult->netmask),
+ uip_ipaddr3(presult->netmask), uip_ipaddr4(presult->netmask));
dbg("Got DNS server %d.%d.%d.%d\n",
- uip_ipaddr1(s.dnsaddr), uip_ipaddr2(s.dnsaddr),
- uip_ipaddr3(s.dnsaddr), uip_ipaddr4(s.dnsaddr));
+ uip_ipaddr1(presult->dnsaddr), uip_ipaddr2(presult->dnsaddr),
+ uip_ipaddr3(presult->dnsaddr), uip_ipaddr4(presult->dnsaddr));
dbg("Got default router %d.%d.%d.%d\n",
- uip_ipaddr1(s.default_router), uip_ipaddr2(s.default_router),
- uip_ipaddr3(s.default_router), uip_ipaddr4(s.default_router));
+ uip_ipaddr1(presult->default_router), uip_ipaddr2(presult->default_router),
+ uip_ipaddr3(presult->default_router), uip_ipaddr4(presult->default_router));
dbg("Lease expires in %ld seconds\n",
- ntohs(s.lease_time[0])*65536ul + ntohs(s.lease_time[1]));
-
- dhcpc_configured(&s);
-
- pthread_exit(NULL);
+ ntohs(presult->lease_time[0])*65536ul + ntohs(presult->lease_time[1]));
}
-/************************************************************
+/****************************************************************************
* Global Functions
- ************************************************************/
+ ****************************************************************************/
-void dhcpc_init(const void *mac_addr, int mac_len)
+void *dhcpc_open(const void *mac_addr, int mac_len)
{
uip_ipaddr_t addr;
+ struct dhcpc_state_internal *pdhcpc;
- s.mac_addr = mac_addr;
- s.mac_len = mac_len;
+ pdhcpc = (struct dhcpc_state_internal *)malloc(sizeof(struct dhcpc_state_internal));
+ if (pdhcpc)
+ {
+ memset(pdhcpc, 0, sizeof(struct dhcpc_state_internal));
+ pdhcpc->mac_addr = mac_addr;
+ pdhcpc->mac_len = mac_len;
+ pdhcpc->state = STATE_INITIAL;
+ sem_init(&pdhcpc->sem, 0, 0);
+
+ uip_ipaddr(addr, 255,255,255,255);
+ pdhcpc->conn = uip_udp_new(&addr, HTONS(DHCPC_SERVER_PORT));
+ if (pdhcpc->conn != NULL)
+ {
+ uip_udp_bind(pdhcpc->conn, HTONS(DHCPC_CLIENT_PORT));
+ }
+ }
+ return (void*)pdhcpc;
+}
- s.state = STATE_INITIAL;
- uip_ipaddr(addr, 255,255,255,255);
- s.conn = uip_udp_new(&addr, HTONS(DHCPC_SERVER_PORT));
- if (s.conn != NULL)
+void dhcpc_close(void *handle)
+{
+ struct dchcpc_state_internal *pdhcpc = (struct dchcpc_state_internal *)handle;
+ if (pdhcpc)
{
- uip_udp_bind(s.conn, HTONS(DHCPC_CLIENT_PORT));
+ free(pdhcpc);
}
}
@@ -375,16 +402,27 @@ void dhcpc_init(const void *mac_addr, int mac_len)
void uip_interrupt_udp_event(void)
{
- handle_dhcp();
+ if (gpdhcpc)
+ {
+ sem_post(&gpdhcpc->sem);
+ }
}
-void dhcpc_request(void)
+int dhcpc_request(void *handle, struct dhcpc_state *ds)
{
+ struct dhcpc_state_internal *pdhcpc = (struct dhcpc_state_internal *)handle;
uint16 ipaddr[2];
- if (s.state == STATE_INITIAL)
+ if (pdhcpc->state == STATE_INITIAL)
{
uip_ipaddr(ipaddr, 0,0,0,0);
uip_sethostaddr(ipaddr);
}
+
+ pdhcpc->result = ds;
+ gpdhcpc = pdhcpc;
+ sem_wait(&pdhcpc->sem);
+ gpdhcpc = NULL;
+ handle_dhcp(pdhcpc);
+ return OK;
}