summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-03 23:35:18 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-03 23:35:18 +0000
commit65f8e15b78891b15b1caabe45d1163f63fa530e0 (patch)
treecbca93cb25a0ae75f1f4ebce49d94e9ec6060ac8 /nuttx
parentc96d656001914b495f54e7a25d54079e41af86ce (diff)
downloadpx4-nuttx-65f8e15b78891b15b1caabe45d1163f63fa530e0.tar.gz
px4-nuttx-65f8e15b78891b15b1caabe45d1163f63fa530e0.tar.bz2
px4-nuttx-65f8e15b78891b15b1caabe45d1163f63fa530e0.zip
cleanup
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@329 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/fs/fs_write.c2
-rw-r--r--nuttx/include/net/uip/resolv.h4
-rw-r--r--nuttx/include/net/uip/uip.h9
-rw-r--r--nuttx/net/uip/uip.c65
-rw-r--r--nuttx/netutils/dhcpc/dhcpc.c2
-rw-r--r--nuttx/netutils/resolv/resolv.c67
-rw-r--r--nuttx/netutils/smtp/smtp.c3
-rw-r--r--nuttx/netutils/telnetd/shell.c53
-rw-r--r--nuttx/netutils/telnetd/telnetd.c6
-rw-r--r--nuttx/netutils/webclient/webclient.c7
-rw-r--r--nuttx/netutils/webclient/webclient.h89
-rw-r--r--nuttx/netutils/webserver/httpd.c1
12 files changed, 138 insertions, 170 deletions
diff --git a/nuttx/fs/fs_write.c b/nuttx/fs/fs_write.c
index 7de7898f4..b0d523a45 100644
--- a/nuttx/fs/fs_write.c
+++ b/nuttx/fs/fs_write.c
@@ -156,7 +156,7 @@ int write(int fd, const void *buf, unsigned int nbytes)
/* Is a driver registered? Does it support the write method? */
inode = this_file->f_inode;
- if (!inode || !inode->u.i_ops && inode->u.i_ops->write)
+ if (!inode || !inode->u.i_ops || !inode->u.i_ops->write)
{
err = EBADF;
goto errout;
diff --git a/nuttx/include/net/uip/resolv.h b/nuttx/include/net/uip/resolv.h
index 9ab900978..1f22012b5 100644
--- a/nuttx/include/net/uip/resolv.h
+++ b/nuttx/include/net/uip/resolv.h
@@ -51,11 +51,11 @@ EXTERN int resolv_init(void);
#ifdef CONFIG_NET_IPv6
EXTERN void resolv_conf(const struct sockaddr_in6 *dnsserver);
EXTERN void resolv_getserver(const struct sockaddr_in6 *dnsserver);
-EXTERN int resolv_query(char *name, struct sockaddr_in6 *addr);
+EXTERN int resolv_query(const char *name, struct sockaddr_in6 *addr);
#else
EXTERN void resolv_conf(const struct sockaddr_in *dnsserver);
EXTERN void resolv_getserver(const struct sockaddr_in *dnsserver);
-EXTERN int resolv_query(char *name, struct sockaddr_in *addr);
+EXTERN int resolv_query(const char *name, struct sockaddr_in *addr);
#endif
#undef EXTERN
diff --git a/nuttx/include/net/uip/uip.h b/nuttx/include/net/uip/uip.h
index b03233ed3..0aceb8603 100644
--- a/nuttx/include/net/uip/uip.h
+++ b/nuttx/include/net/uip/uip.h
@@ -608,14 +608,7 @@ void uip_setipid(uint16 id);
* functions for opening and closing connections, sending and receiving
* data, etc.
*
- * The following function must be provided by the application logic. It
- * is called from the UIP interrupt handler when interesting events are
- * detected that may be of interest to the application.
- */
-
-extern void uip_interrupt_event(void);
-
-/* Find a free connection structure and allocate it for use. This is
+ * Find a free connection structure and allocate it for use. This is
* normally something done by the implementation of the socket() API
*/
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index 44403af84..a8a149be2 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -588,8 +588,10 @@ static void uip_add_rcv_nxt(uint16 n)
uip_conn->rcv_nxt[3] = uip_acc32[3];
}
-static uip_udp_callback(void)
+static void uip_udp_callback(void)
{
+ uip_event_signal();
+
/* Some sanity checking */
if (uip_udp_conn && uip_udp_conn->callback)
@@ -600,6 +602,20 @@ static uip_udp_callback(void)
}
}
+static void uip_tcp_callback(void)
+{
+ uip_event_signal();
+
+ /* Some sanity checking */
+
+ if (uip_conn && uip_conn->callback)
+ {
+ /* Perform the callback */
+
+ uip_conn->callback(uip_conn->private);
+ }
+}
+
void uip_interrupt(uint8 flag)
{
register struct uip_conn *uip_connr = uip_conn;
@@ -623,8 +639,7 @@ void uip_interrupt(uint8 flag)
!uip_outstanding(uip_connr))
{
uip_flags = UIP_POLL;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
goto appsend;
}
goto drop;
@@ -683,14 +698,13 @@ void uip_interrupt(uint8 flag)
{
uip_connr->tcpstateflags = UIP_CLOSED;
- /* We call uip_interrupt_event() with uip_flags set to
+ /* We call uip_tcp_callback() with uip_flags set to
* UIP_TIMEDOUT to inform the application that the
* connection has timed out.
*/
uip_flags = UIP_TIMEDOUT;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
/* We also send a reset packet to the remote host. */
@@ -734,8 +748,7 @@ void uip_interrupt(uint8 flag)
*/
uip_flags = UIP_REXMIT;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
goto apprexmit;
case UIP_FIN_WAIT_1:
@@ -754,8 +767,7 @@ void uip_interrupt(uint8 flag)
*/
uip_flags = UIP_POLL;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
goto appsend;
}
}
@@ -771,8 +783,7 @@ void uip_interrupt(uint8 flag)
uip_sappdata = uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
uip_len = uip_slen = 0;
uip_flags = UIP_POLL;
- uip_event_signal();
- up_udp_callback();
+ uip_udp_callback();
goto udp_send;
}
else
@@ -1111,8 +1122,7 @@ void uip_interrupt(uint8 flag)
uip_flags = UIP_NEWDATA;
uip_sappdata = uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
uip_slen = 0;
- uip_event_signal();
- up_udp_callback();
+ uip_udp_callback();
udp_send:
if (uip_slen == 0)
@@ -1362,8 +1372,7 @@ tcp_send_synack:
uip_connr->tcpstateflags = UIP_CLOSED;
UIP_LOG("tcp: got reset, aborting connection.");
uip_flags = UIP_ABORT;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
goto drop;
}
@@ -1471,8 +1480,7 @@ tcp_send_synack:
uip_add_rcv_nxt(uip_len);
}
uip_slen = 0;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
goto appsend;
}
goto drop;
@@ -1537,15 +1545,13 @@ tcp_send_synack:
uip_connr->len = 0;
uip_len = 0;
uip_slen = 0;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
goto appsend;
}
/* Inform the application that the connection failed */
uip_flags = UIP_ABORT;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
/* The connection is closed after we send the RST */
uip_conn->tcpstateflags = UIP_CLOSED;
@@ -1575,8 +1581,7 @@ tcp_send_synack:
{
uip_flags |= UIP_NEWDATA;
}
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
uip_connr->len = 1;
uip_connr->tcpstateflags = UIP_LAST_ACK;
uip_connr->nrtx = 0;
@@ -1660,8 +1665,7 @@ tcp_send_synack:
if (uip_flags & (UIP_NEWDATA | UIP_ACKDATA))
{
uip_slen = 0;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
appsend:
if (uip_flags & UIP_ABORT)
@@ -1753,8 +1757,7 @@ tcp_send_synack:
{
uip_connr->tcpstateflags = UIP_CLOSED;
uip_flags = UIP_CLOSE;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
}
break;
@@ -1780,8 +1783,7 @@ tcp_send_synack:
}
uip_add_rcv_nxt(1);
uip_flags = UIP_CLOSE;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
goto tcp_send_ack;
}
else if (uip_flags & UIP_ACKDATA)
@@ -1807,8 +1809,7 @@ tcp_send_synack:
uip_connr->timer = 0;
uip_add_rcv_nxt(1);
uip_flags = UIP_CLOSE;
- uip_event_signal();
- uip_interrupt_event();
+ uip_tcp_callback();
goto tcp_send_ack;
}
if (uip_len > 0)
diff --git a/nuttx/netutils/dhcpc/dhcpc.c b/nuttx/netutils/dhcpc/dhcpc.c
index a2a233e93..30172cef5 100644
--- a/nuttx/netutils/dhcpc/dhcpc.c
+++ b/nuttx/netutils/dhcpc/dhcpc.c
@@ -402,7 +402,7 @@ void dhcpc_close(void *handle)
void uip_interrupt_udp_event(void)
{
-#error OBSOLETE
+#warning OBSOLETE
if (gpdhcpc)
{
sem_post(&gpdhcpc->sem);
diff --git a/nuttx/netutils/resolv/resolv.c b/nuttx/netutils/resolv/resolv.c
index 512f1ac59..b6c861e51 100644
--- a/nuttx/netutils/resolv/resolv.c
+++ b/nuttx/netutils/resolv/resolv.c
@@ -55,6 +55,8 @@
#include <debug.h>
#include <sys/socket.h>
+#include <arpa/inet.h>
+
#include <net/uip/resolv.h>
/****************************************************************************
@@ -90,6 +92,12 @@
#define SEND_BUFFER_SIZE 64
#define RECV_BUFFER_SIZE 64
+#ifdef CONFIG_NET_IPv6
+#define ADDRLEN sizeof(struct sockaddr_in6)
+#else
+#define ADDRLEN sizeof(struct sockaddr_in)
+#endif
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -118,7 +126,10 @@ struct dns_answer
uint16 class;
uint16 ttl[2];
uint16 len;
- uip_ipaddr_t ipaddr;
+#ifdef CONFIG_NET_IPv6
+#else
+ uint16 ipaddr[2];
+#endif
};
struct namemap
@@ -129,20 +140,22 @@ struct namemap
uint8 seqno;
uint8 err;
char name[32];
- uip_ipaddr_t ipaddr;
+#ifdef CONFIG_NET_IPv6
+#else
+ uint16 ipaddr[2];
+#endif
};
/****************************************************************************
* Private Data
****************************************************************************/
-static struct namemap names[RESOLV_ENTRIES];
-static uint8 gseqno;
+static uint8 g_seqno;
static int g_sockfd = -1;
#ifdef CONFIG_NET_IPv6
-static struct sockaddr_in6 gdnsserver;
+static struct sockaddr_in6 g_dnsserver;
#else
-static struct sockaddr_in gdnsserver;
+static struct sockaddr_in g_dnsserver;
#endif
/****************************************************************************
@@ -173,19 +186,20 @@ static unsigned char *parse_name(unsigned char *query)
* not yet been queried and, if so, sends out a query.
*/
-static int send_query(const char name)
+#ifdef CONFIG_NET_IPv6
+static int send_query(const char *name, struct sockaddr_in6 *addr)
+#else
+static int send_query(const char *name, struct sockaddr_in *addr)
+#endif
{
register struct dns_hdr *hdr;
char *query;
char *nptr;
- char **nameptr;
- static uint8 i;
- static uint8 n;
- uint8 state = NEW_STATE;
- uint8 seqno = gsegno++;
- uint8 err;
+ const char *nameptr;
+ uint8 seqno = g_seqno++;
static unsigned char endquery[] = {0,0,1,0,1};
char buffer[SEND_BUFFER_SIZE];
+ int n;
hdr = (struct dns_hdr*)buffer;
memset(hdr, 0, sizeof(struct dns_hdr));
@@ -201,18 +215,17 @@ static int send_query(const char name)
{
nameptr++;
nptr = query++;
- for (n = 0; *nameptr != '.' && *nameptr != 0; ++nameptr)
+ for (n = 0; *nameptr != '.' && *nameptr != 0; nameptr++)
{
- *query = *nameptr;
- ++query;
- ++n;
+ *query++ = *nameptr;
+ n++;
}
*nptr = n;
}
while(*nameptr != 0);
memcpy(query, endquery, 5);
- return sendto(gsockfd, buffer, query + 5 - buffer);
+ return sendto(g_sockfd, buffer, query + 5 - buffer, 0, (struct sockaddr*)addr, ADDRLEN);
}
/* Called when new UDP data arrives */
@@ -222,8 +235,6 @@ static int send_query(const char name)
#else
int recv_response(struct sockaddr_in *addr)
#endif
-
-hdr->flags2 & DNS_FLAG2_ERR_MASKstatic int (void)
{
unsigned char *nameptr;
char buffer[RECV_BUFFER_SIZE];
@@ -231,18 +242,17 @@ hdr->flags2 & DNS_FLAG2_ERR_MASKstatic int (void)
struct dns_hdr *hdr;
uint8 nquestions;
uint8 nanswers;
- uint8 i;
int ret;
/* Receive the response */
- ret = recv(g_sockfd, buffer, RECV_BUFFER_SIZE);
+ ret = recv(g_sockfd, buffer, RECV_BUFFER_SIZE, 0);
if (ret < 0)
{
return ret;
}
- hdr = (struct dns_hdr *)b
+ hdr = (struct dns_hdr *)buffer;
dbg( "ID %d\n", htons(hdr->id));
dbg( "Query %d\n", hdr->flags1 & DNS_FLAG1_RESPONSE);
@@ -316,6 +326,7 @@ hdr->flags2 & DNS_FLAG2_ERR_MASKstatic int (void)
nameptr = nameptr + 10 + htons(ans->len);
}
}
+ return ERROR;
}
/****************************************************************************
@@ -325,12 +336,12 @@ hdr->flags2 & DNS_FLAG2_ERR_MASKstatic int (void)
/* Get the binding for name. */
#ifdef CONFIG_NET_IPv6
-int resolv_query(char *name, struct sockaddr_in6 *addr)
+int resolv_query(const char *name, struct sockaddr_in6 *addr)
#else
-int resolv_query(char *name, struct sockaddr_in *addr)
+int resolv_query(const char *name, struct sockaddr_in *addr)
#endif
{
- int ret = send_query(name);
+ int ret = send_query(name, addr);
if (ret == 0)
{
ret = recv_response(addr);
@@ -346,7 +357,7 @@ void resolv_getserver(const struct sockaddr_in6 *dnsserver)
void resolv_getserver(const struct sockaddr_in *dnsserver)
#endif
{
- memcpy(dnsserver, gdnsserver, sizeof(gdnsserver));
+ memcpy(dnsserver, &g_dnsserver, ADDRLEN);
}
/* Configure which DNS server to use for queries */
@@ -357,7 +368,7 @@ void resolv_conf(const struct sockaddr_in6 *dnsserver)
void resolv_conf(const struct sockaddr_in *dnsserver)
#endif
{
- memcpy(&gdnsserver, dnsserver, sizeof(gdnsserver));
+ memcpy(&g_dnsserver, dnsserver, ADDRLEN);
}
/* Initalize the resolver. */
diff --git a/nuttx/netutils/smtp/smtp.c b/nuttx/netutils/smtp/smtp.c
index 09d131057..5d7a61aa6 100644
--- a/nuttx/netutils/smtp/smtp.c
+++ b/nuttx/netutils/smtp/smtp.c
@@ -213,6 +213,7 @@ static void smtp_send_message(struct smtp_state *psmtp)
void uip_interrupt_event(void)
{
+#warning OBSOLETE -- needs to be redesigned
if (gpsmtp)
{
if (uip_closed())
@@ -346,4 +347,4 @@ void smtp_close(void *handle)
sem_destroy(&psmtp->sem);
free(psmtp);
}
-} \ No newline at end of file
+}
diff --git a/nuttx/netutils/telnetd/shell.c b/nuttx/netutils/telnetd/shell.c
index 2c1ddbaae..3c68350e0 100644
--- a/nuttx/netutils/telnetd/shell.c
+++ b/nuttx/netutils/telnetd/shell.c
@@ -25,11 +25,6 @@
* 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 file is part of the uIP TCP/IP stack.
- *
- * $Id: shell.c,v 1.1.1.1 2007-08-26 23:07:06 patacongo Exp $
- *
*/
#include "shell.h"
@@ -43,9 +38,7 @@ struct ptentry {
#define SHELL_PROMPT "uIP 1.0> "
-/*---------------------------------------------------------------------------*/
-static void
-parse(register char *str, struct ptentry *t)
+static void parse(register char *str, struct ptentry *t)
{
struct ptentry *p;
for(p = t; p->commandstr != NULL; ++p) {
@@ -56,25 +49,8 @@ parse(register char *str, struct ptentry *t)
p->pfunc(str);
}
-/*---------------------------------------------------------------------------*/
-static void
-inttostr(register char *str, unsigned int i)
-{
- str[0] = '0' + i / 100;
- if(str[0] == '0') {
- str[0] = ' ';
- }
- str[1] = '0' + (i / 10) % 10;
- if(str[0] == ' ' && str[1] == '0') {
- str[1] = ' ';
- }
- str[2] = '0' + i % 10;
- str[3] = ' ';
- str[4] = 0;
-}
-/*---------------------------------------------------------------------------*/
-static void
-help(char *str)
+
+static void help(char *str)
{
shell_output("Available commands:", "");
shell_output("stats - show network statistics", "");
@@ -82,15 +58,14 @@ help(char *str)
shell_output("help, ? - show help", "");
shell_output("exit - exit shell", "");
}
-/*---------------------------------------------------------------------------*/
-static void
-unknown(char *str)
+
+static void unknown(char *str)
{
if(strlen(str) > 0) {
shell_output("Unknown command: ", str);
}
}
-/*---------------------------------------------------------------------------*/
+
static struct ptentry parsetab[] =
{{"stats", help},
{"conn", help},
@@ -100,24 +75,20 @@ static struct ptentry parsetab[] =
/* Default action */
{NULL, unknown}};
-/*---------------------------------------------------------------------------*/
-void
-shell_init(void)
+
+void shell_init(void)
{
}
-/*---------------------------------------------------------------------------*/
-void
-shell_start(void)
+
+void shell_start(void)
{
shell_output("uIP command shell", "");
shell_output("Type '?' and return for help", "");
shell_prompt(SHELL_PROMPT);
}
-/*---------------------------------------------------------------------------*/
-void
-shell_input(char *cmd)
+
+void shell_input(char *cmd)
{
parse(cmd, parsetab);
shell_prompt(SHELL_PROMPT);
}
-/*---------------------------------------------------------------------------*/
diff --git a/nuttx/netutils/telnetd/telnetd.c b/nuttx/netutils/telnetd/telnetd.c
index 21700023c..39a6f0f10 100644
--- a/nuttx/netutils/telnetd/telnetd.c
+++ b/nuttx/netutils/telnetd/telnetd.c
@@ -25,11 +25,6 @@
* 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 file is part of the uIP TCP/IP stack
- *
- * $Id: telnetd.c,v 1.1.1.1 2007-08-26 23:07:06 patacongo Exp $
- *
*/
#include <sys/types.h>
@@ -293,6 +288,7 @@ newdata(void)
void uip_interrupt_event(void)
{
+#warning OBSOLETE -- needs to be redesigned
static unsigned int i;
if(uip_connected()) {
/* tcp_markconn(uip_conn, &s);*/
diff --git a/nuttx/netutils/webclient/webclient.c b/nuttx/netutils/webclient/webclient.c
index 6d0c0645b..be937db41 100644
--- a/nuttx/netutils/webclient/webclient.c
+++ b/nuttx/netutils/webclient/webclient.c
@@ -38,7 +38,7 @@
*
* This file is part of the uIP TCP/IP stack.
*
- * $Id: webclient.c,v 1.3 2007-09-03 20:34:44 patacongo Exp $
+ * $Id: webclient.c,v 1.4 2007-09-03 23:35:17 patacongo Exp $
*
*/
@@ -117,7 +117,7 @@ void webclient_close(void)
s.state = WEBCLIENT_STATE_CLOSE;
}
-unsigned char webclient_get(char *host, uint16 port, char *file)
+unsigned char webclient_get(const char *host, uint16 port, char *file)
{
uip_ipaddr_t *ipaddr;
static uip_ipaddr_t addr;
@@ -397,6 +397,7 @@ static void newdata(void)
void uip_interrupt_event(void)
{
+#warning OBSOLETE -- needs to be redesigned
if (uip_connected())
{
s.timer = 0;
@@ -466,7 +467,7 @@ void uip_interrupt_event(void)
#endif
if (resolv_query(s.host, &addr) < 0)
{
- return ERROR;
+ return;
}
webclient_get(s.host, s.port, s.file);
}
diff --git a/nuttx/netutils/webclient/webclient.h b/nuttx/netutils/webclient/webclient.h
index c6559e3f0..a293b61fc 100644
--- a/nuttx/netutils/webclient/webclient.h
+++ b/nuttx/netutils/webclient/webclient.h
@@ -30,12 +30,8 @@
* 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 file is part of the uIP TCP/IP stack.
- *
- * $Id: webclient.h,v 1.1.1.1 2007-08-26 23:07:04 patacongo Exp $
- *
*/
+
#ifndef __WEBCLIENT_H__
#define __WEBCLIENT_H__
@@ -46,7 +42,8 @@
#define WEBCLIENT_CONF_MAX_URLLEN 100
-struct webclient_state {
+struct webclient_state
+{
uint8 timer;
uint8 state;
uint8 httpflag;
@@ -63,8 +60,7 @@ struct webclient_state {
char mimetype[32];
};
-/**
- * Callback function that is called from the webclient code when HTTP
+/* Callback function that is called from the webclient code when HTTP
* data has been received.
*
* This function must be implemented by the module that uses the
@@ -72,58 +68,57 @@ struct webclient_state {
* when HTTP data has been received. The function is not called when
* HTTP headers are received, only for the actual data.
*
- * \note This function is called many times, repetedly, when data is
+ * Note: This function is called many times, repetedly, when data is
* being received, and not once when all data has been received.
*
- * \param data A pointer to the data that has been received.
- * \param len The length of the data that has been received.
+ * data A pointer to the data that has been received.
+ * len The length of the data that has been received.
*/
+
void webclient_datahandler(char *data, uint16 len);
-/**
- * Callback function that is called from the webclient code when the
+/* Callback function that is called from the webclient code when the
* HTTP connection has been connected to the web server.
*
* This function must be implemented by the module that uses the
* webclient code.
*/
+
void webclient_connected(void);
-/**
- * Callback function that is called from the webclient code if the
+/* Callback function that is called from the webclient code if the
* HTTP connection to the web server has timed out.
*
* This function must be implemented by the module that uses the
* webclient code.
*/
+
void webclient_timedout(void);
-/**
- * Callback function that is called from the webclient code if the
+/* Callback function that is called from the webclient code if the
* HTTP connection to the web server has been aborted by the web
* server.
*
* This function must be implemented by the module that uses the
* webclient code.
*/
+
void webclient_aborted(void);
-/**
- * Callback function that is called from the webclient code when the
+/* Callback function that is called from the webclient code when the
* HTTP connection to the web server has been closed.
*
* This function must be implemented by the module that uses the
* webclient code.
*/
+
void webclient_closed(void);
-/**
- * Initialize the webclient module.
- */
+/* Initialize the webclient module. */
+
void webclient_init(void);
-/**
- * Open an HTTP connection to a web server and ask for a file using
+/* Open an HTTP connection to a web server and ask for a file using
* the GET method.
*
* This function opens an HTTP connection to the specified web server
@@ -140,75 +135,73 @@ void webclient_init(void);
* When the HTTP request has been completed and the HTTP connection is
* closed, the webclient_closed() callback function will be called.
*
- * \note If the function is passed a host name, it must already be in
+ * Note: If the function is passed a host name, it must already be in
* the resolver cache in order for the function to connect to the web
* server. It is therefore up to the calling module to implement the
* resolver calls and the signal handler used for reporting a resolv
* query answer.
*
- * \param host A pointer to a string containing either a host name or
+ * host A pointer to a string containing either a host name or
* a numerical IP address in dotted decimal notation (e.g., 192.168.23.1).
*
- * \param port The port number to which to connect, in host byte order.
+ * port The port number to which to connect, in host byte order.
*
- * \param file A pointer to the name of the file to get.
+ * file A pointer to the name of the file to get.
*
- * \retval 0 if the host name could not be found in the cache, or
+ * Return: 0 if the host name could not be found in the cache, or
* if a TCP connection could not be created.
*
- * \retval 1 if the connection was initiated.
+ * Return: 1 if the connection was initiated.
*/
-unsigned char webclient_get(char *host, uint16 port, char *file);
-/**
- * Close the currently open HTTP connection.
- */
+unsigned char webclient_get(const char *host, uint16 port, char *file);
+
+/* Close the currently open HTTP connection. */
+
void webclient_close(void);
-/**
- * Obtain the MIME type of the current HTTP data stream.
+/* Obtain the MIME type of the current HTTP data stream.
*
- * \return A pointer to a string contaning the MIME type. The string
+ * Return: A pointer to a string contaning the MIME type. The string
* may be empty if no MIME type was reported by the web server.
*/
+
char *webclient_mimetype(void);
-/**
- * Obtain the filename of the current HTTP data stream.
+/* Obtain the filename of the current HTTP data stream.
*
* The filename of an HTTP request may be changed by the web server,
* and may therefore not be the same as when the original GET request
* was made with webclient_get(). This function is used for obtaining
* the current filename.
*
- * \return A pointer to the current filename.
+ * Return: A pointer to the current filename.
*/
+
char *webclient_filename(void);
-/**
- * Obtain the hostname of the current HTTP data stream.
+/* Obtain the hostname of the current HTTP data stream.
*
* The hostname of the web server of an HTTP request may be changed
* by the web server, and may therefore not be the same as when the
* original GET request was made with webclient_get(). This function
* is used for obtaining the current hostname.
*
- * \return A pointer to the current hostname.
+ * Return: A pointer to the current hostname.
*/
+
char *webclient_hostname(void);
-/**
- * Obtain the port number of the current HTTP data stream.
+/* Obtain the port number of the current HTTP data stream.
*
* The port number of an HTTP request may be changed by the web
* server, and may therefore not be the same as when the original GET
* request was made with webclient_get(). This function is used for
* obtaining the current port number.
*
- * \return The port number of the current HTTP data stream, in host byte order.
+ * Return: The port number of the current HTTP data stream, in host byte order.
*/
+
unsigned short webclient_port(void);
#endif /* __WEBCLIENT_H__ */
-
-/** @} */
diff --git a/nuttx/netutils/webserver/httpd.c b/nuttx/netutils/webserver/httpd.c
index d6c855e61..6cf50962f 100644
--- a/nuttx/netutils/webserver/httpd.c
+++ b/nuttx/netutils/webserver/httpd.c
@@ -253,6 +253,7 @@ static void handle_connection(struct httpd_state *s)
void uip_interrupt_event(void)
{
+#warning OBSOLETE -- needs to be redesigned
/* Get the private application specific data */
struct httpd_state *s = (struct httpd_state *)(uip_conn->private);