From 5dc79030987a04233b672933793c1d0182854160 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 2 Nov 2007 23:05:53 +0000 Subject: Changes for clean compile of DM90x0 driver on Neuros OSD git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@365 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/irq.h | 1 + nuttx/arch/arm/src/c5471/Make.defs | 2 +- nuttx/arch/arm/src/c5471/c5471_serial.c | 9 +- nuttx/arch/arm/src/common/up_assert.c | 8 +- nuttx/arch/arm/src/common/up_delay.c | 100 ---------------------- nuttx/arch/arm/src/common/up_internal.h | 3 +- nuttx/arch/arm/src/common/up_mdelay.c | 90 ++++++++++++++++++++ nuttx/arch/arm/src/common/up_udelay.c | 132 +++++++++++++++++++++++++++++ nuttx/arch/arm/src/dm320/Make.defs | 2 +- nuttx/arch/arm/src/dm320/dm320_gio.h | 4 +- nuttx/arch/arm/src/lpc214x/Make.defs | 4 +- nuttx/configs/ntosd-dm320/src/up_network.c | 7 +- nuttx/drivers/net/dm90x0.c | 37 ++++++-- nuttx/net/net-arptimer.c | 1 + 14 files changed, 278 insertions(+), 122 deletions(-) delete mode 100644 nuttx/arch/arm/src/common/up_delay.c create mode 100644 nuttx/arch/arm/src/common/up_mdelay.c create mode 100644 nuttx/arch/arm/src/common/up_udelay.c (limited to 'nuttx') diff --git a/nuttx/arch/arm/include/irq.h b/nuttx/arch/arm/include/irq.h index c838ad402..a13e04cd1 100644 --- a/nuttx/arch/arm/include/irq.h +++ b/nuttx/arch/arm/include/irq.h @@ -44,6 +44,7 @@ * Included Files ************************************************************/ +#include #include /************************************************************ diff --git a/nuttx/arch/arm/src/c5471/Make.defs b/nuttx/arch/arm/src/c5471/Make.defs index ea04d6b81..540edc053 100644 --- a/nuttx/arch/arm/src/c5471/Make.defs +++ b/nuttx/arch/arm/src/c5471/Make.defs @@ -37,7 +37,7 @@ HEAD_ASRC = up_nommuhead.S CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_dataabort.c up_delay.c up_doirq.c \ + up_createstack.c up_dataabort.c up_mdelay.c up_udealy.c up_doirq.c \ up_exit.c up_idle.c up_initialize.c up_initialstate.c \ up_interruptcontext.c up_prefetchabort.c up_releasepending.c \ up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \ diff --git a/nuttx/arch/arm/src/c5471/c5471_serial.c b/nuttx/arch/arm/src/c5471/c5471_serial.c index 13197816b..ceeba8a36 100644 --- a/nuttx/arch/arm/src/c5471/c5471_serial.c +++ b/nuttx/arch/arm/src/c5471/c5471_serial.c @@ -1,5 +1,5 @@ /************************************************************ - * c5471/c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471c5471_serial.c + * c5471/c5471_serial.c * * Copyright (C) 2007 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -38,16 +38,19 @@ ************************************************************/ #include + #include #include #include #include #include #include + #include #include #include #include + #include "up_arch.h" #include "os_internal.h" #include "up_internal.h" @@ -381,9 +384,9 @@ static int up_setup(struct uart_dev_s *dev) /* Both the IrDA and MODEM UARTs support RESET and UART mode. */ up_serialout(priv, UART_MDR_OFFS, MDR_RESET_MODE); - up_delay(5); + up_mdelay(5); up_serialout(priv, UART_MDR_OFFS, MDR_UART_MODE); - up_delay(5); + up_mdelay(5); priv->regs.ier = up_inserial(priv, UART_IER_OFFS); priv->regs.lcr = up_inserial(priv, UART_LCR_OFFS); diff --git a/nuttx/arch/arm/src/common/up_assert.c b/nuttx/arch/arm/src/common/up_assert.c index 5c032c2f0..3c8c859e0 100644 --- a/nuttx/arch/arm/src/common/up_assert.c +++ b/nuttx/arch/arm/src/common/up_assert.c @@ -38,11 +38,15 @@ ************************************************************/ #include + #include #include #include #include + #include +#include + #include "up_arch.h" #include "os_internal.h" #include "up_internal.h" @@ -163,9 +167,9 @@ static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */ { #ifdef CONFIG_ARCH_LEDS up_ledon(LED_PANIC); - up_delay(250); + up_mdelay(250); up_ledoff(LED_PANIC); - up_delay(250); + up_mdelay(250); #endif } } diff --git a/nuttx/arch/arm/src/common/up_delay.c b/nuttx/arch/arm/src/common/up_delay.c deleted file mode 100644 index 19e98484a..000000000 --- a/nuttx/arch/arm/src/common/up_delay.c +++ /dev/null @@ -1,100 +0,0 @@ -/************************************************************ - * common/up_delay.c - * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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. - * - ************************************************************/ - -/************************************************************ - * Included Files - ************************************************************/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "up_arch.h" -#include "os_internal.h" -#include "up_internal.h" - -/************************************************************ - * Definitions - ************************************************************/ - -/************************************************************ - * Private Types - ************************************************************/ - -/************************************************************ - * Private Function Prototypes - ************************************************************/ - -/************************************************************ - * Private Variables - ************************************************************/ - -/************************************************************ - * Private Functions - ************************************************************/ - - -/************************************************************ - * Public Funtions - ************************************************************/ - -/************************************************************ - * Name: up_delay - * - * Description: - * Delay inline for the requested number of milliseconds. - * NOT multi-tasking friendly. - * - ************************************************************/ - -void up_delay(int milliseconds) -{ - volatile int i; - volatile int j; - - for (i = 0; i < milliseconds; i++) - { - for (j = 0; j < CONFIG_BOARD_LOOPSPERMSEC; j++) - { - } - } -} diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h index f75995b00..2d789a802 100644 --- a/nuttx/arch/arm/src/common/up_internal.h +++ b/nuttx/arch/arm/src/common/up_internal.h @@ -100,7 +100,6 @@ extern uint32 g_heapbase; extern void up_boot(void); extern void up_copystate(uint32 *dest, uint32 *src); extern void up_dataabort(uint32 *regs); -extern void up_delay(int milliseconds); extern void up_decodeirq(uint32 *regs); extern void up_doirq(int irq, uint32 *regs); extern void up_fullcontextrestore(uint32 *regs) __attribute__ ((noreturn)); @@ -160,7 +159,7 @@ extern void up_ledoff(int led); /* Defined in board/up_network.c */ #ifdef CONFIG_NET -extern up_netinitialize(void); +extern void up_netinitialize(void); #else # define up_netinitialize() #endif diff --git a/nuttx/arch/arm/src/common/up_mdelay.c b/nuttx/arch/arm/src/common/up_mdelay.c new file mode 100644 index 000000000..5a91a17d7 --- /dev/null +++ b/nuttx/arch/arm/src/common/up_mdelay.c @@ -0,0 +1,90 @@ +/**************************************************************************** + * common/up_mdelay.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_mdelay + * + * Description: + * Delay inline for the requested number of milliseconds. + * *** NOT multi-tasking friendly *** + * + * ASSUMPTIONS: + * The setting CONFIG_BOARD_LOOPSPERMSEC has been calibrated + * + ****************************************************************************/ + +void up_mdelay(unsigned int milliseconds) +{ + volatile int i; + volatile int j; + + for (i = 0; i < milliseconds; i++) + { + for (j = 0; j < CONFIG_BOARD_LOOPSPERMSEC; j++) + { + } + } +} diff --git a/nuttx/arch/arm/src/common/up_udelay.c b/nuttx/arch/arm/src/common/up_udelay.c new file mode 100644 index 000000000..f7d10e459 --- /dev/null +++ b/nuttx/arch/arm/src/common/up_udelay.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * common/up_udelay.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define CONFIG_BOARD_LOOPSPERUSEC ((CONFIG_BOARD_LOOPSPERMSEC+500)/1000) +#define CONFIG_BOARD_LOOPSPER10USEC ((CONFIG_BOARD_LOOPSPERMSEC+50)/100) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_udelay + * + * Description: + * Delay inline for the requested number of microseconds. NOTE: Because + * of all of the setup, several microseconds will be lost before the actual + * timing looop begins. Thus, the delay will always be a few microseconds + * longer than requested. + * + * *** NOT multi-tasking friendly *** + * + * ASSUMPTIONS: + * The setting CONFIG_BOARD_LOOPSPERMSEC has been calibrated + * + ****************************************************************************/ + +void up_udelay(unsigned int microseconds) +{ + volatile int i; + volatile int j; + register uint32 loops; + + /* The value of microseconds should be less than 1000. If not, then we + * will perform millescond delays until it is. + */ + + while (microseconds > 1000) + { + for (j = 0; j < CONFIG_BOARD_LOOPSPERMSEC; j++) + { + } + microseconds -= 1000; + } + + /* The numerator of the 'loops' below will overflow if CONFIG_BOARD_LOOPSPERMSEC + * is larger than (4*1024*1024*1024 - 500)/999 = 4,299,266.06 + */ + +#if CONFIG_BOARD_LOOPSPERMSEC >= 4299266 + while (microseconds > 500) + { + for (j = 0; j < ((CONFIG_BOARD_LOOPSPERMSEC+1)/2); j++) + { + } + microseconds -= 500; + } +#endif + + /* The overflow could still occur if CONFIG_BOARD_LOOPSPERMSEC is larger than + * (4*1024*1024*1024 - 500)/499 = 8,607,147.89 + */ + +#if CONFIG_BOARD_LOOPSPERMSEC >= 8607147 +# warning "Overflow in loops calculation is possible" +#endif + + /* Caculate the number of loops need to produce the required usec delay */ + + loops = (CONFIG_BOARD_LOOPSPERMSEC * microseconds + 500) / 1000; + for (j = 0; j < loops; j++) + { + } +} diff --git a/nuttx/arch/arm/src/dm320/Make.defs b/nuttx/arch/arm/src/dm320/Make.defs index 0c54c02a9..09a86be28 100644 --- a/nuttx/arch/arm/src/dm320/Make.defs +++ b/nuttx/arch/arm/src/dm320/Make.defs @@ -38,7 +38,7 @@ HEAD_ASRC = up_head.S CMN_ASRCS = up_cache.S up_fullcontextrestore.S up_saveusercontext.S \ up_vectors.S up_vectortab.S CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \ - up_dataabort.c up_delay.c up_exit.c up_idle.c \ + up_dataabort.c up_mdelay.c up_udelay.c up_exit.c up_idle.c \ up_initialize.c up_initialstate.c up_interruptcontext.c \ up_prefetchabort.c up_releasepending.c up_releasestack.c \ up_reprioritizertr.c up_schedulesigaction.c \ diff --git a/nuttx/arch/arm/src/dm320/dm320_gio.h b/nuttx/arch/arm/src/dm320/dm320_gio.h index 9b9a206f3..642c68bc9 100644 --- a/nuttx/arch/arm/src/dm320/dm320_gio.h +++ b/nuttx/arch/arm/src/dm320/dm320_gio.h @@ -90,7 +90,7 @@ if ((pin) < 16) { _reg = (reg0); _pin = (pin); } \ else if ((pin) < 32) { _reg = (reg1); _pin = ((pin) - 16); } \ else { _reg = (reg2); _pin = ((pin) - 32); } \ - putreg16((getreg16(_reg) | (1 << _pin)), _reg)); \ + putreg16((getreg16(_reg) | (1 << _pin)), _reg); \ } while (0) #define _GIO_CLEAR_REG(pin, reg0, reg1, reg2) \ @@ -99,7 +99,7 @@ if ((pin) < 16) { _reg = (reg0); _pin = (pin); } \ else if ((pin) < 32) { _reg = (reg1); _pin = ((pin) - 16); } \ else { _reg = (reg2); _pin = ((pin) - 32); } \ - putreg16((getreg16(_reg) & ~(1 << _pin)), _reg)); \ + putreg16((getreg16(_reg) & ~(1 << _pin)), _reg); \ } while (0) /* Select GIO input or output */ diff --git a/nuttx/arch/arm/src/lpc214x/Make.defs b/nuttx/arch/arm/src/lpc214x/Make.defs index 1ff1ccd8d..1211e3c12 100644 --- a/nuttx/arch/arm/src/lpc214x/Make.defs +++ b/nuttx/arch/arm/src/lpc214x/Make.defs @@ -37,8 +37,8 @@ HEAD_ASRC = lpc214x_head.S CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_vectors.S CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_dataabort.c up_delay.c up_exit.c \ - up_idle.c up_initialize.c up_initialstate.c \ + up_createstack.c up_dataabort.c up_mdelay.c up_udelay.c \ + up_exit.c up_idle.c up_initialize.c up_initialstate.c \ up_interruptcontext.c up_prefetchabort.c up_releasepending.c \ up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \ up_sigdeliver.c up_syscall.c up_unblocktask.c \ diff --git a/nuttx/configs/ntosd-dm320/src/up_network.c b/nuttx/configs/ntosd-dm320/src/up_network.c index 5ba9fd3aa..78234f98f 100644 --- a/nuttx/configs/ntosd-dm320/src/up_network.c +++ b/nuttx/configs/ntosd-dm320/src/up_network.c @@ -41,10 +41,13 @@ #if defined(CONFIG_NET) && defined(CONFIG_NET_DM90x0) #include -#include +#include +#include "up_arch.h" #include "up_internal.h" -#include "chip/dm320_gio.h" + +#include "dm320_memorymap.h" +#include "dm320_gio.h" extern void dm9x_initialize(void); diff --git a/nuttx/drivers/net/dm90x0.c b/nuttx/drivers/net/dm90x0.c index 5a8675bee..878664481 100644 --- a/nuttx/drivers/net/dm90x0.c +++ b/nuttx/drivers/net/dm90x0.c @@ -46,12 +46,15 @@ /* Force debug on for this file */ -#undef CONFIG_DEBUG +#undef CONFIG_DEBUG #define CONFIG_DEBUG 1 -#undef CONFIG_DEBUG_VERBOSE +#undef CONFIG_DEBUG_VERBOSE #define CONFIG_DEBUG_VERBOSE 1 -/* Only one hardware interface supported */ +/* Only one hardware interface supported at present (althought there are + * hooks throughout the design to that extending the support to multiple + * interfaces should not be that difficult) + */ #undef CONFIG_DM9X_NINTERFACES #define CONFIG_DM9X_NINTERFACES 1 @@ -830,6 +833,15 @@ static int dm9x_uiptxpoll(struct dm9x_driver_s *dm9x) { uip_arp_out(&dm9x->dev); dm9x_transmit(dm9x); + + /* Check if there is room in the DM90x0 to hold another packet. In 100M mode, + * that can be 2 packets, otherwise it is a single packet. + */ + + if (dm9x->ntxpending > 1 || !dm9x->b100M) + { + return; + } } } @@ -847,6 +859,15 @@ static int dm9x_uiptxpoll(struct dm9x_driver_s *dm9x) { uip_arp_out(&dm9x->dev); dm9x_transmit(dm9x); + + /* Check if there is room in the DM90x0 to hold another packet. In 100M mode, + * that can be 2 packets, otherwise it is a single packet. + */ + + if (dm9x->ntxpending > 1 || !dm9x->b100M) + { + return; + } } } #endif /* CONFIG_NET_UDP */ @@ -1118,7 +1139,7 @@ static int dm9x_interrupt(int irq, FAR void *context) for (i = 0; i < 200; i++) { - up_udelay(1000); + up_mdelay(1); } /* Set the new network speed */ @@ -1133,7 +1154,7 @@ static int dm9x_interrupt(int irq, FAR void *context) } break; } - up_udelay(1000); + up_mdelay(1); } dbg("delay: %d mS speed: %s\n", i, dm9x->b100M ? "100M" : "10M"); } @@ -1255,7 +1276,9 @@ static void dm9x_polltimer(int argc, uint32 arg, ...) putreg(DM9X_IMR, DM9X_IMRENABLE); } - /* Check if there is room in the TX FIFO to hold another packet */ + /* Check if there is room in the DM90x0 to hold another packet. In 100M mode, + * that can be 2 packets, otherwise it is a single packet. + */ if (dm9x->ntxpending < 1 || (dm9x->b100M && dm9x->ntxpending < 2)) { @@ -1561,7 +1584,7 @@ static void dm9x_reset(struct dm9x_driver_s *dm9x) } break; } - up_udelay(1000); + up_mdelay(1); } /* Restore previous register address */ diff --git a/nuttx/net/net-arptimer.c b/nuttx/net/net-arptimer.c index 69d8aebb0..a83406905 100644 --- a/nuttx/net/net-arptimer.c +++ b/nuttx/net/net-arptimer.c @@ -42,6 +42,7 @@ #include #include +#include #include -- cgit v1.2.3