From a95f177d20c45f908b62d35c0d58a4448713e628 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 28 Jan 2008 14:59:21 +0000 Subject: Z16F compile/link with all OS features enabled git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@574 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/TODO | 17 ++++++-- nuttx/arch/z16/include/z16f/irq.h | 2 +- nuttx/arch/z16/src/common/up_sigdeliver.c | 4 +- nuttx/arch/z16/src/z16f/z16f_head.S | 11 +++++ nuttx/arch/z16/src/z16f/z16f_lowuart.S | 1 - nuttx/arch/z16/src/z16f/z16f_serial.c | 45 +++++++++---------- nuttx/configs/sim/defconfig | 17 ++++---- nuttx/configs/z16f2800100zcog/include/board.h | 1 + nuttx/configs/z16f2800100zcog/ostest/defconfig | 60 ++++++++++++++------------ nuttx/examples/ostest/mqueue.c | 14 +++--- nuttx/examples/ostest/timedmqueue.c | 13 +++--- nuttx/include/nuttx/arch.h | 2 +- nuttx/sched/env_getenv.c | 4 +- nuttx/sched/env_getenvironptr.c | 20 ++++++++- nuttx/sched/timer_getoverrun.c | 9 ++-- 15 files changed, 136 insertions(+), 84 deletions(-) (limited to 'nuttx') diff --git a/nuttx/TODO b/nuttx/TODO index f8fd352fe..6e5b04527 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -7,7 +7,7 @@ NuttX TODO List (Last updated January 6, 2008) (1) Signals (sched/, arch/) (1) pthreads (sched/) (1) C++ Support - (10) Network (net/, netutils/) + (11) Network (net/, netutils/) (2) USB (drivers/usbdev) (3) Libraries (lib/) (2) File system (fs/, drivers/) @@ -21,7 +21,7 @@ NuttX TODO List (Last updated January 6, 2008) (2) ARM/LPC214x (arch/arm/src/lpc214x/) (4) pjrc-8052 / MCS51 (arch/pjrc-8051/) (2) z80 (arch/z80/) - (1) z16 (arch/z16/) + (2) z16 (arch/z16/) o Task/Scheduler (sched/) ^^^^^^^^^^^^^^^^^^^^^^^ @@ -361,4 +361,15 @@ o z16 (arch/z16) Description: ZDS-II Librarian complains that the source for the .obj file is not in the library. Status: Open - Priority: Low, thought to be cosmetic. + Priority: Low, thought to be cosmetic. I think this is a consequence of + replacing vs. inserting the library. + + Description: When printf is used, there are warnings like: + + WARNING (255) Missing declaration of (s)printf helper function, variable, or field + Declaration of __print_out is missing + + Need to suppress built-in printf logic to use NuttX printf logic. + Status: Open + Priority: Undetermined + diff --git a/nuttx/arch/z16/include/z16f/irq.h b/nuttx/arch/z16/include/z16f/irq.h index 7434b1f25..3e4ae472c 100644 --- a/nuttx/arch/z16/include/z16f/irq.h +++ b/nuttx/arch/z16/include/z16f/irq.h @@ -180,7 +180,7 @@ struct xcptcontext */ #ifndef CONFIG_DISABLE_SIGNALS - void *sigdeliver; /* Actual type is sig_deliver_t */ + CODE void *sigdeliver; /* Actual type is sig_deliver_t */ /* The following retains that state during signal execution */ diff --git a/nuttx/arch/z16/src/common/up_sigdeliver.c b/nuttx/arch/z16/src/common/up_sigdeliver.c index 59b40715d..ce94d1a40 100644 --- a/nuttx/arch/z16/src/common/up_sigdeliver.c +++ b/nuttx/arch/z16/src/common/up_sigdeliver.c @@ -113,12 +113,12 @@ void up_sigdeliver(void) * signals. */ - sigdeliver = rtcb->xcp.sigdeliver; + sigdeliver = (sig_deliver_t)rtcb->xcp.sigdeliver; rtcb->xcp.sigdeliver = NULL; /* Then restore the task interrupt state. */ - if ((reg[REG_FLAGS] & Z16F_CNTRL_FLAGS_IRQE) != 0) + if ((regs[REG_FLAGS] & Z16F_CNTRL_FLAGS_IRQE) != 0) { EI(); } diff --git a/nuttx/arch/z16/src/z16f/z16f_head.S b/nuttx/arch/z16/src/z16f/z16f_head.S index fc480822a..7e0682e76 100755 --- a/nuttx/arch/z16/src/z16f/z16f_head.S +++ b/nuttx/arch/z16/src/z16f/z16f_head.S @@ -50,8 +50,14 @@ #ifdef CONFIG_ARCH_LEDS xref _up_ledinit:EROM #endif +#if defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0 + xref _up_earlyserialinit:EROM +#endif #if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC) xref _z16f_lowuartinit:EROM +#endif +#if defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0 + xref up_earlyserialinit:EROM #endif xref _os_start:EROM xref _up_doirq:EROM @@ -207,6 +213,11 @@ _z16f_reset8: call _z16f_lowinit /* Perform low-level hardware initialization */ +#if defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0 + /* Perform early serial initialization */ + + call _up_earlyserialinit +#endif /* Start NuttX */ call _os_start /* Start the operating system */ diff --git a/nuttx/arch/z16/src/z16f/z16f_lowuart.S b/nuttx/arch/z16/src/z16f/z16f_lowuart.S index b39232122..bea5f25fc 100755 --- a/nuttx/arch/z16/src/z16f/z16f_lowuart.S +++ b/nuttx/arch/z16/src/z16f/z16f_lowuart.S @@ -168,7 +168,6 @@ _up_lowputc: * *************************************************************************/ -#ifdef CONFIG_ARCH_LOWPUTC _z16f_xmitc: _z16f_xmitc1: ld r0, Z16F_UARTSTAT0_TDRE /* TDRE=Transmitter Data Register Empty */ diff --git a/nuttx/arch/z16/src/z16f/z16f_serial.c b/nuttx/arch/z16/src/z16f/z16f_serial.c index 38d7492af..fb92919b1 100644 --- a/nuttx/arch/z16/src/z16f/z16f_serial.c +++ b/nuttx/arch/z16/src/z16f/z16f_serial.c @@ -158,7 +158,7 @@ static uart_dev_t g_uart0port = #endif { 0 }, /* closesem */ { 0 }, /* xmitsem */ - { 0 ], /* recvsem */ + { 0 }, /* recvsem */ { { 0 }, /* xmit.sem */ 0, /* xmit.head */ @@ -203,7 +203,7 @@ static uart_dev_t g_uart1port = #endif { 0 }, /* closesem */ { 0 }, /* xmitsem */ - { 0 ], /* recvsem */ + { 0 }, /* recvsem */ { { 0 }, /* xmit.sem */ 0, /* xmit.head */ @@ -246,7 +246,7 @@ static ubyte z16f_disableuartirq(struct uart_dev_s *dev) { struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv; irqstate_t flags = irqsave(); - ubyte state = priv->rxdisabed ? 0 : 1 | priv->txdisabled ? 0 : 2; + ubyte state = priv->rxenabled ? 1 : 0 | priv->txenabled ? 2 : 0; z16f_txint(dev, FALSE); z16f_rxint(dev, FALSE); @@ -268,20 +268,19 @@ static void z16f_restoreuartirq(struct uart_dev_s *dev, ubyte state) z16f_rxint(dev, (state & 1) ? TRUE : FALSE); irqrestore(flags); - return state; } /**************************************************************************** * Name: z16f_waittx ****************************************************************************/ -static void z16f_waittx(struct z16f_uart_s *priv, void (*status)(struct z16f_uart_s *)) +static void z16f_waittx(struct uart_dev_s *dev, boolean (*status)(struct uart_dev_s *)) { int tmp; for (tmp = 1000 ; tmp > 0 ; tmp--) { - if (status(priv) != 0) + if (status(dev)) { break; } @@ -374,7 +373,7 @@ static void z16f_shutdown(struct uart_dev_s *dev) static int z16f_attach(struct uart_dev_s *dev) { - struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv; int ret; /* Attach the RX IRQ */ @@ -412,7 +411,7 @@ errout: static void z16f_detach(struct uart_dev_s *dev) { - struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv; up_disable_irq(priv->rxirq); up_disable_irq(priv->txirq); irq_detach(priv->rxirq); @@ -465,6 +464,7 @@ static int z16f_rxinterrupt(int irq, void *context) uart_recvchars(dev); } + return OK; } /**************************************************************************** @@ -506,6 +506,7 @@ static int z16f_txinterrupt(int irq, void *context) uart_xmitchars(dev); } + return OK; } /**************************************************************************** @@ -567,9 +568,8 @@ static void z16f_rxint(struct uart_dev_s *dev, boolean enable) { up_disable_irq(priv->rxirq); } -#endif - priv->rxenable = enable; + priv->rxenabled = enable; irqrestore(flags); } @@ -625,7 +625,7 @@ static void z16f_txint(struct uart_dev_s *dev, boolean enable) up_disable_irq(priv->txirq); } - priv->txenable = enable; + priv->txenabled = enable; irqrestore(flags); } @@ -673,15 +673,15 @@ static boolean z16f_txempty(struct uart_dev_s *dev) void up_earlyserialinit(void) { - (void)z16f_disableuartirq(TTYS0_DEV); - (void)z16f_disableuartirq(TTYS1_DEV); + (void)z16f_disableuartirq(&TTYS0_DEV); + (void)z16f_disableuartirq(&TTYS1_DEV); CONSOLE_DEV.isconsole = TRUE; z16f_setup(&CONSOLE_DEV); } /**************************************************************************** - * Name: z16f_serialinit + * Name: up_serialinit * * Description: * Register serial console and serial ports. This assumes @@ -689,7 +689,7 @@ void up_earlyserialinit(void) * ****************************************************************************/ -void z16f_serialinit(void) +void up_serialinit(void) { (void)uart_register("/dev/console", &CONSOLE_DEV); (void)uart_register("/dev/ttyS0", &TTYS0_DEV); @@ -722,21 +722,21 @@ int up_putc(int ch) { /* Add CR before LF */ - z16f_waittx(priv, z16f_txready); + z16f_waittx(&CONSOLE_DEV, z16f_txready); putreg8('\r', priv->uartbase + Z16F_UART_TXD); } /* Output the character */ - z16f_waittx(priv, z16f_txready); + z16f_waittx(&CONSOLE_DEV, z16f_txready); putreg8((ubyte)ch, priv->uartbase + Z16F_UART_TXD); /* Now wait for all queue TX data to drain before restoring interrupts. The * driver should receive one txdone interrupt which it may or may not ignore. */ - z16f_waittx(priv, z16f_txempty); - z16f_restoreuartirq(priv, state); + z16f_waittx(&CONSOLE_DEV, z16f_txempty); + z16f_restoreuartirq(&CONSOLE_DEV, state); return ch; } @@ -775,17 +775,18 @@ static void _up_putc(int ch) int up_putc(int ch) { - _up_putc(ch); - /* Check for LF */ if (ch == '\n') { - /* Add CR */ + /* Output CR before LF */ _up_putc('\r'); } + /* Output character */ + + _up_putc(ch); return ch; } diff --git a/nuttx/configs/sim/defconfig b/nuttx/configs/sim/defconfig index d7c2eb0fc..93d9d0459 100644 --- a/nuttx/configs/sim/defconfig +++ b/nuttx/configs/sim/defconfig @@ -1,7 +1,7 @@ -############################################################ -# defconfig +############################################################################ +# sim/defconfig # -# Copyright (C) 2007 Gregory Nutt. All rights reserved. +# Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ # 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 +# 3. Neither the name NuttX nor the names of its contributors may be # used to endorse or promote products derived from this software # without specific prior written permission. # @@ -31,15 +31,14 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # -############################################################ +############################################################################ # -# architecture selection +# Architecture selection # # CONFIG_ARCH - identifies the arch subdirectory and, hence, the # processor architecture. -# CONFIG_ARCH_name - for use in C code. This identifies the -# particular chip or SoC that the architecture is implemented -# in. +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_SIM). # CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, # the board that supports the particular chip or SoC. # CONFIG_ARCH_BOARD_name - for use in C code diff --git a/nuttx/configs/z16f2800100zcog/include/board.h b/nuttx/configs/z16f2800100zcog/include/board.h index 774ca92c1..c8d43eee3 100644 --- a/nuttx/configs/z16f2800100zcog/include/board.h +++ b/nuttx/configs/z16f2800100zcog/include/board.h @@ -61,6 +61,7 @@ #define LED_IDLE 4 #define LED_INIRQ 5 #define LED_ASSERTION 6 +#define LED_SIGNAL 6 #define LED_PANIC 7 /**************************************************************************** diff --git a/nuttx/configs/z16f2800100zcog/ostest/defconfig b/nuttx/configs/z16f2800100zcog/ostest/defconfig index 60c0cb788..92315d28d 100644 --- a/nuttx/configs/z16f2800100zcog/ostest/defconfig +++ b/nuttx/configs/z16f2800100zcog/ostest/defconfig @@ -1,5 +1,5 @@ ############################################################################ -# configs/z16f2800100zcog/defconfig +# configs/z16f2800100zcog/ostest/defconfig # # Copyright (C) 2008 Gregory Nutt. All rights reserved. # Author: Gregory Nutt @@ -37,10 +37,14 @@ # # CONFIG_ARCH - identifies the arch subdirectory and, hence, the # processor architecture. -# CONFIG_ARCH_Z16 - Set if processor is Z16 -# CONFIG_ARCH_CHIP - Identifies the specific chip -# CONFIG_ARCH_CHIP_Z16F - Set if this the Z16F -# CONFIG_ARCH_CHIP_Z16F2810 - Identifies chip variant +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_Z16). +# CONFIG_ARCH_CHIP - Identifies the specific chip or SoC that implements the +# architecture. +# CONFIG_ARCH_CHIP_chip - for use in C code. This identifies the +# particular chip or SoC that the architecture is implemented +# in (CONFIG_ARCH_CHIP_Z16F) +# CONFIG_ARCH_CHIP_Z16F2810 - Identifies z16f chip variant # CONFIG_ARCH_CHIP_Z16F2811 # CONFIG_ARCH_CHIP_Z16F3211 # CONFIG_ARCH_CHIP_Z16F6411 @@ -114,7 +118,7 @@ CONFIG_HAVE_LIBM=n # CONFIG_HAVE_LOWPUTC - architecture supports low-level, boot # time console output # CONFIG_HAVE_GETPUTC - architecture supports low-level, boot -# time console output +# time console input # CONFIG_TICKS_PER_MSEC - The default system timer is 100Hz # or TICKS_PER_MSEC=10. This setting may be defined to # inform NuttX that the processor hardware is providing @@ -138,16 +142,16 @@ CONFIG_EXAMPLE=ostest CONFIG_DEBUG=n CONFIG_DEBUG_VERBOSE=n CONFIG_MM_REGIONS=1 -CONFIG_ARCH_LOWPUTC=y +CONFIG_ARCH_LOWPUTC=n CONFIG_ARCH_LOWGETC=n CONFIG_RR_INTERVAL=0 CONFIG_SCHED_INSTRUMENTATION=n CONFIG_TASK_NAME_SIZE=0 -CONFIG_START_YEAR=2007 -CONFIG_START_MONTH=2 -CONFIG_START_DAY=21 +CONFIG_START_YEAR=2008 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=28 CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=n +CONFIG_DEV_CONSOLE=y # # The following can be used to disable categories of @@ -164,13 +168,13 @@ CONFIG_DEV_CONSOLE=n # o pthread_condtimedwait() depends on signals to wake # up waiting tasks. # -CONFIG_DISABLE_CLOCK=y -CONFIG_DISABLE_POSIX_TIMERS=y -CONFIG_DISABLE_PTHREAD=y -CONFIG_DISABLE_SIGNALS=y -CONFIG_DISABLE_MQUEUE=y -CONFIG_DISABLE_MOUNTPOINT=y -CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n # # Misc libc settings @@ -203,7 +207,7 @@ CONFIG_ARCH_KFREE=n # Sizes of configurable things (0 disables) # # CONFIG_MAX_TASKS - The maximum number of simultaneously -# actived tasks. This value must be a power of two. +# active tasks. This value must be a power of two. # CONFIG_MAX_TASK_ARGS - This controls the maximum number of # of parameters that a task may receive (i.e., maxmum value # of 'argc') @@ -234,19 +238,19 @@ CONFIG_ARCH_KFREE=n # timer structures to minimize dynamic allocations. Set to # zero for all dynamic allocations. # -CONFIG_MAX_TASKS=8 +CONFIG_MAX_TASKS=16 CONFIG_MAX_TASK_ARGS=4 -CONFIG_NPTHREAD_KEYS=0 -CONFIG_NFILE_DESCRIPTORS=0 -CONFIG_NFILE_STREAMS=0 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=0 -CONFIG_NUNGET_CHARS=0 -CONFIG_PREALLOC_MQ_MSGS=0 -CONFIG_MQ_MAXMSGSIZE=0 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 CONFIG_MAX_WDOGPARMS=2 CONFIG_PREALLOC_WDOGS=4 -CONFIG_PREALLOC_TIMERS=0 +CONFIG_PREALLOC_TIMERS=4 # # TCP/IP and UDP support via uIP diff --git a/nuttx/examples/ostest/mqueue.c b/nuttx/examples/ostest/mqueue.c index 99cf1e585..e15d4680c 100644 --- a/nuttx/examples/ostest/mqueue.c +++ b/nuttx/examples/ostest/mqueue.c @@ -1,7 +1,7 @@ /************************************************************************** * mqueue.c * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * 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 + * 3. Neither the name NuttX nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * @@ -56,10 +56,14 @@ **************************************************************************/ #define TEST_MESSAGE "This is a test and only a test" -#ifdef SDCC -#define TEST_MSGLEN (31) +#if defined(SDCC) || defined(__ZILOG__) + /* Cannot use strlen in array size */ + +# define TEST_MSGLEN (31) #else -#define TEST_MSGLEN (strlen(TEST_MESSAGE)+1) + /* Message lenght is the size of the message plus the null terminator */ + +# define TEST_MSGLEN (strlen(TEST_MESSAGE)+1) #endif #define TEST_SEND_NMSGS (10) diff --git a/nuttx/examples/ostest/timedmqueue.c b/nuttx/examples/ostest/timedmqueue.c index 2ef0dedea..3d68039d0 100644 --- a/nuttx/examples/ostest/timedmqueue.c +++ b/nuttx/examples/ostest/timedmqueue.c @@ -1,7 +1,7 @@ /************************************************************************** * mqueue.c * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * 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 + * 3. Neither the name NuttX nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * @@ -56,11 +56,14 @@ **************************************************************************/ #define TEST_MESSAGE "This is a test and only a test" +#if defined(SDCC) || defined(__ZILOG__) + /* Cannot use strlen in array size */ -#ifdef SDCC -#define TEST_MSGLEN (31) +# define TEST_MSGLEN (31) #else -#define TEST_MSGLEN (strlen(TEST_MESSAGE)+1) + /* Message lenght is the size of the message plus the null terminator */ + +# define TEST_MSGLEN (strlen(TEST_MESSAGE)+1) #endif #define TEST_SEND_NMSGS (10) diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h index f7fc6582e..aca7c299b 100644 --- a/nuttx/include/nuttx/arch.h +++ b/nuttx/include/nuttx/arch.h @@ -57,7 +57,7 @@ * Public Variables ****************************************************************************/ -typedef void (*sig_deliver_t)(FAR _TCB *tcb); +typedef CODE void (*sig_deliver_t)(FAR _TCB *tcb); /**************************************************************************** * Public Function Prototypes diff --git a/nuttx/sched/env_getenv.c b/nuttx/sched/env_getenv.c index 91e974845..be0a83d2e 100644 --- a/nuttx/sched/env_getenv.c +++ b/nuttx/sched/env_getenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * env_getenv.c * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * 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 + * 3. Neither the name NuttX nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * diff --git a/nuttx/sched/env_getenvironptr.c b/nuttx/sched/env_getenvironptr.c index 4c01250b4..ab7fe9816 100644 --- a/nuttx/sched/env_getenvironptr.c +++ b/nuttx/sched/env_getenvironptr.c @@ -1,7 +1,7 @@ /**************************************************************************** * env_getenvironptr.c * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * 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 + * 3. Neither the name NuttX nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * @@ -73,6 +73,20 @@ FAR char **get_environ_ptr( void ) { +#if 1 + + /* Type of internal representation of environment is incompatible with + * char ** return value. + */ + +#ifdef CONFIG_CPP_HAVE_WARNING +# warning "get_environ_ptr not Implemented" +#endif + + return NULL; + +#else + /* Return a reference to the thread-private environ in the TCB.*/ FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head; @@ -84,6 +98,8 @@ FAR char **get_environ_ptr( void ) { return NULL; } + +#endif } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/timer_getoverrun.c b/nuttx/sched/timer_getoverrun.c index 9b23136da..07095a13c 100644 --- a/nuttx/sched/timer_getoverrun.c +++ b/nuttx/sched/timer_getoverrun.c @@ -1,7 +1,7 @@ /******************************************************************************** * timer_getoverrun.c * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * 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 + * 3. Neither the name NuttX nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * @@ -102,7 +102,10 @@ int timer_getoverrun(timer_t timerid) { -#warning "Not Implemented" +#ifdef CONFIG_CPP_HAVE_WARNING +# warning "timer_getoverrun not Implemented" +#endif + *get_errno_ptr() = ENOSYS; return ERROR; } -- cgit v1.2.3