summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/sim/src/up_devconsole.c7
-rw-r--r--nuttx/arch/sim/src/up_idle.c2
-rw-r--r--nuttx/arch/sim/src/up_initialize.c2
-rw-r--r--nuttx/arch/sim/src/up_internal.h2
-rw-r--r--nuttx/arch/sim/src/up_setjmp.S134
-rw-r--r--nuttx/arch/sim/src/up_tapdev.c7
-rw-r--r--nuttx/arch/sim/src/up_uipdriver.c5
-rw-r--r--nuttx/include/nuttx/compiler.h17
-rw-r--r--nuttx/net/send.c6
-rw-r--r--nuttx/net/socket.c2
-rw-r--r--nuttx/net/uip/uip.c4
11 files changed, 42 insertions, 146 deletions
diff --git a/nuttx/arch/sim/src/up_devconsole.c b/nuttx/arch/sim/src/up_devconsole.c
index 31c4e46c6..1bb0debdd 100644
--- a/nuttx/arch/sim/src/up_devconsole.c
+++ b/nuttx/arch/sim/src/up_devconsole.c
@@ -33,9 +33,9 @@
*
************************************************************/
-#ifndef linux
+#if !defined(linux) && !defined(__CYGWIN__)
# error "Sorry, this will only work with Linux"
-#endif
+#else
/************************************************************
* Included Files
@@ -138,3 +138,6 @@ int up_putc(int ch)
(void)up_write(1, &b, 1);
return ch;
}
+
+#endif /* linux */
+
diff --git a/nuttx/arch/sim/src/up_idle.c b/nuttx/arch/sim/src/up_idle.c
index 01457962e..5735540e1 100644
--- a/nuttx/arch/sim/src/up_idle.c
+++ b/nuttx/arch/sim/src/up_idle.c
@@ -83,7 +83,7 @@ void up_idle(void)
/* Run the network if enabled */
-#ifdef CONFIG_NET
+#if defined(CONFIG_NET) && defined(linux)
uipdriver_loop();
#endif
}
diff --git a/nuttx/arch/sim/src/up_initialize.c b/nuttx/arch/sim/src/up_initialize.c
index a7faa5032..82ba215d8 100644
--- a/nuttx/arch/sim/src/up_initialize.c
+++ b/nuttx/arch/sim/src/up_initialize.c
@@ -86,7 +86,7 @@ void up_initialize(void)
devnull_register(); /* Standard /dev/null */
up_devconsole(); /* Our private /dev/console */
up_registerblockdevice(); /* Our simulated block device /dev/blkdev */
-#ifdef CONFIG_NET
+#if defined(CONFIG_NET) && defined(linux)
uipdriver_init(); /* Our "real" netwok driver */
#endif
}
diff --git a/nuttx/arch/sim/src/up_internal.h b/nuttx/arch/sim/src/up_internal.h
index de83173d1..1d08f8381 100644
--- a/nuttx/arch/sim/src/up_internal.h
+++ b/nuttx/arch/sim/src/up_internal.h
@@ -118,7 +118,7 @@ extern void tapdev_send(char *buf, unsigned int buflen);
/* up_uipdriver.c *********************************************************/
-#ifdef CONFIG_NET
+#if defined(CONFIG_NET) && defined(linux)
extern int uipdriver_init(void);
extern void uipdriver_loop(void);
#endif
diff --git a/nuttx/arch/sim/src/up_setjmp.S b/nuttx/arch/sim/src/up_setjmp.S
index 96b9bfee8..31b9e56c0 100644
--- a/nuttx/arch/sim/src/up_setjmp.S
+++ b/nuttx/arch/sim/src/up_setjmp.S
@@ -1,129 +1,5 @@
-/**************************************************************************
- * up_setjmp.S
- *
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * 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 Gregory Nutt 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.
- *
- **************************************************************************/
-
-/**************************************************************************
- * Conditional Compilation Options
- **************************************************************************/
-
-/**************************************************************************
- * Included Files
- **************************************************************************/
-
-#include "up_internal.h"
-
-/**************************************************************************
- * Private Definitions
- **************************************************************************/
-
-/**************************************************************************
- * Private Types
- **************************************************************************/
-
-/**************************************************************************
- * Private Function Prototypes
- **************************************************************************/
-
-/**************************************************************************
- * Global Variables
- **************************************************************************/
-
-/**************************************************************************
- * Private Variables
- **************************************************************************/
-
-/**************************************************************************
- * Private Functions
- **************************************************************************/
-
-/**************************************************************************
- * Public Functions
- **************************************************************************/
-
- .text
- .globl up_setjmp
- .type up_setjmp, @function
-up_setjmp:
-
- /* %ebx, %esi, %edi, and %ebp must be preserved.
- * save %ebx, $esi, and %edi now... */
-
- movl 4(%esp), %eax
- movl %ebx, (JB_EBX)(%eax)
- movl %esi, (JB_ESI)(%eax)
- movl %edi, (JB_EDI)(%eax)
-
- /* Save the value of SP as will be after we return */
-
- leal 4(%esp), %ecx
- movl %ecx, (JB_SP)(%eax)
-
- /* Save the return PC */
-
- movl 0(%esp), %ecx
- movl %ecx, (JB_PC)(%eax)
-
- /* Save the framepointer */
-
- movl %ebp, (JB_EBP)(%eax)
-
- /* And return 0 */
-
- xorl %eax, %eax
- ret
- .size up_setjmp, . - up_setjmp
-
- .globl up_longjmp
- .type up_longjmp, @function
-up_longjmp:
- movl 4(%esp), %ecx /* U_pthread_jmpbuf in %ecx. */
- movl 8(%esp), %eax /* Second argument is return value. */
-
- /* Save the return address now. */
-
- movl (JB_PC)(%ecx), %edx
-
- /* Restore registers. */
-
- movl (JB_EBX)(%ecx), %ebx
- movl (JB_ESI)(%ecx), %esi
- movl (JB_EDI)(%ecx), %edi
- movl (JB_EBP)(%ecx), %ebp
- movl (JB_SP)(%ecx), %esp
-
- /* Jump to saved PC. */
-
- jmp *%edx
- .size up_longjmp, . - up_longjmp
-
+# 1 "up_setjmp.S"
+# 1 "/home/Owner/projects/nuttx/arch/sim/src//"
+# 1 "<built-in>"
+# 1 "<command line>"
+# 1 "up_setjmp.S"
diff --git a/nuttx/arch/sim/src/up_tapdev.c b/nuttx/arch/sim/src/up_tapdev.c
index f742afeac..bf9d9db81 100644
--- a/nuttx/arch/sim/src/up_tapdev.c
+++ b/nuttx/arch/sim/src/up_tapdev.c
@@ -38,9 +38,7 @@
*
****************************************************************************/
-#ifndef linux
-# error "Sorry, this will only work with Linux"
-#endif
+#ifdef linux
/****************************************************************************
* Included Files
@@ -281,3 +279,6 @@ void tapdev_send(char *buf, unsigned int buflen)
}
}
+#endif /* linux */
+
+
diff --git a/nuttx/arch/sim/src/up_uipdriver.c b/nuttx/arch/sim/src/up_uipdriver.c
index 8783634b5..b49e772e0 100644
--- a/nuttx/arch/sim/src/up_uipdriver.c
+++ b/nuttx/arch/sim/src/up_uipdriver.c
@@ -38,6 +38,8 @@
*
****************************************************************************/
+#ifdef linux
+
/****************************************************************************
* Included Files
****************************************************************************/
@@ -202,3 +204,6 @@ int uipdriver_init(void)
(void)netdev_register(&g_sim_dev);
return OK;
}
+
+#endif /* linux */
+
diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h
index 2b7a96788..f39d10674 100644
--- a/nuttx/include/nuttx/compiler.h
+++ b/nuttx/include/nuttx/compiler.h
@@ -53,11 +53,18 @@
* excluded from the link.
*/
-# define CONFIG_HAVE_WEAKFUNCTIONS 1
-# define weak_alias(name, aliasname) \
- extern __typeof (name) aliasname __attribute__ ((weak, alias (#name)));
-# define weak_function __attribute__ ((weak))
-# define weak_const_function __attribute__ ((weak, __const__))
+# ifndef __CYGWIN__
+# define CONFIG_HAVE_WEAKFUNCTIONS 1
+# define weak_alias(name, aliasname) \
+ extern __typeof (name) aliasname __attribute__ ((weak, alias (#name)));
+# define weak_function __attribute__ ((weak))
+# define weak_const_function __attribute__ ((weak, __const__))
+# else
+# undef CONFIG_HAVE_WEAKFUNCTIONS
+# define weak_alias(name, aliasname)
+# define weak_function
+# define weak_const_function
+#endif
/* The noreturn attribute informs GCC that the function will
* not return.
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index 57e19ade7..dc5dbc75b 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -165,12 +165,14 @@ static void send_interrupt(struct uip_driver_s *dev, void *private)
{
/* Stop further callbacks */
- uip_udp_conn->private = NULL;
- uip_udp_conn->event = NULL;
+ conn = (struct uip_conn *)pstate->snd_sock->s_conn;
+ conn->data_private = NULL;
+ conn->data_event = NULL;
/* Report not connected */
pstate->snd_sent = -ENOTCONN;
+
/* Wake up the waiting thread */
sem_post(&pstate->snd_sem);
diff --git a/nuttx/net/socket.c b/nuttx/net/socket.c
index b35c8e866..5efc86df9 100644
--- a/nuttx/net/socket.c
+++ b/nuttx/net/socket.c
@@ -88,9 +88,7 @@
int socket(int domain, int type, int protocol)
{
-#ifdef CONFIG_NET_UDP
FAR struct socket *psock;
-#endif
int sockfd;
int err;
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index 677cf64db..49536fa41 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -372,7 +372,9 @@ void uip_init(void)
/* Initialize the UDP connection structures */
+#ifdef CONFIG_NET_UDP
uip_udpinit();
+#endif
/* IPv4 initialization. */
}
@@ -561,6 +563,7 @@ static void uip_add_rcv_nxt(uint16 n)
uip_conn->rcv_nxt[3] = uip_acc32[3];
}
+#ifdef CONFIG_NET_UDP
static void uip_udp_callback(struct uip_driver_s *dev)
{
/* Some sanity checking */
@@ -572,6 +575,7 @@ static void uip_udp_callback(struct uip_driver_s *dev)
uip_udp_conn->event(dev, uip_udp_conn->private);
}
}
+#endif
static void uip_tcp_callback(struct uip_driver_s *dev)
{