From 888306f7280390e610544289429660d444a637c0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 Jan 2013 18:39:53 +0000 Subject: Add psock_poll(); Fix some warnings reported by Lorenz Meier; lm4f logic from JP git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5557 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/lm/chip.h | 26 ++++++++++++++++++++++++-- 1 file changed, 24 insertions(+), 2 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/include/lm/chip.h b/nuttx/arch/arm/include/lm/chip.h index 6b49fe2ce..6214a50d0 100644 --- a/nuttx/arch/arm/include/lm/chip.h +++ b/nuttx/arch/arm/include/lm/chip.h @@ -3,6 +3,7 @@ * * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Author: Jose Pablo Carballo * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -50,6 +51,7 @@ #if defined(CONFIG_ARCH_CHIP_LM3S6918) # define LM_NTIMERS 4 /* Four general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # undef LM_ETHTS /* No timestamp register */ # define LM_NSSI 2 /* Two SSI modules */ @@ -59,8 +61,10 @@ # define LM_NPWM 0 /* No PWM generator modules */ # define LM_NQEI 0 /* No quadrature encoders */ # define LM_NPORTS 8 /* 8 Ports (GPIOA-H) 5-38 GPIOs */ +# define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S6432) # define LM_NTIMERS 3 /* Three general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # undef LM_ETHTS /* No timestamp register */ # define LM_NSSI 1 /* One SSI module */ @@ -70,8 +74,10 @@ # define LM_NPWM 1 /* One PWM generator module */ # define LM_NQEI 0 /* No quadrature encoders */ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ +# define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S6965) # define LM_NTIMERS 4 /* Four general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # undef LM_ETHTS /* No timestamp register */ # define LM_NSSI 1 /* One SSI module */ @@ -81,8 +87,10 @@ # define LM_NPWM 3 /* Three PWM generator modules */ # define LM_NQEI 2 /* Two quadrature encoders */ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ +# define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S9B96) # define LM_NTIMERS 4 /* Four general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # undef LM_ETHTS /* No timestamp register */ # define LM_NSSI 2 /* Two SSI modules */ @@ -93,8 +101,10 @@ # define LM_NPWM 4 /* Four PWM generator modules */ # define LM_NQEI 2 /* Two quadrature encoders */ # define LM_NPORTS 9 /* 9 Ports (GPIOA-H,J) 0-65 GPIOs */ +# define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S8962) -# define LM_NTIMERS 4 /* Four general purpose timers */ +# define LM_NTIMERS 6 /* Four general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # define LM_NSSI 1 /* One SSI module */ # define LM_NUARTS 3 /* Two UART modules */ @@ -103,7 +113,19 @@ # define LM_NPWM 3 /* Three PWM generator modules */ # define LM_NQEI 2 /* Two quadrature encoders */ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 5-42 GPIOs */ -# define LM_CANCONTROLLER 1 /* One CAN controller */ +# define LM_NCANCONTROLLER 1 /* One CAN controller */ +#elif defined(CONFIG_ARCH_CHIP_LM4F120) +# define LM_NTIMERS 6 /* Six general purpose timers */ +# define LM_NWIDETIMERS 6 /* Six general purpose wide timers */ +# define LM_NETHCONTROLLERS 0 /* No Ethernet controller */ +# define LM_NSSI 4 /* Four SSI module */ +# define LM_NUARTS 8 /* Eight UART modules */ +# define LM_NI2C 4 /* Four I2C modules */ +# define LM_NADC 2 /* Two ADC modules */ +# define LM_NPWM 0 /* No PWM generator modules */ +# define LM_NQEI 0 /* No quadrature encoders */ +# define LM_NPORTS 6 /* 6 Ports (GPIOA-F), 0-43 GPIOs */ +# define LM_NCANCONTROLLER 1 /* One CAN controller */ #else # error "Capabilities not specified for this Stellaris chip" #endif -- cgit v1.2.3 From 91504abf89988b25322cd04f416c44bfbfbc86c2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 Jan 2013 18:41:46 +0000 Subject: Add psock_poll(); Fix some warnings reported by Lorenz Meier; lm4f logic from JP git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5558 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/lm/chip.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/include/lm/chip.h b/nuttx/arch/arm/include/lm/chip.h index 6214a50d0..6761e029e 100644 --- a/nuttx/arch/arm/include/lm/chip.h +++ b/nuttx/arch/arm/include/lm/chip.h @@ -2,8 +2,8 @@ * arch/arm/include/lm/chip.h * * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * Author: Jose Pablo Carballo + * Authors: Gregory Nutt + * Jose Pablo Carballo * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions -- cgit v1.2.3 From 25e9b8d0846b68a18014c63146234193bfe539e8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 Jan 2013 19:19:38 +0000 Subject: Fix poll/select issue reported by Qiang git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5559 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +- nuttx/TODO | 19 +-- nuttx/arch/8051/src/up_reprioritizertr.c | 13 +- nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c | 13 +- nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h | 85 +++++++++++++ nuttx/arch/avr/src/avr/up_reprioritizertr.c | 13 +- nuttx/arch/avr/src/avr32/up_reprioritizertr.c | 13 +- nuttx/arch/hc/src/common/up_reprioritizertr.c | 2 +- nuttx/arch/mips/src/mips32/up_reprioritizertr.c | 13 +- nuttx/arch/sh/src/common/up_reprioritizertr.c | 13 +- nuttx/arch/sim/src/up_reprioritizertr.c | 6 +- nuttx/arch/x86/src/common/up_reprioritizertr.c | 2 +- nuttx/arch/z16/src/common/up_reprioritizertr.c | 13 +- nuttx/arch/z80/src/common/up_reprioritizertr.c | 13 +- nuttx/net/net_poll.c | 156 +++++++++++++++++------- 15 files changed, 279 insertions(+), 100 deletions(-) create mode 100644 nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h (limited to 'nuttx/arch') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ffd1b66ae..2eaa03b21 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4021,4 +4021,7 @@ * configs/olimex-lpc1766stk/nettest: Configuration converted to use the kconfig-frontends tools. * net/net_poll.c: Split net_poll() to create psock_poll() too. - + * net/net_poll.c: Fix poll/select issure reported by Qiang: + poll_interrupt() must cat call net_lostconnection() when a + loss of connection is reported. Otherwise, the system will + not know that the connection has been lost. diff --git a/nuttx/TODO b/nuttx/TODO index c302760ab..ed91515ba 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 23, 2013) +NuttX TODO List (Last updated January 24, 2013) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -12,7 +12,7 @@ nuttx/ (2) pthreads (sched/) (2) C++ Support (6) Binary loaders (binfmt/) - (17) Network (net/, drivers/net) + (16) Network (net/, drivers/net) (4) USB (drivers/usbdev, drivers/usbhost) (12) Libraries (libc/, ) (9) File system/Generic drivers (fs/, drivers/) @@ -667,21 +667,6 @@ o Network (net/, drivers/net) Status: Open Priority: Low... fix defconfig files as necessary. - Title: net_poll() DOES NOT HANDLE LOSS-OF-CONNECTION CORRECTLY - Description: When a loss of connection is detected by any logic waiting on the - networking events, the function net_lostconnection() must be called. - That function just sets some bits in the socket structure so that - it remembers that the connection is lost. - - That is currently done in recvfrom(), send(), and net_monitor.c. But - it is not done in the net_poll() logic; that logic correctly sets - the POLLHUP status, but it does not call net_lostconnection(). As a - result, if recv() is called after the poll() or select(), the system - will hang because the recv() does not know that the connection has - been lost. - Status: Open - Priority: High - o USB (drivers/usbdev, drivers/usbhost) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/arch/8051/src/up_reprioritizertr.c b/nuttx/arch/8051/src/up_reprioritizertr.c index 6d4a72487..0d1941f66 100644 --- a/nuttx/arch/8051/src/up_reprioritizertr.c +++ b/nuttx/arch/8051/src/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * up_reprioritizertr.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -90,9 +90,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c index f1c961b15..9a971f064 100644 --- a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c +++ b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/armv7-m/up_reprioritizertr.c * - * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h new file mode 100644 index 000000000..6963545fe --- /dev/null +++ b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h @@ -0,0 +1,85 @@ +/************************************************************************************ + * arch/arm/src/lm/chip/lm3s_memorymap.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Jose Pablo Carballo + * + * 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 + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H +#define __ARCH_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Memory map ***********************************************************************/ + +#if defined(CONFIG_ARCH_CHIP_LM4F120) +# define LM_FLASH_BASE 0x00000000 /* -0x0003ffff: On-chip FLASH */ + /* -0x00ffffff: Reserved */ +# define LM_ROM_BASE 0x01000000 /* -0x1fffffff: Reserved for ROM */ +# define LM_SRAM_BASE 0x20000000 /* -0x20007fff: Bit-banded on-chip SRAM */ + /* -0x21ffffff: Reserved */ +/* @TODO */ +#endif + +#else +# error "Memory map not specified for this LM4F chip" +#endif + +/* Peripheral base addresses ********************************************************/ + +#if defined(CONFIG_ARCH_CHIP_LM4F120) +/* @TODO */ +#else +# error "Peripheral base addresses not specified for this Stellaris chip" +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H */ diff --git a/nuttx/arch/avr/src/avr/up_reprioritizertr.c b/nuttx/arch/avr/src/avr/up_reprioritizertr.c index 14033a3bd..af329c13f 100644 --- a/nuttx/arch/avr/src/avr/up_reprioritizertr.c +++ b/nuttx/arch/avr/src/avr/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/avr/src/avr/up_reprioritizertr.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/avr/src/avr32/up_reprioritizertr.c b/nuttx/arch/avr/src/avr32/up_reprioritizertr.c index e1712fed0..0aad214e8 100644 --- a/nuttx/arch/avr/src/avr32/up_reprioritizertr.c +++ b/nuttx/arch/avr/src/avr32/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/avr/src/avr32/up_reprioritizertr.c * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/hc/src/common/up_reprioritizertr.c b/nuttx/arch/hc/src/common/up_reprioritizertr.c index ffd90bf1f..31c76a9f5 100644 --- a/nuttx/arch/hc/src/common/up_reprioritizertr.c +++ b/nuttx/arch/hc/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/hc/src/common/up_reprioritizertr.c * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/nuttx/arch/mips/src/mips32/up_reprioritizertr.c b/nuttx/arch/mips/src/mips32/up_reprioritizertr.c index 66ce687e0..2e5f41d68 100644 --- a/nuttx/arch/mips/src/mips32/up_reprioritizertr.c +++ b/nuttx/arch/mips/src/mips32/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/mips/src/mips32/up_reprioritizertr.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -91,9 +91,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/sh/src/common/up_reprioritizertr.c b/nuttx/arch/sh/src/common/up_reprioritizertr.c index 728cafdf3..99d350b29 100644 --- a/nuttx/arch/sh/src/common/up_reprioritizertr.c +++ b/nuttx/arch/sh/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/sh/src/common/up_reprioritizertr.c * - * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/sim/src/up_reprioritizertr.c b/nuttx/arch/sim/src/up_reprioritizertr.c index 913d8d5f5..15c1b26d5 100644 --- a/nuttx/arch/sim/src/up_reprioritizertr.c +++ b/nuttx/arch/sim/src/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * up_reprioritizertr.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -91,13 +91,13 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) if (tcb->task_state < FIRST_READY_TO_RUN_STATE || tcb->task_state > LAST_READY_TO_RUN_STATE -#if SCHED_PRIORITY_MIN > UINT8_MIN +#if SCHED_PRIORITY_MIN > 0 || priority < SCHED_PRIORITY_MIN #endif #if SCHED_PRIORITY_MAX < UINT8_MAX || priority > SCHED_PRIORITY_MAX #endif - ) + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/x86/src/common/up_reprioritizertr.c b/nuttx/arch/x86/src/common/up_reprioritizertr.c index ad8a748a8..53a0e4315 100644 --- a/nuttx/arch/x86/src/common/up_reprioritizertr.c +++ b/nuttx/arch/x86/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/arm/up_reprioritizertr.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/nuttx/arch/z16/src/common/up_reprioritizertr.c b/nuttx/arch/z16/src/common/up_reprioritizertr.c index 0363184cd..6e76d6ce1 100644 --- a/nuttx/arch/z16/src/common/up_reprioritizertr.c +++ b/nuttx/arch/z16/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_reprioritizertr.c * - * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -91,9 +91,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/z80/src/common/up_reprioritizertr.c b/nuttx/arch/z80/src/common/up_reprioritizertr.c index 84cd3e1e1..b8102c99f 100644 --- a/nuttx/arch/z80/src/common/up_reprioritizertr.c +++ b/nuttx/arch/z80/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/z80/src/common/up_reprioritizertr.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -92,9 +92,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c index 2e73bd73c..ea6f54a6b 100644 --- a/nuttx/net/net_poll.c +++ b/nuttx/net/net_poll.c @@ -1,7 +1,7 @@ /**************************************************************************** * net/net_poll.c * - * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -46,11 +46,13 @@ #include #include #include +#include #include +#include +#include #include #include -#include #include @@ -75,6 +77,14 @@ /**************************************************************************** * Private Types ****************************************************************************/ +/* This is an allocated container that holds the poll-related information */ + +struct net_poll_s +{ + FAR struct socket *psock; /* Needed to handle loss of connection */ + struct pollfd *fds; /* Needed to handle poll events */ + FAR struct uip_callback_s *cb; /* Needed to teardown the poll */ +}; /**************************************************************************** * Private Functions @@ -101,16 +111,18 @@ ****************************************************************************/ #ifdef HAVE_NETPOLL -static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn, +static uint16_t poll_interrupt(FAR struct uip_driver_s *dev, FAR void *conn, FAR void *pvpriv, uint16_t flags) { - FAR struct pollfd *fds = (FAR struct pollfd *)pvpriv; + FAR struct net_poll_s *info = (FAR struct net_poll_s *)pvpriv; nllvdbg("flags: %04x\n", flags); + DEBUGASSERT(info && info->psock && info->fds); + /* 'priv' might be null in some race conditions (?) */ - if (fds) + if (info->fds) { pollevent_t eventset = 0; @@ -118,24 +130,23 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn, if ((flags & (UIP_NEWDATA|UIP_BACKLOG)) != 0) { - eventset |= POLLIN & fds->events; + eventset |= POLLIN & info->fds->events; } /* A poll is a sign that we are free to send data. */ if ((flags & UIP_POLL) != 0) { - eventset |= (POLLOUT & fds->events); + eventset |= (POLLOUT & info->fds->events); } - /* Check for a loss of connection events. - * - * REVISIT: Need to call net_lostconnection() here, but don't have - * the psock instance. What should we do? - */ + /* Check for a loss of connection events. */ if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0) { + /* Make the the connection has been lost */ + + net_lostconnection(info->psock, flags); eventset |= (POLLERR | POLLHUP); } @@ -143,8 +154,8 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn, if (eventset) { - fds->revents |= eventset; - sem_post(fds->sem); + info->fds->revents |= eventset; + sem_post(info->fds->sem); } } @@ -169,9 +180,11 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn, ****************************************************************************/ #ifdef HAVE_NETPOLL -static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds) +static inline int net_pollsetup(FAR struct socket *psock, + FAR struct pollfd *fds) { FAR struct uip_conn *conn = psock->s_conn; + FAR struct net_poll_s *info; FAR struct uip_callback_s *cb; uip_lock_t flags; int ret; @@ -185,6 +198,14 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds) } #endif + /* Allocate a container to hold the poll information */ + + info = (FAR struct net_poll_s *)kmalloc(sizeof(struct net_poll_s)); + if (!info) + { + return -ENOMEM; + } + /* Some of the following must be atomic */ flags = uip_lock(); @@ -195,18 +216,29 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds) if (!cb) { ret = -EBUSY; - goto errout_with_irq; + goto errout_with_lock; } - /* Initialize the callback structure */ + /* Initialize the poll info container */ + + info->psock = psock; + info->fds = fds; + info->cb = cb; + + /* Initialize the callback structure. Save the reference to the info + * structure as callback private data so that it will be available during + * callback processing. + */ cb->flags = (UIP_NEWDATA|UIP_BACKLOG|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT); - cb->priv = (FAR void *)fds; + cb->priv = (FAR void *)info; cb->event = poll_interrupt; - /* Save the nps reference in the poll structure for use at teardown as well */ + /* Save the reference in the poll info structure as fds private as well + * for use durring poll teardown as well. + */ - fds->priv = (FAR void *)cb; + fds->priv = (FAR void *)info; #ifdef CONFIG_NET_TCPBACKLOG /* Check for read data or backlogged connection availability now */ @@ -240,7 +272,8 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds) uip_unlock(flags); return OK; -errout_with_irq: +errout_with_lock: + kfree(info); uip_unlock(flags); return ret; } @@ -261,10 +294,11 @@ errout_with_irq: ****************************************************************************/ #ifdef HAVE_NETPOLL -static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds) +static inline int net_pollteardown(FAR struct socket *psock, + FAR struct pollfd *fds) { FAR struct uip_conn *conn = psock->s_conn; - FAR struct uip_callback_s *cb; + FAR struct net_poll_s *info; uip_lock_t flags; /* Sanity check */ @@ -278,18 +312,23 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds) /* Recover the socket descriptor poll state info from the poll structure */ - cb = (FAR struct uip_callback_s *)fds->priv; - if (cb) + info = (FAR struct net_poll_s *)fds->priv; + DEBUGASSERT(info && info->fds && info->cb); + if (info) { /* Release the callback */ flags = uip_lock(); - uip_tcpcallbackfree(conn, cb); + uip_tcpcallbackfree(conn, info->cb); uip_unlock(flags); /* Release the poll/select data slot */ - fds->priv = NULL; + info->fds->priv = NULL; + + /* Then free the poll info container */ + + kfree(info); } return OK; @@ -308,7 +347,7 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds) * to this function. * * Input Parameters: - * fd - The socket descriptor of interest + * psock - An instance of the internal socket structure. * fds - The structure describing the events to be monitored, OR NULL if * this is a request to stop monitoring events. * setup - true: Setup up the poll; false: Teardown the poll @@ -318,26 +357,11 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds) * ****************************************************************************/ -#ifndef CONFIG_DISABLE_POLL -int net_poll(int sockfd, struct pollfd *fds, bool setup) +#if !defined(CONFIG_DISABLE_POLL) && defined(HAVE_NETPOLL) +int psock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup) { -#ifndef HAVE_NETPOLL - return -ENOSYS; -#else - FAR struct socket *psock; int ret; - /* Get the underlying socket structure and verify that the sockfd - * corresponds to valid, allocated socket - */ - - psock = sockfd_socket(sockfd); - if (!psock || psock->s_crefs <= 0) - { - ret = -EBADF; - goto errout; - } - #ifdef CONFIG_NET_UDP /* poll() not supported for UDP */ @@ -365,6 +389,48 @@ int net_poll(int sockfd, struct pollfd *fds, bool setup) errout: return ret; +} +#endif + +/**************************************************************************** + * Function: net_poll + * + * Description: + * The standard poll() operation redirects operations on socket descriptors + * to this function. + * + * Input Parameters: + * fd - The socket descriptor of interest + * fds - The structure describing the events to be monitored, OR NULL if + * this is a request to stop monitoring events. + * setup - true: Setup up the poll; false: Teardown the poll + * + * Returned Value: + * 0: Success; Negated errno on failure + * + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +int net_poll(int sockfd, struct pollfd *fds, bool setup) +{ +#ifndef HAVE_NETPOLL + return -ENOSYS; +#else + FAR struct socket *psock; + + /* Get the underlying socket structure and verify that the sockfd + * corresponds to valid, allocated socket + */ + + psock = sockfd_socket(sockfd); + if (!psock || psock->s_crefs <= 0) + { + return -EBADF; + } + + /* Then let psock_poll() do the heavy lifting */ + + return psock_poll(psock, fds, setup); #endif /* HAVE_NETPOLL */ } #endif /* !CONFIG_DISABLE_POLL */ -- cgit v1.2.3 From 5b6482a22bb8b656e3d70a6efc5ae2c77ed2a58b Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 20:17:29 +0000 Subject: Move file data from TCB to task group git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5567 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/TODO | 23 +---- nuttx/arch/arm/src/common/up_exit.c | 8 +- nuttx/arch/avr/src/common/up_exit.c | 8 +- nuttx/arch/hc/src/common/up_exit.c | 8 +- nuttx/arch/mips/src/common/up_exit.c | 8 +- nuttx/arch/sh/src/common/up_exit.c | 9 +- nuttx/arch/x86/src/common/up_exit.c | 6 +- nuttx/arch/z16/src/common/up_exit.c | 11 +- nuttx/arch/z80/src/common/up_exit.c | 9 +- nuttx/fs/fs_fdopen.c | 8 +- nuttx/fs/fs_files.c | 101 ++++--------------- nuttx/include/nuttx/fs/fs.h | 89 +++++++---------- nuttx/include/nuttx/sched.h | 42 +++++--- nuttx/sched/group_leave.c | 16 ++- nuttx/sched/sched_getfiles.c | 5 +- nuttx/sched/sched_releasefiles.c | 13 ++- nuttx/sched/sched_releasetcb.c | 4 - nuttx/sched/sched_setupidlefiles.c | 15 +-- nuttx/sched/sched_setuppthreadfiles.c | 8 -- nuttx/sched/sched_setuptaskfiles.c | 49 +++++---- nuttx/sched/task_exithook.c | 182 +++++++++++++++++++++------------- 22 files changed, 288 insertions(+), 336 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 858f82819..ae7105b89 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4034,3 +4034,5 @@ * sched/: Lots of file changed. Don't keep the parent task's task ID in the child task's TCB. Instead, keep the parent task group IN the child task's task group. + * fs/, sched/, include/nuttx/sched.h, and include/nutts/fs/fs.h: + Move file data from TCB to task group structure. diff --git a/nuttx/TODO b/nuttx/TODO index d6bd18d12..cb99f1bf7 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 24, 2013) +NuttX TODO List (Last updated January 26, 2013) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -6,7 +6,7 @@ standards, things that could be improved, and ideas for enhancements. nuttx/ - (11) Task/Scheduler (sched/) + (10) Task/Scheduler (sched/) (2) Memory Managment (mm/) (3) Signals (sched/, arch/) (2) pthreads (sched/) @@ -161,25 +161,6 @@ o Task/Scheduler (sched/) Status: Open Priority: Medium Low for now - Title: IMPROVED TASK CONTROL BLOCK STRUCTURE - Description: All task resources that are shared amongst threads have - their own "break-away", reference-counted structure. The - Task Control Block (TCB) of each thread holds a reference - to each breakaway structure (see include/nuttx/sched.h). - It would be more efficent to have one reference counted - structure that holds all of the shared resources. - - These are the current shared structures: - - Environment varaibles (struct environ_s) - - PIC data space and address environments (struct dspace_s) - - File descriptors (struct filelist) - - FILE streams (struct streamlist) - - Sockets (struct socketlist) - Status: Open - Priority: Low. This is an enhancement. It would slight reduce - memory usage but would also increase coupling. These - resources are nicely modular now. - Title: ISSUES WITH atexit() AND on_exit() Description: These functions execute with the following bad properties: diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c index 6f6d54f76..5b469fd03 100644 --- a/nuttx/arch/arm/src/common/up_exit.c +++ b/nuttx/arch/arm/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 201-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/avr/src/common/up_exit.c b/nuttx/arch/avr/src/common/up_exit.c index 0a8cc0d18..0813754a0 100644 --- a/nuttx/arch/avr/src/common/up_exit.c +++ b/nuttx/arch/avr/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/avr/src/common/up_exit.c * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/hc/src/common/up_exit.c b/nuttx/arch/hc/src/common/up_exit.c index 7cd16b438..5313a1172 100644 --- a/nuttx/arch/hc/src/common/up_exit.c +++ b/nuttx/arch/hc/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/hc/src/common/up_exit.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/mips/src/common/up_exit.c b/nuttx/arch/mips/src/common/up_exit.c index 876b486b6..5a7b68a99 100644 --- a/nuttx/arch/mips/src/common/up_exit.c +++ b/nuttx/arch/mips/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/mips/src/common/up_exit.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -87,12 +87,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/sh/src/common/up_exit.c b/nuttx/arch/sh/src/common/up_exit.c index 84a44a705..af270b335 100644 --- a/nuttx/arch/sh/src/common/up_exit.c +++ b/nuttx/arch/sh/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -81,16 +81,15 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #endif sdbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/x86/src/common/up_exit.c b/nuttx/arch/x86/src/common/up_exit.c index e3d27b0af..6a98c7dd0 100644 --- a/nuttx/arch/x86/src/common/up_exit.c +++ b/nuttx/arch/x86/src/common/up_exit.c @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/z16/src/common/up_exit.c b/nuttx/arch/z16/src/common/up_exit.c index 41f058347..ad0c55eed 100644 --- a/nuttx/arch/z16/src/common/up_exit.c +++ b/nuttx/arch/z16/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -81,17 +81,16 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) int i; #endif - dbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - lldbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { lldbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c index 85ddd841e..50289f52b 100644 --- a/nuttx/arch/z80/src/common/up_exit.c +++ b/nuttx/arch/z80/src/common/up_exit.c @@ -82,17 +82,16 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) int i; #endif - dbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - lldbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { lldbg(" fd=%d refcount=%d\n", diff --git a/nuttx/fs/fs_fdopen.c b/nuttx/fs/fs_fdopen.c index fd6aa88a8..629083c77 100644 --- a/nuttx/fs/fs_fdopen.c +++ b/nuttx/fs/fs_fdopen.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/fs_fdopen.c * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -68,9 +68,11 @@ static inline int fs_checkfd(FAR _TCB *tcb, int fd, int oflags) FAR struct filelist *flist; FAR struct inode *inode; - /* Get the file list from the TCB */ + DEBUGASSERT(tcb && tcb->group); - flist = tcb->filelist; + /* Get the file list from the task group */ + + flist = &tcb->group->tg_filelist; /* Get the inode associated with the file descriptor. This should * normally be the case if fd >= 0. But not in the case where the diff --git a/nuttx/fs/fs_files.c b/nuttx/fs/fs_files.c index 06addb1ef..c68ec7e73 100644 --- a/nuttx/fs/fs_files.c +++ b/nuttx/fs/fs_files.c @@ -155,56 +155,19 @@ void files_initialize(void) } /**************************************************************************** - * Name: files_alloclist + * Name: files_initlist * - * Description: Allocate a list of files for a new task + * Description: Initializes the list of files for a new task * ****************************************************************************/ -FAR struct filelist *files_alloclist(void) +void files_initlist(FAR struct filelist *list) { - FAR struct filelist *list; - list = (FAR struct filelist*)kzalloc(sizeof(struct filelist)); - if (list) - { - /* Start with a reference count of one */ - - list->fl_crefs = 1; - - /* Initialize the list access mutex */ + DEBUGASSERT(list); - (void)sem_init(&list->fl_sem, 0, 1); - } + /* Initialize the list access mutex */ - return list; -} - -/**************************************************************************** - * Name: files_addreflist - * - * Description: - * Increase the reference count on a file list - * - ****************************************************************************/ - -int files_addreflist(FAR struct filelist *list) -{ - if (list) - { - /* Increment the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - list->fl_crefs++; - irqrestore(flags); - } - - return OK; + (void)sem_init(&list->fl_sem, 0, 1); } /**************************************************************************** @@ -215,51 +178,25 @@ int files_addreflist(FAR struct filelist *list) * ****************************************************************************/ -int files_releaselist(FAR struct filelist *list) +void files_releaselist(FAR struct filelist *list) { - int crefs; - if (list) - { - /* Decrement the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - crefs = --(list->fl_crefs); - irqrestore(flags); - - /* If the count decrements to zero, then there is no reference - * to the structure and it should be deallocated. Since there - * are references, it would be an error if any task still held - * a reference to the list's semaphore. - */ - - if (crefs <= 0) - { - int i; + int i; - /* Close each file descriptor .. Normally, you would need - * take the list semaphore, but it is safe to ignore the - * semaphore in this context because there are no references - */ + DEBUGASSERT(list); - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) - { - (void)_files_close(&list->fl_files[i]); - } - - /* Destroy the semaphore and release the filelist */ + /* Close each file descriptor .. Normally, you would need take the list + * semaphore, but it is safe to ignore the semaphore in this context because + * there should not be any references in this context. + */ - (void)sem_destroy(&list->fl_sem); - sched_free(list); - } + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + { + (void)_files_close(&list->fl_files[i]); } - return OK; + /* Destroy the semaphore */ + + (void)sem_destroy(&list->fl_sem); } /**************************************************************************** diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index 327bf37ca..02855460c 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -240,7 +240,6 @@ struct file struct filelist { sem_t fl_sem; /* Manage access to the file list */ - int16_t fl_crefs; /* Reference count */ struct file fl_files[CONFIG_NFILE_DESCRIPTORS]; }; #endif @@ -318,7 +317,8 @@ typedef int (*foreach_mountpoint_t)(FAR const char *mountpoint, #undef EXTERN #if defined(__cplusplus) #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif @@ -333,7 +333,7 @@ extern "C" { * ****************************************************************************/ -EXTERN void weak_function fs_initialize(void); +void weak_function fs_initialize(void); /* fs_foreachmountpoint.c ***************************************************/ /**************************************************************************** @@ -357,7 +357,7 @@ EXTERN void weak_function fs_initialize(void); ****************************************************************************/ #ifndef CONFIG_DISABLE_MOUNTPOUNT -EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); +int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); #endif /* fs_registerdriver.c ******************************************************/ @@ -384,9 +384,8 @@ EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); * ****************************************************************************/ -EXTERN int register_driver(const char *path, - const struct file_operations *fops, - mode_t mode, void *priv); +int register_driver(FAR const char *path, FAR const struct file_operations *fops, + mode_t mode, FAR void *priv); /* fs_registerblockdriver.c *************************************************/ /**************************************************************************** @@ -412,9 +411,9 @@ EXTERN int register_driver(const char *path, * ****************************************************************************/ -EXTERN int register_blockdriver(const char *path, - const struct block_operations *bops, - mode_t mode, void *priv); +int register_blockdriver(FAR const char *path, + FAR const struct block_operations *bops, mode_t mode, + FAR void *priv); /* fs_unregisterdriver.c ****************************************************/ /**************************************************************************** @@ -425,7 +424,7 @@ EXTERN int register_blockdriver(const char *path, * ****************************************************************************/ -EXTERN int unregister_driver(const char *path); +int unregister_driver(const char *path); /* fs_unregisterblockdriver.c ***********************************************/ /**************************************************************************** @@ -436,7 +435,7 @@ EXTERN int unregister_driver(const char *path); * ****************************************************************************/ -EXTERN int unregister_blockdriver(const char *path); +int unregister_blockdriver(const char *path); /* fs_open.c ****************************************************************/ /**************************************************************************** @@ -447,30 +446,19 @@ EXTERN int unregister_blockdriver(const char *path); * ****************************************************************************/ -EXTERN int inode_checkflags(FAR struct inode *inode, int oflags); +int inode_checkflags(FAR struct inode *inode, int oflags); /* fs_files.c ***************************************************************/ /**************************************************************************** - * Name: files_alloclist - * - * Description: Allocate a list of files for a new task - * - ****************************************************************************/ - -#if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN FAR struct filelist *files_alloclist(void); -#endif - -/**************************************************************************** - * Name: files_addreflist + * Name: files_initlist * * Description: - * Increase the reference count on a file list + * Initializes the list of files for a new task * ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_addreflist(FAR struct filelist *list); +void files_initlist(FAR struct filelist *list); #endif /**************************************************************************** @@ -482,7 +470,7 @@ EXTERN int files_addreflist(FAR struct filelist *list); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_releaselist(FAR struct filelist *list); +void files_releaselist(FAR struct filelist *list); #endif /**************************************************************************** @@ -495,7 +483,7 @@ EXTERN int files_releaselist(FAR struct filelist *list); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2); +int files_dup(FAR struct file *filep1, FAR struct file *filep2); #endif /* fs_filedup.c *************************************************************/ @@ -515,7 +503,7 @@ EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int file_dup(int fd, int minfd); +int file_dup(int fd, int minfd); #endif /* fs_filedup2.c ************************************************************/ @@ -535,7 +523,7 @@ EXTERN int file_dup(int fd, int minfd); #if CONFIG_NFILE_DESCRIPTORS > 0 #if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 -EXTERN int file_dup2(int fd1, int fd2); +int file_dup2(int fd1, int fd2); #else # define file_dup2(fd1, fd2) dup2(fd1, fd2) #endif @@ -566,8 +554,8 @@ EXTERN int file_dup2(int fd1, int fd2); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int open_blockdriver(FAR const char *pathname, int mountflags, - FAR struct inode **ppinode); +int open_blockdriver(FAR const char *pathname, int mountflags, + FAR struct inode **ppinode); #endif /* fs_closeblockdriver.c ****************************************************/ @@ -589,7 +577,7 @@ EXTERN int open_blockdriver(FAR const char *pathname, int mountflags, ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int close_blockdriver(FAR struct inode *inode); +int close_blockdriver(FAR struct inode *inode); #endif /* fs_fdopen.c **************************************************************/ @@ -609,7 +597,7 @@ typedef struct _TCB _TCB; #define __TCB_DEFINED__ #endif -EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); +FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); #endif /* lib/stdio/lib_fflush.c **************************************************/ @@ -623,7 +611,7 @@ EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); ****************************************************************************/ #if CONFIG_NFILE_STREAMS > 0 -EXTERN int lib_flushall(FAR struct streamlist *list); +int lib_flushall(FAR struct streamlist *list); #endif /* drivers/dev_null.c *******************************************************/ @@ -635,7 +623,7 @@ EXTERN int lib_flushall(FAR struct streamlist *list); * ****************************************************************************/ -EXTERN void devnull_register(void); +void devnull_register(void); /* drivers/dev_zero.c *******************************************************/ /**************************************************************************** @@ -646,7 +634,7 @@ EXTERN void devnull_register(void); * ****************************************************************************/ -EXTERN void devzero_register(void); +void devzero_register(void); /* drivers/loop.c ***********************************************************/ /**************************************************************************** @@ -658,8 +646,8 @@ EXTERN void devzero_register(void); * ****************************************************************************/ -EXTERN int losetup(FAR const char *devname, FAR const char *filename, - uint16_t sectsize, off_t offset, bool readonly); +int losetup(FAR const char *devname, FAR const char *filename, + uint16_t sectsize, off_t offset, bool readonly); /**************************************************************************** * Name: loteardown @@ -669,7 +657,7 @@ EXTERN int losetup(FAR const char *devname, FAR const char *filename, * ****************************************************************************/ -EXTERN int loteardown(FAR const char *devname); +int loteardown(FAR const char *devname); /* drivers/bch/bchdev_register.c ********************************************/ /**************************************************************************** @@ -681,8 +669,8 @@ EXTERN int loteardown(FAR const char *devname); * ****************************************************************************/ -EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev, - bool readonly); +int bchdev_register(FAR const char *blkdev, FAR const char *chardev, + bool readonly); /* drivers/bch/bchdev_unregister.c ******************************************/ /**************************************************************************** @@ -694,7 +682,7 @@ EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev, * ****************************************************************************/ -EXTERN int bchdev_unregister(FAR const char *chardev); +int bchdev_unregister(FAR const char *chardev); /* Low level, direct access. NOTE: low-level access and character driver access * are incompatible. One and only one access method should be implemented. @@ -710,8 +698,7 @@ EXTERN int bchdev_unregister(FAR const char *chardev); * ****************************************************************************/ -EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly, - FAR void **handle); +int bchlib_setup(FAR const char *blkdev, bool readonly, FAR void **handle); /* drivers/bch/bchlib_teardown.c ********************************************/ /**************************************************************************** @@ -723,7 +710,7 @@ EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly, * ****************************************************************************/ -EXTERN int bchlib_teardown(FAR void *handle); +int bchlib_teardown(FAR void *handle); /* drivers/bch/bchlib_read.c ************************************************/ /**************************************************************************** @@ -735,8 +722,8 @@ EXTERN int bchlib_teardown(FAR void *handle); * ****************************************************************************/ -EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, - size_t len); +ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, + size_t len); /* drivers/bch/bchlib_write.c ***********************************************/ /**************************************************************************** @@ -748,8 +735,8 @@ EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, * ****************************************************************************/ -EXTERN ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, - size_t offset, size_t len); +ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, size_t offset, + size_t len); #undef EXTERN #if defined(__cplusplus) diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 8ebb7db4c..1580a80d3 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -52,6 +52,7 @@ #include #include +#include #include /******************************************************************************** @@ -63,14 +64,24 @@ #undef HAVE_TASK_GROUP #undef HAVE_GROUP_MEMBERS +/* We need a group an group members if we are supportint the parent/child + * relationship. + */ + #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) -# define HAVE_TASK_GROUP 1 -# define HAVE_GROUP_MEMBERS 1 -#endif +# define HAVE_TASK_GROUP 1 +# define HAVE_GROUP_MEMBERS 1 -#if !defined(CONFIG_DISABLE_ENVIRON) -# undef HAVE_TASK_GROUP -# define HAVE_TASK_GROUP 1 +/* We need a group (but not members) if any other resources are shared within + * a task group. + */ + +#else +# if !defined(CONFIG_DISABLE_ENVIRON) +# define HAVE_TASK_GROUP 1 +# elif CONFIG_NFILE_DESCRIPTORS > 0 +# define HAVE_TASK_GROUP 1 +# endif #endif /* In any event, we don't need group members if support for pthreads is disabled */ @@ -79,7 +90,7 @@ # undef HAVE_GROUP_MEMBERS #endif -/* Task Management Definitins ***************************************************/ +/* Task Management Definitions **************************************************/ /* This is the maximum number of times that a lock can be set */ @@ -282,16 +293,19 @@ struct task_group_s FAR char *tg_envp; /* Allocated environment strings */ #endif - /* PIC data space and address environments */ + /* PIC data space and address environments ************************************/ /* Not yet (see struct dspace_s) */ - /* File descriptors */ - /* Not yet (see struct filelist) */ + /* File descriptors ***********************************************************/ - /* FILE streams */ +#if CONFIG_NFILE_DESCRIPTORS > 0 + struct filelist tg_filelist; /* Maps file descriptor to file */ +#endif + + /* FILE streams ***************************************************************/ /* Not yet (see streamlist) */ - /* Sockets */ + /* Sockets ********************************************************************/ /* Not yet (see struct socketlist) */ }; #endif @@ -433,10 +447,6 @@ struct _TCB /* File system support ********************************************************/ -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct filelist *filelist; /* Maps file descriptor to file */ -#endif - #if CONFIG_NFILE_STREAMS > 0 FAR struct streamlist *streams; /* Holds C buffered I/O info */ #endif diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index add424185..f5dca1829 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -176,6 +176,13 @@ void group_leave(FAR _TCB *tcb) #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) group_removechildren(tcb->group); +#endif + /* Free all file-related resources now. We really need to close + * files as soon as possible while we still have a functioning task. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 + (void)sched_releasefiles(tcb); #endif /* Release all shared environment variables */ @@ -231,7 +238,14 @@ void group_leave(FAR _TCB *tcb) #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) group_removechildren(tcb->group); #endif - /* Release all shared environment variables */ + /* Free all file-related resources now. We really need to close + * files as soon as possible while we still have a functioning task. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 + (void)sched_releasefiles(tcb); +#endif + /* Release all shared environment variables */ #ifndef CONFIG_DISABLE_ENVIRON env_release(tcb); diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c index 256b4cb6b..eca4ba3ff 100644 --- a/nuttx/sched/sched_getfiles.c +++ b/nuttx/sched/sched_getfiles.c @@ -70,7 +70,10 @@ FAR struct filelist *sched_getfiles(void) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - return rtcb->filelist; + FAR struct task_group_s *group = rtcb->group; + + DEBUGASSERT(group); + return &group->tg_filelist; } #endif /* CONFIG_NFILE_DESCRIPTORS */ diff --git a/nuttx/sched/sched_releasefiles.c b/nuttx/sched/sched_releasefiles.c index a3ef71af4..4be92f4eb 100644 --- a/nuttx/sched/sched_releasefiles.c +++ b/nuttx/sched/sched_releasefiles.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_releasefiles.c * - * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -78,13 +78,12 @@ int sched_releasefiles(_TCB *tcb) if (tcb) { #if CONFIG_NFILE_DESCRIPTORS > 0 - /* Free the file descriptor list */ + FAR struct task_group_s *group = tcb->group; + DEBUGASSERT(group); - if (tcb->filelist) - { - files_releaselist(tcb->filelist); - tcb->filelist = NULL; - } + /* Free resources used by the file descriptor list */ + + files_releaselist(&group->tg_filelist); #if CONFIG_NFILE_STREAMS > 0 /* Free the stream list */ diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c index 00d4c2c0c..02f7170c2 100644 --- a/nuttx/sched/sched_releasetcb.c +++ b/nuttx/sched/sched_releasetcb.c @@ -163,10 +163,6 @@ int sched_releasetcb(FAR _TCB *tcb) } } - /* Release any allocated file structures */ - - ret = sched_releasefiles(tcb); - /* Release this thread's reference to the address environment */ #ifdef CONFIG_ADDRENV diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/sched_setupidlefiles.c index ae814e1a6..4bbd4d3b7 100644 --- a/nuttx/sched/sched_setupidlefiles.c +++ b/nuttx/sched/sched_setupidlefiles.c @@ -79,18 +79,21 @@ int sched_setupidlefiles(FAR _TCB *tcb) { +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct task_group_s *group = tcb->group; +#endif #if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) int fd; #endif - /* Allocate file descriptors for the TCB */ +#if CONFIG_NFILE_DESCRIPTORS > 0 + DEBUGASSERT(group); +#endif + + /* Initialize file descriptors for the TCB */ #if CONFIG_NFILE_DESCRIPTORS > 0 - tcb->filelist = files_alloclist(); - if (!tcb->filelist) - { - return -ENOMEM; - } + files_initlist(&group->tg_filelist); #endif /* Allocate socket descriptors for the TCB */ diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c index 648d9273e..78d6cbfec 100644 --- a/nuttx/sched/sched_setuppthreadfiles.c +++ b/nuttx/sched/sched_setuppthreadfiles.c @@ -79,14 +79,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; -#if CONFIG_NFILE_DESCRIPTORS > 0 - /* The child thread inherits the parent file descriptors */ - - tcb->filelist = rtcb->filelist; - files_addreflist(tcb->filelist); - -#endif /* CONFIG_NFILE_DESCRIPTORS */ - #if CONFIG_NSOCKET_DESCRIPTORS > 0 /* The child thread inherits the parent socket descriptors */ diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c index d01b8d4cd..9e44147e9 100644 --- a/nuttx/sched/sched_setuptaskfiles.c +++ b/nuttx/sched/sched_setuptaskfiles.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_setuptaskfiles.c * - * Copyright (C) 2007-2008, 2010, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2008, 2010, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -93,34 +93,33 @@ static inline void sched_dupfiles(FAR _TCB *tcb) FAR struct file *child; int i; + DEBUGASSERT(tcb && tcb->group && rtcb->group); + /* Duplicate the file descriptors. This will be either all of the * file descriptors or just the first three (stdin, stdout, and stderr) * if CONFIG_FDCLONE_STDIO is defined. NFSDS_TOCLONE is set * accordingly above. */ - if (rtcb->filelist) - { - /* Get pointers to the parent and child task file lists */ + /* Get pointers to the parent and child task file lists */ - parent = rtcb->filelist->fl_files; - child = tcb->filelist->fl_files; + parent = rtcb->group->tg_filelist.fl_files; + child = tcb->group->tg_filelist.fl_files; - /* Check each file in the parent file list */ + /* Check each file in the parent file list */ - for (i = 0; i < NFDS_TOCLONE; i++) - { - /* Check if this file is opened by the parent. We can tell if - * if the file is open because it contain a reference to a non-NULL - * i-node structure. - */ + for (i = 0; i < NFDS_TOCLONE; i++) + { + /* Check if this file is opened by the parent. We can tell if + * if the file is open because it contain a reference to a non-NULL + * i-node structure. + */ - if (parent[i].f_inode) - { - /* Yes... duplicate it for the child */ + if (parent[i].f_inode) + { + /* Yes... duplicate it for the child */ - (void)files_dup(&parent[i], &child[i]); - } + (void)files_dup(&parent[i], &child[i]); } } } @@ -209,14 +208,14 @@ static inline void sched_dupsockets(FAR _TCB *tcb) int sched_setuptaskfiles(FAR _TCB *tcb) { - /* Allocate file descriptors for the TCB */ - #if CONFIG_NFILE_DESCRIPTORS > 0 - tcb->filelist = files_alloclist(); - if (!tcb->filelist) - { - return -ENOMEM; - } + FAR struct task_group_s *group = tcb->group; + + DEBUGASSERT(group); + + /* Initialize file descriptors for the TCB */ + + files_initlist(&group->tg_filelist); #endif /* Allocate socket descriptors for the TCB */ diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 3fdf08bf7..5a2b9e57e 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -177,6 +177,89 @@ static inline void task_onexit(FAR _TCB *tcb, int status) # define task_onexit(tcb,status) #endif +/**************************************************************************** + * Name: task_exitstatus + * + * Description: + * Report exit status when main task of a task group exits + * + ****************************************************************************/ + +#ifdef CONFIG_SCHED_CHILD_STATUS +static inline void task_exitstatus(FAR struct task_group_s *group, int status) +{ + FAR struct child_status_s *child; + + /* Check if the parent task group has suppressed retention of + * child exit status information. + */ + + if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) + { + /* No.. Find the exit status entry for this task in the parent TCB */ + + child = group_findchild(group, getpid()); + DEBUGASSERT(child); + if (child) + { +#ifndef HAVE_GROUP_MEMBERS + /* No group members? Save the exit status */ + + child->ch_status = status; +#endif + /* Save the exit status.. For the case of HAVE_GROUP_MEMBERS, + * the child status will be as exited until the last member + * of the task group exits. + */ + + child->ch_status = status; + } + } +} +#else + +# define task_exitstatus(group,status) + +#endif /* CONFIG_SCHED_CHILD_STATUS */ + +/**************************************************************************** + * Name: task_groupexit + * + * Description: + * Mark that the final thread of a child task group as exited. + * + ****************************************************************************/ + +#ifdef CONFIG_SCHED_CHILD_STATUS +static inline void task_groupexit(FAR struct task_group_s *group) +{ + FAR struct child_status_s *child; + + /* Check if the parent task group has suppressed retention of child exit + * status information. + */ + + if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) + { + /* No.. Find the exit status entry for this task in the parent TCB */ + + child = group_findchild(group, getpid()); + DEBUGASSERT(child); + if (child) + { + /* Mark that all members of the child task group has exit'ed */ + + child->ch_flags |= CHILD_FLAG_EXITED; + } + } +} + +#else + +# define task_groupexit(group) + +#endif /* CONFIG_SCHED_CHILD_STATUS */ + /**************************************************************************** * Name: task_sigchild * @@ -195,55 +278,41 @@ static inline void task_sigchild(gid_t pgid, FAR _TCB *ctcb, int status) DEBUGASSERT(chgrp); - /* Only the final exiting thread in a task group should generate SIGCHLD. */ + /* Get the parent task group. It is possible that all of the members of + * the parent task group have exited. This would not be an error. In + * this case, the child task group has been orphaned. + */ - if (chgrp->tg_nmembers == 1) + pgrp = group_find(chgrp->tg_pgid); + if (!pgrp) { - /* Get the parent task group */ - - pgrp = group_find(chgrp->tg_pgid); - - /* It is possible that all of the members of the parent task group - * have exited. This would not be an error. In this case, the - * child task group has been orphaned. + /* Set the task group ID to an invalid group ID. The dead parent + * task group ID could get reused some time in the future. */ - if (!pgrp) - { - /* Set the task group ID to an invalid group ID. The dead parent - * task group ID could get reused some time in the future. - */ - - chgrp->tg_pgid = INVALID_GROUP_ID; - return; - } - -#ifdef CONFIG_SCHED_CHILD_STATUS - /* Check if the parent task group has suppressed retention of child exit - * status information. Only 'tasks' report exit status, not pthreads. - * pthreads have a different mechanism. - */ - - if ((pgrp->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) - { - FAR struct child_status_s *child; + chgrp->tg_pgid = INVALID_GROUP_ID; + return; + } - /* No.. Find the exit status entry for this task in the parent TCB */ + /* Save the exit status now if this is the main thread of the task group + * that is exiting. Only the exiting main task of a task group carries + * interpretable exit Check if this is the main task that is exiting. + */ - child = group_findchild(pgrp, getpid()); - DEBUGASSERT(child); - if (child) - { - /* Mark that the child has exit'ed */ + if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) + { + task_exitstatus(pgrp, status); + } - child->ch_flags |= CHILD_FLAG_EXITED; + /* But only the final exiting thread in a task group, whatever it is, + * should generate SIGCHLD. + */ - /* Save the exit status */ + if (chgrp->tg_nmembers == 1) + { + /* Mark that all of the threads in the task group have exited */ - child->ch_status = status; - } - } -#endif /* CONFIG_SCHED_CHILD_STATUS */ + task_groupexit(pgrp); /* Create the siginfo structure. We don't actually know the cause. * That is a bug. Let's just say that the child task just exit-ted @@ -278,30 +347,9 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) { #ifdef CONFIG_SCHED_CHILD_STATUS - /* Check if the parent task group has suppressed retention of child exit - * status information. Only 'tasks' report exit status, not pthreads. - * pthreads have a different mechanism. - */ + /* Save the exit status now of the main thread */ - if ((ptcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) - { - FAR struct child_status_s *child; - - /* No.. Find the exit status entry for this task in the parent TCB */ - - child = group_findchild(ptcb->group, getpid()); - DEBUGASSERT(child); - if (child) - { - /* Mark that the child has exit'ed */ - - child->ch_flags |= CHILD_FLAG_EXITED; - - /* Save the exit status */ - - child->ch_status = status; - } - } + task_exitstatus(ptcb->group, status); #else /* CONFIG_SCHED_CHILD_STATUS */ @@ -506,14 +554,6 @@ void task_exithook(FAR _TCB *tcb, int status) group_leave(tcb); #endif - /* Free all file-related resources now. This gets called again - * just be be certain when the TCB is delallocated. However, we - * really need to close files as soon as possible while we still - * have a functioning task. - */ - - (void)sched_releasefiles(tcb); - /* Deallocate anything left in the TCB's queues */ #ifndef CONFIG_DISABLE_SIGNALS -- cgit v1.2.3 From b82c36961aa730fc39a9fc8eac17e2518128cb67 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 22:25:21 +0000 Subject: Move stream data from TCB to task group structure. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5569 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/arch/arm/src/common/up_exit.c | 42 +++++------ nuttx/arch/avr/src/common/up_exit.c | 42 +++++------ nuttx/arch/hc/src/common/up_exit.c | 42 +++++------ nuttx/arch/mips/src/common/up_exit.c | 42 +++++------ nuttx/arch/sh/src/common/up_exit.c | 42 +++++------ nuttx/arch/x86/src/common/up_exit.c | 44 +++++------ nuttx/arch/z16/src/common/up_exit.c | 42 +++++------ nuttx/arch/z80/src/common/up_exit.c | 44 +++++------ nuttx/fs/fs_fdopen.c | 5 +- nuttx/include/nuttx/fs/fs.h | 1 - nuttx/include/nuttx/lib.h | 9 +-- nuttx/include/nuttx/sched.h | 13 ++-- nuttx/libc/misc/lib_init.c | 134 ++++++++++------------------------ nuttx/libc/stdio/lib_libflushall.c | 2 +- nuttx/sched/group_internal.h | 27 +------ nuttx/sched/group_leave.c | 2 + nuttx/sched/group_releasefiles.c | 9 +-- nuttx/sched/sched_getfiles.c | 2 +- nuttx/sched/sched_getstreams.c | 7 +- nuttx/sched/sched_setuppthreadfiles.c | 9 --- nuttx/sched/sched_setupstreams.c | 35 +++++---- nuttx/sched/task_exithook.c | 2 +- 23 files changed, 242 insertions(+), 357 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ae7105b89..b5933f620 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4036,3 +4036,5 @@ task group IN the child task's task group. * fs/, sched/, include/nuttx/sched.h, and include/nutts/fs/fs.h: Move file data from TCB to task group structure. + * libc/stdio/, sched/, include/nuttx/lib.h, and include/nutts/fs/fs.h: + Move stream data from TCB to task group structure. diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c index 5b469fd03..16f5c4442 100644 --- a/nuttx/arch/arm/src/common/up_exit.c +++ b/nuttx/arch/arm/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/avr/src/common/up_exit.c b/nuttx/arch/avr/src/common/up_exit.c index 0813754a0..68e33fde7 100644 --- a/nuttx/arch/avr/src/common/up_exit.c +++ b/nuttx/arch/avr/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/hc/src/common/up_exit.c b/nuttx/arch/hc/src/common/up_exit.c index 5313a1172..1c46875f8 100644 --- a/nuttx/arch/hc/src/common/up_exit.c +++ b/nuttx/arch/hc/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/mips/src/common/up_exit.c b/nuttx/arch/mips/src/common/up_exit.c index 5a7b68a99..e112364b4 100644 --- a/nuttx/arch/mips/src/common/up_exit.c +++ b/nuttx/arch/mips/src/common/up_exit.c @@ -77,7 +77,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -85,40 +89,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/sh/src/common/up_exit.c b/nuttx/arch/sh/src/common/up_exit.c index af270b335..705f49852 100644 --- a/nuttx/arch/sh/src/common/up_exit.c +++ b/nuttx/arch/sh/src/common/up_exit.c @@ -76,7 +76,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -84,40 +88,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/x86/src/common/up_exit.c b/nuttx/arch/x86/src/common/up_exit.c index 6a98c7dd0..dee6f7d49 100644 --- a/nuttx/arch/x86/src/common/up_exit.c +++ b/nuttx/arch/x86/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/z16/src/common/up_exit.c b/nuttx/arch/z16/src/common/up_exit.c index ad0c55eed..20b808360 100644 --- a/nuttx/arch/z16/src/common/up_exit.c +++ b/nuttx/arch/z16/src/common/up_exit.c @@ -77,7 +77,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -85,40 +89,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - lldbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + lldbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - lldbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - lldbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + lldbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - lldbg(" fd=%d\n", filep->fs_filedes); + lldbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c index 50289f52b..603a0bfbe 100644 --- a/nuttx/arch/z80/src/common/up_exit.c +++ b/nuttx/arch/z80/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -78,7 +78,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -86,40 +90,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - lldbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + lldbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - lldbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - lldbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + lldbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - lldbg(" fd=%d\n", filep->fs_filedes); + lldbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/fs/fs_fdopen.c b/nuttx/fs/fs_fdopen.c index 629083c77..d8a370482 100644 --- a/nuttx/fs/fs_fdopen.c +++ b/nuttx/fs/fs_fdopen.c @@ -144,6 +144,7 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb) { tcb = sched_self(); } + DEBUGASSERT(tcb && tcb->group); /* Verify that this is a valid file/socket descriptor and that the * requested access can be support. @@ -191,9 +192,9 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb) /* Get the stream list from the TCB */ - slist = tcb->streams; + slist = &tcb->group->tg_streamlist; - /* Find an unallocated FILE structure in the stream list */ + /* Find an unallocated FILE structure in the stream list */ ret = sem_wait(&slist->sl_sem); if (ret != OK) diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index 02855460c..93ca2a334 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -293,7 +293,6 @@ struct file_struct struct streamlist { - int sl_crefs; /* Reference count */ sem_t sl_sem; /* For thread safety */ struct file_struct sl_streams[CONFIG_NFILE_STREAMS]; }; diff --git a/nuttx/include/nuttx/lib.h b/nuttx/include/nuttx/lib.h index 220af2030..3bc581e18 100644 --- a/nuttx/include/nuttx/lib.h +++ b/nuttx/include/nuttx/lib.h @@ -2,7 +2,7 @@ * include/nuttx/lib.h * Non-standard, internal APIs available in lib/. * - * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -67,11 +67,10 @@ extern "C" { /* Functions contained in lib_init.c ****************************************/ -EXTERN void weak_function lib_initialize(void); +void weak_function lib_initialize(void); #if CONFIG_NFILE_STREAMS > 0 -EXTERN FAR struct streamlist *lib_alloclist(void); -EXTERN void lib_addreflist(FAR struct streamlist *list); -EXTERN void lib_releaselist(FAR struct streamlist *list); +void lib_streaminit(FAR struct streamlist *list); +void lib_releaselist(FAR struct streamlist *list); #endif #undef EXTERN diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 1580a80d3..a084d50ba 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -81,6 +81,8 @@ # define HAVE_TASK_GROUP 1 # elif CONFIG_NFILE_DESCRIPTORS > 0 # define HAVE_TASK_GROUP 1 +# elif CONFIG_NFILE_STREAMS > 0 +# define HAVE_TASK_GROUP 1 # endif #endif @@ -303,7 +305,10 @@ struct task_group_s #endif /* FILE streams ***************************************************************/ - /* Not yet (see streamlist) */ + +#if CONFIG_NFILE_STREAMS > 0 + struct streamlist tg_streamlist; /* Holds C buffered I/O info */ +#endif /* CONFIG_NFILE_STREAMS */ /* Sockets ********************************************************************/ /* Not yet (see struct socketlist) */ @@ -445,12 +450,6 @@ struct _TCB int pterrno; /* Current per-thread errno */ - /* File system support ********************************************************/ - -#if CONFIG_NFILE_STREAMS > 0 - FAR struct streamlist *streams; /* Holds C buffered I/O info */ -#endif - /* Network socket *************************************************************/ #if CONFIG_NSOCKET_DESCRIPTORS > 0 diff --git a/nuttx/libc/misc/lib_init.c b/nuttx/libc/misc/lib_init.c index 6a120f7b1..434c46505 100644 --- a/nuttx/libc/misc/lib_init.c +++ b/nuttx/libc/misc/lib_init.c @@ -1,7 +1,7 @@ /************************************************************ * libc/misc/lib_init.c * - * Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -76,69 +76,35 @@ void weak_const_function lib_initialize(void) } #if CONFIG_NFILE_STREAMS > 0 -/* The following function is called when a new TCB is allocated. It - * creates the streamlist instance that is stored in the TCB. +/* The following function is called when a new task is allocated. It + * intializes the streamlist instance that is stored in the task group. */ -FAR struct streamlist *lib_alloclist(void) +void lib_streaminit(FAR struct streamlist *list) { - FAR struct streamlist *list; - list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist)); - if (list) - { - int i; - - /* Start with a reference count of one */ - - list->sl_crefs = 1; + int i; - /* Initialize the list access mutex */ + /* Initialize the list access mutex */ - (void)sem_init(&list->sl_sem, 0, 1); + (void)sem_init(&list->sl_sem, 0, 1); - /* Initialize each FILE structure */ + /* Initialize each FILE structure */ - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - /* Clear the IOB */ + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + /* Clear the IOB */ - memset(&list->sl_streams[i], 0, sizeof(FILE)); + memset(&list->sl_streams[i], 0, sizeof(FILE)); - /* Indicate not opened */ + /* Indicate not opened */ - list->sl_streams[i].fs_filedes = -1; + list->sl_streams[i].fs_filedes = -1; - /* Initialize the stream semaphore to one to support one-at- - * a-time access to private data sets. - */ - - lib_sem_initialize(&list->sl_streams[i]); - } - } - return list; + /* Initialize the stream semaphore to one to support one-at- + * a-time access to private data sets. + */ -} - -/* This function is called when a TCB is closed (such as with - * pthread_create(). It increases the reference count on the stream - * list. - */ - -void lib_addreflist(FAR struct streamlist *list) -{ - if (list) - { - /* Increment the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - list->sl_crefs++; - irqrestore(flags); + lib_sem_initialize(&list->sl_streams[i]); } } @@ -149,57 +115,33 @@ void lib_addreflist(FAR struct streamlist *list) void lib_releaselist(FAR struct streamlist *list) { - int crefs; - if (list) - { - /* Decrement the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - crefs = --(list->sl_crefs); - irqrestore(flags); - - /* If the count decrements to zero, then there is no reference - * to the structure and it should be deallocated. Since there - * are references, it would be an error if any task still held - * a reference to the list's semaphore. - */ - - if (crefs <= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - int i; + int i; #endif - /* Destroy the semaphore and release the filelist */ - (void)sem_destroy(&list->sl_sem); + DEBUGASSERT(list); + + /* Destroy the semaphore and release the filelist */ - /* Release each stream in the list */ + (void)sem_destroy(&list->sl_sem); + + /* Release each stream in the list */ #if CONFIG_STDIO_BUFFER_SIZE > 0 - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - /* Destroy the semaphore that protects the IO buffer */ - - (void)sem_destroy(&list->sl_streams[i].fs_sem); - - /* Release the IO buffer */ - if (list->sl_streams[i].fs_bufstart) - { - sched_free(list->sl_streams[i].fs_bufstart); - } - } -#endif - /* Finally, release the list itself */ + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + /* Destroy the semaphore that protects the IO buffer */ - sched_free(list); - } - } + (void)sem_destroy(&list->sl_streams[i].fs_sem); + + /* Release the IO buffer */ + + if (list->sl_streams[i].fs_bufstart) + { + sched_free(list->sl_streams[i].fs_bufstart); + } + } +#endif } #endif /* CONFIG_NFILE_STREAMS */ diff --git a/nuttx/libc/stdio/lib_libflushall.c b/nuttx/libc/stdio/lib_libflushall.c index 7ac3da7e0..22baed968 100644 --- a/nuttx/libc/stdio/lib_libflushall.c +++ b/nuttx/libc/stdio/lib_libflushall.c @@ -1,7 +1,7 @@ /**************************************************************************** * libc/stdio/lib_libflushall.c * - * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index 39d0a2b7c..e6e0dfd16 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -86,28 +86,11 @@ void group_leave(FAR _TCB *tcb); FAR struct task_group_s *group_find(gid_t gid); int group_addmember(FAR struct task_group_s *group, pid_t pid); int group_removemember(FAR struct task_group_s *group, pid_t pid); -#else -# define group_find(gid) (NULL) -# define group_addmember(group,pid) (0) -# define group_removemember(group,pid) (1) #endif #ifndef CONFIG_DISABLE_SIGNALS int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info); -#else -# define group_signal(tcb,info) (0) #endif - -#else -# define group_allocate(tcb) (0) -# define group_initialize(tcb) (0) -# define group_bind(tcb) (0) -# define group_join(tcb) (0) -# define group_leave(tcb) -# define group_find(gid) (NULL) -# define group_addmember(group,pid) (0) -# define group_removemember(group,pid) (1) -# define group_signal(tcb,info) (0) #endif /* HAVE_TASK_GROUP */ /* Parent/child data management */ @@ -127,15 +110,13 @@ FAR struct child_status_s *group_removechild(FAR struct task_group_s *group, pid_t pid); void group_removechildren(FAR struct task_group_s *group); +#endif /* CONFIG_SCHED_CHILD_STATUS */ +#endif /* CONFIG_SCHED_HAVE_PARENT */ + /* File/network resources */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -int group_releasefiles(FAR _TCB *tcb); -#else -# define group_releasefiles(t) (OK) +int group_releasefiles(FAR _TCB *tcb); #endif -#endif /* CONFIG_SCHED_CHILD_STATUS */ -#endif /* CONFIG_SCHED_HAVE_PARENT */ - #endif /* __SCHED_GROUP_INERNAL_H */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index 158ba30b5..70ef93666 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -165,6 +165,7 @@ static inline void group_release(FAR _TCB *tcb, env_release(tcb); #endif +#ifdef HAVE_GROUP_MEMBERS /* Remove the group from the list of groups */ group_remove(group); @@ -176,6 +177,7 @@ static inline void group_release(FAR _TCB *tcb, sched_free(group->tg_members); group->tg_members = NULL; } +#endif /* Release the group container itself */ diff --git a/nuttx/sched/group_releasefiles.c b/nuttx/sched/group_releasefiles.c index 40bf373b4..b33415c76 100644 --- a/nuttx/sched/group_releasefiles.c +++ b/nuttx/sched/group_releasefiles.c @@ -80,7 +80,9 @@ int group_releasefiles(_TCB *tcb) #if CONFIG_NFILE_DESCRIPTORS > 0 FAR struct task_group_s *group = tcb->group; DEBUGASSERT(group); +#endif +#if CONFIG_NFILE_DESCRIPTORS > 0 /* Free resources used by the file descriptor list */ files_releaselist(&group->tg_filelist); @@ -88,11 +90,8 @@ int group_releasefiles(_TCB *tcb) #if CONFIG_NFILE_STREAMS > 0 /* Free the stream list */ - if (tcb->streams) - { - lib_releaselist(tcb->streams); - tcb->streams = NULL; - } + lib_releaselist(&group->tg_streamlist); + #endif /* CONFIG_NFILE_STREAMS */ #endif /* CONFIG_NFILE_DESCRIPTORS */ diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c index eca4ba3ff..17ca2bbf6 100644 --- a/nuttx/sched/sched_getfiles.c +++ b/nuttx/sched/sched_getfiles.c @@ -1,7 +1,7 @@ /************************************************************************ * sched/sched_getfiles.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/nuttx/sched/sched_getstreams.c b/nuttx/sched/sched_getstreams.c index f7c21ab4c..dab406e66 100644 --- a/nuttx/sched/sched_getstreams.c +++ b/nuttx/sched/sched_getstreams.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_getstreams.c * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -70,7 +70,10 @@ FAR struct streamlist *sched_getstreams(void) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - return rtcb->streams; + FAR struct task_group_s *group = rtcb->group; + + DEBUGASSERT(group); + return &group->tg_streamlist; } #endif /* CONFIG_NFILE_DESCRIPTORS && CONFIG_NFILE_STREAMS */ diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c index 78d6cbfec..91d72fa7f 100644 --- a/nuttx/sched/sched_setuppthreadfiles.c +++ b/nuttx/sched/sched_setuppthreadfiles.c @@ -77,8 +77,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) { - FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - #if CONFIG_NSOCKET_DESCRIPTORS > 0 /* The child thread inherits the parent socket descriptors */ @@ -87,13 +85,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) #endif /* CONFIG_NSOCKET_DESCRIPTORS */ -#if CONFIG_NFILE_STREAMS > 0 - /* The child thread inherits the parent streams */ - - tcb->streams = rtcb->streams; - lib_addreflist(tcb->streams); - -#endif /* CONFIG_NFILE_STREAMS */ return OK; } diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/sched_setupstreams.c index 22895b047..fb2e4d0be 100644 --- a/nuttx/sched/sched_setupstreams.c +++ b/nuttx/sched/sched_setupstreams.c @@ -72,24 +72,23 @@ int sched_setupstreams(FAR _TCB *tcb) { - /* Allocate file streams for the TCB */ - - tcb->streams = lib_alloclist(); - if (tcb->streams) - { - /* fdopen to get the stdin, stdout and stderr streams. - * The following logic depends on the fact that the library - * layer will allocate FILEs in order. - * - * fd = 0 is stdin (read-only) - * fd = 1 is stdout (write-only, append) - * fd = 2 is stderr (write-only, append) - */ - - (void)fs_fdopen(0, O_RDONLY, tcb); - (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); - (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); - } + DEBUGASSERT(tcb && tcb->group); + + /* Initialize file streams for the task group */ + + lib_streaminit(&tcb->group->tg_streamlist); + + /* fdopen to get the stdin, stdout and stderr streams. The following logic + * depends on the fact that the library layer will allocate FILEs in order. + * + * fd = 0 is stdin (read-only) + * fd = 1 is stdout (write-only, append) + * fd = 2 is stderr (write-only, append) + */ + + (void)fs_fdopen(0, O_RDONLY, tcb); + (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); + (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); return OK; } diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 5a2b9e57e..889df25e0 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -543,7 +543,7 @@ void task_exithook(FAR _TCB *tcb, int status) */ #if CONFIG_NFILE_STREAMS > 0 - (void)lib_flushall(tcb->streams); + (void)lib_flushall(&tcb->group->tg_streamlist); #endif /* Leave the task group. Perhaps discarding any un-reaped child -- cgit v1.2.3 From cc99071a6827580d7b9c403a907605777522ab5f Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 28 Jan 2013 15:03:17 +0000 Subject: Serial driver needed even when no console; Fix user LED settings in all STM32 configurations git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5575 42af7a65-404d-4744-a932-0658087f49c3 --- misc/tools/README.txt | 21 ++++++++++---- nuttx/ChangeLog | 7 +++++ nuttx/arch/arm/src/common/up_initialize.c | 14 +++++++--- nuttx/arch/arm/src/common/up_internal.h | 17 ++++++++++-- nuttx/arch/avr/src/at32uc3/at32uc3_config.h | 17 ++++++++++-- nuttx/arch/avr/src/at90usb/at90usb_config.h | 17 ++++++++++-- nuttx/arch/avr/src/atmega/atmega_config.h | 17 ++++++++++-- nuttx/arch/avr/src/common/up_initialize.c | 28 ++++++++++++++++--- nuttx/arch/hc/src/common/up_initialize.c | 14 +++++++--- nuttx/arch/hc/src/common/up_internal.h | 17 ++++++++++-- nuttx/arch/mips/src/common/up_initialize.c | 12 ++++++-- nuttx/arch/mips/src/common/up_internal.h | 15 +++++++++- nuttx/arch/sh/src/common/up_initialize.c | 22 +++++++++------ nuttx/arch/sh/src/common/up_internal.h | 15 +++++++++- nuttx/arch/x86/src/common/up_initialize.c | 14 +++++++--- nuttx/arch/x86/src/common/up_internal.h | 17 ++++++++++-- nuttx/arch/z16/src/common/up_initialize.c | 6 ++-- nuttx/arch/z16/src/common/up_internal.h | 35 +++++++++++++++++++++--- nuttx/arch/z80/src/common/up_initialize.c | 14 +++++----- nuttx/arch/z80/src/common/up_internal.h | 31 +++++++++++++++++++-- nuttx/configs/cloudctrl/src/up_userleds.c | 8 +++--- nuttx/configs/fire-stm32v2/src/up_userleds.c | 6 ++-- nuttx/configs/lpc4330-xplorer/src/up_userleds.c | 8 +++--- nuttx/configs/shenzhou/src/up_userleds.c | 8 +++--- nuttx/configs/stm3220g-eval/src/up_userleds.c | 8 +++--- nuttx/configs/stm3240g-eval/src/up_userleds.c | 8 +++--- nuttx/configs/stm32f4discovery/README.txt | 2 +- nuttx/configs/stm32f4discovery/src/up_userleds.c | 8 +++--- 28 files changed, 314 insertions(+), 92 deletions(-) (limited to 'nuttx/arch') diff --git a/misc/tools/README.txt b/misc/tools/README.txt index 1546c6f39..e1c67c5f0 100644 --- a/misc/tools/README.txt +++ b/misc/tools/README.txt @@ -30,25 +30,34 @@ kconfig-frontends General build instructions: cd kconfig-frontends - ./configure + ./configure --enable-mconf make make install - To suppress the nconf and the graphical interfaces which are not used by - NuttX: + It is a good idea to add '--enable-mconf' on the 'configure' command line. + The kconfig-frontends make will generate many programs, but the NuttX + build system only needs the 'kconfig-conf' and 'kconfig-mconf' programs. + If the requirements for 'kconfig-mconf' are not supported by your system, + the kconfig-frontends configuration system will not build it. Adding the + option --enable-mconf assures you that 'kconfig-mconf' will be built or + if it is not built, it will tell you why it was not built. - ./configure --disable-gconf --disable-qconf + To suppress the 'nconf' and the graphical front-ends which are not used by + NuttX, you can add: + + ./configure --enable-mconfig --disable-nconf --disable-gconf --disable-qconf make make install To suppress the graphical interfaces, use static libraries, and disable creation of other utilities: - ./configure --disable-shared --enable-static --disable-gconf --disable-qconf --disable-nconf --disable-utils + ./configure --disable-shared --enable-static --enable-mconfig --disable-nconf --disable-gconf --disable-qconf --disable-nconf --disable-utils make make install - You may require root privileges to 'make install'. + The default installation location for the tools is /usr/local/bin. You + may require root privileges to 'make install'. --program-prefix= ----------------- diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 4fc75c084..c2ce13738 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4050,4 +4050,11 @@ configuration that uses USB CDC/ACM for the NSH console. * configs/stm32f4discovery/nsh: Converted to use the kconfig-frontends tools. + * configs/*/src/up_userleds.c: Fix a error that was cloned into + all STM32 user LED code. The wrong defintions were being used + to set LEDs on or off. + * arch/*/common/up_internal.h and arch/*/common/up_initialize.c: + Serial was driver was not being built if there is no console + device. Obviously, the serial driver may be needed even in + this case. diff --git a/nuttx/arch/arm/src/common/up_initialize.c b/nuttx/arch/arm/src/common/up_initialize.c index 80f9b1193..0ea3fcd35 100644 --- a/nuttx/arch/arm/src/common/up_initialize.c +++ b/nuttx/arch/arm/src/common/up_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/common/up_initialize.c * - * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2010, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -161,11 +161,17 @@ void up_initialize(void) devnull_register(); /* Standard /dev/null */ #endif - /* Initialize the console device driver */ + /* Initialize the serial device driver */ -#if defined(USE_SERIALDRIVER) +#ifdef USE_SERIALDRIVER up_serialinit(); -#elif defined(CONFIG_DEV_LOWCONSOLE) +#endif + + /* Initialize the console device driver (if it is other than the standard + * serial driver). + */ + +#if defined(CONFIG_DEV_LOWCONSOLE) lowconsole_init(); #elif defined(CONFIG_RAMLOG_CONSOLE) ramlog_consoleinit(); diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h index 55071345f..8a24f003e 100644 --- a/nuttx/arch/arm/src/common/up_internal.h +++ b/nuttx/arch/arm/src/common/up_internal.h @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_internal.h * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -63,7 +63,10 @@ #undef CONFIG_SUPPRESS_UART_CONFIG /* DEFINED: Do not reconfig UART */ #undef CONFIG_DUMP_ON_EXIT /* DEFINED: Dump task state on exit */ -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS == 0 # undef USE_SERIALDRIVER @@ -84,6 +87,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_config.h b/nuttx/arch/avr/src/at32uc3/at32uc3_config.h index 1f942591a..8867fae86 100644 --- a/nuttx/arch/avr/src/at32uc3/at32uc3_config.h +++ b/nuttx/arch/avr/src/at32uc3/at32uc3_config.h @@ -1,7 +1,7 @@ /************************************************************************************ * arch/avr/src/at32uc3/at32uc3_config.h * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -144,7 +144,10 @@ # undef HAVE_SERIAL_CONSOLE #endif -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 # undef USE_SERIALDRIVER @@ -168,6 +171,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG diff --git a/nuttx/arch/avr/src/at90usb/at90usb_config.h b/nuttx/arch/avr/src/at90usb/at90usb_config.h index 0aa73053e..3f0d80a19 100644 --- a/nuttx/arch/avr/src/at90usb/at90usb_config.h +++ b/nuttx/arch/avr/src/at90usb/at90usb_config.h @@ -1,7 +1,7 @@ /************************************************************************************ * arch/avr/src/at90usb/at90usb_config.h * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -63,7 +63,10 @@ # undef HAVE_SERIAL_CONSOLE #endif -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 # undef USE_SERIALDRIVER @@ -87,6 +90,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG diff --git a/nuttx/arch/avr/src/atmega/atmega_config.h b/nuttx/arch/avr/src/atmega/atmega_config.h index 3835fb459..5d784ccf3 100644 --- a/nuttx/arch/avr/src/atmega/atmega_config.h +++ b/nuttx/arch/avr/src/atmega/atmega_config.h @@ -1,7 +1,7 @@ /************************************************************************************ * arch/avr/src/atmega/atmega_config.h * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -68,7 +68,10 @@ # undef HAVE_SERIAL_CONSOLE #endif -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 # undef USE_SERIALDRIVER @@ -92,6 +95,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG diff --git a/nuttx/arch/avr/src/common/up_initialize.c b/nuttx/arch/avr/src/common/up_initialize.c index 76de41c99..684dab09d 100644 --- a/nuttx/arch/avr/src/common/up_initialize.c +++ b/nuttx/arch/avr/src/common/up_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/avr/src/common/up_initialize.c * - * Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -57,6 +57,10 @@ * up_serialinit to be incorrectly called if there is no USART configured to * be an RS-232 device (see as an example arch/avr/src/at32uc23/at32uc3_config.h) * This will probably have to be revisited someday. + * + * If a console is enabled and no other console device is specified, then a + * serial console is + * assumed. */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 @@ -78,6 +82,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG @@ -182,11 +196,17 @@ void up_initialize(void) devnull_register(); /* Standard /dev/null */ #endif - /* Initialize the console device driver */ + /* Initialize the serial device driver */ -#if defined(USE_SERIALDRIVER) +#ifdef USE_SERIALDRIVER up_serialinit(); -#elif defined(CONFIG_DEV_LOWCONSOLE) +#endif + + /* Initialize the console device driver (if it is other than the standard + * serial driver). + */ + +#if defined(CONFIG_DEV_LOWCONSOLE) lowconsole_init(); #elif defined(CONFIG_RAMLOG_CONSOLE) ramlog_consoleinit(); diff --git a/nuttx/arch/hc/src/common/up_initialize.c b/nuttx/arch/hc/src/common/up_initialize.c index b9dfd9ba1..885e79905 100644 --- a/nuttx/arch/hc/src/common/up_initialize.c +++ b/nuttx/arch/hc/src/common/up_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/hc/src/common/up_initialize.c * - * Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2010, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -149,11 +149,17 @@ void up_initialize(void) devnull_register(); /* Standard /dev/null */ #endif - /* Initialize the console device driver */ + /* Initialize the serial device driver */ -#if defined(USE_SERIALDRIVER) +#ifdef USE_SERIALDRIVER up_serialinit(); -#elif defined(CONFIG_DEV_LOWCONSOLE) +#endif + + /* Initialize the console device driver (if it is other than the standard + * serial driver). + */ + +#if defined(CONFIG_DEV_LOWCONSOLE) lowconsole_init(); #elif defined(CONFIG_RAMLOG_CONSOLE) ramlog_consoleinit(); diff --git a/nuttx/arch/hc/src/common/up_internal.h b/nuttx/arch/hc/src/common/up_internal.h index f1daf690f..0de737fb6 100644 --- a/nuttx/arch/hc/src/common/up_internal.h +++ b/nuttx/arch/hc/src/common/up_internal.h @@ -1,7 +1,7 @@ /**************************************************************************** * arch/hc/src/common/up_internal.h * - * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -62,7 +62,10 @@ #undef CONFIG_SUPPRESS_UART_CONFIG /* DEFINED: Do not reconfig UART */ #undef CONFIG_DUMP_ON_EXIT /* DEFINED: Dump task state on exit */ -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 # undef USE_SERIALDRIVER @@ -83,6 +86,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG diff --git a/nuttx/arch/mips/src/common/up_initialize.c b/nuttx/arch/mips/src/common/up_initialize.c index 3063b4b4b..a0f0ca9d5 100644 --- a/nuttx/arch/mips/src/common/up_initialize.c +++ b/nuttx/arch/mips/src/common/up_initialize.c @@ -151,11 +151,17 @@ void up_initialize(void) devnull_register(); /* Standard /dev/null */ #endif - /* Initialize the console device driver */ + /* Initialize the serial device driver */ -#if defined(USE_SERIALDRIVER) +#ifdef USE_SERIALDRIVER up_serialinit(); -#elif defined(CONFIG_DEV_LOWCONSOLE) +#endif + + /* Initialize the console device driver (if it is other than the standard + * serial driver). + */ + +#if defined(CONFIG_DEV_LOWCONSOLE) lowconsole_init(); #elif defined(CONFIG_RAMLOG_CONSOLE) ramlog_consoleinit(); diff --git a/nuttx/arch/mips/src/common/up_internal.h b/nuttx/arch/mips/src/common/up_internal.h index b284961b0..927538dea 100644 --- a/nuttx/arch/mips/src/common/up_internal.h +++ b/nuttx/arch/mips/src/common/up_internal.h @@ -60,7 +60,10 @@ #undef CONFIG_SUPPRESS_UART_CONFIG /* DEFINED: Do not reconfig UART */ #undef CONFIG_DUMP_ON_EXIT /* DEFINED: Dump task state on exit */ -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 # undef USE_SERIALDRIVER @@ -81,6 +84,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG diff --git a/nuttx/arch/sh/src/common/up_initialize.c b/nuttx/arch/sh/src/common/up_initialize.c index 3aef5c637..727dc1352 100644 --- a/nuttx/arch/sh/src/common/up_initialize.c +++ b/nuttx/arch/sh/src/common/up_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/sh/src/common/up_initialize.c * - * Copyright (C) 2008-2010, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2010, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -136,16 +136,20 @@ void up_initialize(void) devnull_register(); /* Standard /dev/null */ #endif - /* Initialize the console device driver. NOTE that the naming - * implies that the console is a serial driver. That is usually the case, - * however, if no UARTs are enabled, the console could als be provided - * through some other device, such as an LCD. Architecture-specific logic - * will have to detect that case. + /* Initialize the serial device driver */ + +#ifdef USE_SERIALDRIVER + up_serialinit(); +#endif + + /* Initialize the console device driver (if it is other than the standard + * serial driver). NOTE that the naming implies that the console is a serial + * driver. That is usually the case, however, if no UARTs are enabled, the + * console could als be provided through some other device, such as an LCD. + * Architecture-specific logic will have to detect that case. */ -#if defined(USE_SERIALDRIVER) - up_consoleinit(); -#elif defined(CONFIG_DEV_LOWCONSOLE) +#if defined(CONFIG_DEV_LOWCONSOLE) lowconsole_init(); #elif defined(CONFIG_RAMLOG_CONSOLE) ramlog_consoleinit(); diff --git a/nuttx/arch/sh/src/common/up_internal.h b/nuttx/arch/sh/src/common/up_internal.h index f47b1078f..f56e97c97 100644 --- a/nuttx/arch/sh/src/common/up_internal.h +++ b/nuttx/arch/sh/src/common/up_internal.h @@ -1,7 +1,7 @@ /**************************************************************************** * arch/sh/src/common/up_internal.h * - * Copyright (C) 2008-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -67,6 +67,9 @@ * however, if no UARTs are enabled, the console could als be provided * through some other device, such as an LCD. Architecture-specific logic * will have to detect that case. + * + * If a console is enabled and no other console device is specified, then + * a serial console is assumed. */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 @@ -88,6 +91,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG diff --git a/nuttx/arch/x86/src/common/up_initialize.c b/nuttx/arch/x86/src/common/up_initialize.c index 49238556d..b49dd55b4 100644 --- a/nuttx/arch/x86/src/common/up_initialize.c +++ b/nuttx/arch/x86/src/common/up_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/x86/src/common/up_initialize.c * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -151,11 +151,17 @@ void up_initialize(void) devnull_register(); /* Standard /dev/null */ #endif - /* Initialize the console device driver */ + /* Initialize the serial device driver */ -#if defined(USE_SERIALDRIVER) +#ifdef USE_SERIALDRIVER up_serialinit(); -#elif defined(CONFIG_DEV_LOWCONSOLE) +#endif + + /* Initialize the console device driver (if it is other than the standard + * serial driver). + */ + +#if defined(CONFIG_DEV_LOWCONSOLE) lowconsole_init(); #elif defined(CONFIG_RAMLOG_CONSOLE) ramlog_consoleinit(); diff --git a/nuttx/arch/x86/src/common/up_internal.h b/nuttx/arch/x86/src/common/up_internal.h index df43ca1a8..c27717c38 100644 --- a/nuttx/arch/x86/src/common/up_internal.h +++ b/nuttx/arch/x86/src/common/up_internal.h @@ -1,7 +1,7 @@ /**************************************************************************** * arch/x86/src/common/up_internal.h * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -62,7 +62,10 @@ #undef CONFIG_SUPPRESS_UART_CONFIG /* DEFINED: Do not reconfig UART */ #undef CONFIG_DUMP_ON_EXIT /* DEFINED: Dump task state on exit */ -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 # undef USE_SERIALDRIVER @@ -83,6 +86,16 @@ # endif #endif +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) +# define USE_SERIALDRIVER 1 +#endif + /* Determine which device to use as the system logging device */ #ifndef CONFIG_SYSLOG diff --git a/nuttx/arch/z16/src/common/up_initialize.c b/nuttx/arch/z16/src/common/up_initialize.c index e9c58c489..f06d8ff24 100644 --- a/nuttx/arch/z16/src/common/up_initialize.c +++ b/nuttx/arch/z16/src/common/up_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_initialize.c * - * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -168,7 +168,9 @@ void up_initialize(void) up_serialinit(); #endif - /* Initialize the console device driver */ + /* Initialize the console device driver (if it is other than the standard + * serial driver). + */ #if defined(CONFIG_DEV_LOWCONSOLE) lowconsole_init(); diff --git a/nuttx/arch/z16/src/common/up_internal.h b/nuttx/arch/z16/src/common/up_internal.h index 2c1968e8d..e4dfd1dd5 100644 --- a/nuttx/arch/z16/src/common/up_internal.h +++ b/nuttx/arch/z16/src/common/up_internal.h @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_internal.h * - * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -60,15 +60,42 @@ #undef CONFIG_Z16_LOWPUTC /* Support up_lowputc for debug */ #undef CONFIG_Z16_LOWGETC /* support up_lowgetc for debug */ -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if defined(CONFIG_Z16_LOWPUTC) || defined(CONFIG_Z16_LOWGETC) || \ CONFIG_NFILE_DESCRIPTORS == 0 || defined(CONFIG_DEV_LOWCONSOLE) # define USE_LOWCONSOLE 1 # define USE_LOWUARTINIT 1 -#elif defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0 +#elif !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 +# undef USE_SERIALDRIVER +# undef USE_EARLYSERIALINIT +# undef CONFIG_DEV_LOWCONSOLE +# undef CONFIG_RAMLOG_CONSOLE +#else +# if defined(CONFIG_RAMLOG_CONSOLE) +# undef USE_SERIALDRIVER +# undef USE_EARLYSERIALINIT +# undef CONFIG_DEV_LOWCONSOLE +# elif defined(CONFIG_DEV_LOWCONSOLE) +# undef USE_SERIALDRIVER +# undef USE_EARLYSERIALINIT +# else +# define USE_SERIALDRIVER 1 +# define USE_EARLYSERIALINIT 1 +# endif +#endif + +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) # define USE_SERIALDRIVER 1 -# define USE_EARLYSERIALINIT 1 #endif /* Determine which device to use as the system logging device */ diff --git a/nuttx/arch/z80/src/common/up_initialize.c b/nuttx/arch/z80/src/common/up_initialize.c index 652a7cc88..c7b7bdb22 100644 --- a/nuttx/arch/z80/src/common/up_initialize.c +++ b/nuttx/arch/z80/src/common/up_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/z80/src/common/up_initialize.c * - * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -161,15 +161,15 @@ void up_initialize(void) /* Initialize the serial device driver */ -#ifdef USE_LOWSERIALINIT - up_lowserialinit(); +#ifdef USE_SERIALDRIVER + up_serialinit(); #endif - /* Initialize the console device driver */ + /* Initialize the console device driver (if it is other than the standard + * serial driver). + */ -#if defined(USE_SERIALDRIVER) - up_serialinit(); -#elif defined(CONFIG_DEV_LOWCONSOLE) +#if defined(CONFIG_DEV_LOWCONSOLE) lowconsole_init(); #elif defined(CONFIG_RAMLOG_CONSOLE) ramlog_consoleinit(); diff --git a/nuttx/arch/z80/src/common/up_internal.h b/nuttx/arch/z80/src/common/up_internal.h index 5f1750b64..36e1ac141 100644 --- a/nuttx/arch/z80/src/common/up_internal.h +++ b/nuttx/arch/z80/src/common/up_internal.h @@ -66,7 +66,10 @@ * Definitions ****************************************************************************/ -/* Determine which (if any) console driver to use */ +/* Determine which (if any) console driver to use. If a console is enabled + * and no other console device is specified, then a serial console is + * assumed. + */ #if CONFIG_NFILE_DESCRIPTORS == 0 || defined(CONFIG_DEV_LOWCONSOLE) # undef USE_SERIALDRIVER @@ -75,9 +78,31 @@ # else # undef USE_LOWSERIALINIT # endif -#elif defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0 +#elif !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS <= 0 +# undef USE_SERIALDRIVER +# undef USE_LOWSERIALINIT +# undef CONFIG_DEV_LOWCONSOLE +# undef CONFIG_RAMLOG_CONSOLE +#else +# undef USE_LOWSERIALINIT +# if defined(CONFIG_RAMLOG_CONSOLE) +# undef USE_SERIALDRIVER +# undef CONFIG_DEV_LOWCONSOLE +# elif defined(CONFIG_DEV_LOWCONSOLE) +# undef USE_SERIALDRIVER +# else +# define USE_SERIALDRIVER 1 +# endif +#endif + +/* If some other device is used as the console, then the serial driver may + * still be needed. Let's assume that if the upper half serial driver is + * built, then the lower half will also be needed. There is no need for + * the early serial initialization in this case. + */ + +#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL) # define USE_SERIALDRIVER 1 -# undef USE_LOWSERIALINIT #endif /**************************************************************************** diff --git a/nuttx/configs/cloudctrl/src/up_userleds.c b/nuttx/configs/cloudctrl/src/up_userleds.c index 5c112123b..bbb7cc62c 100644 --- a/nuttx/configs/cloudctrl/src/up_userleds.c +++ b/nuttx/configs/cloudctrl/src/up_userleds.c @@ -123,10 +123,10 @@ void stm32_setled(int led, bool ledon) void stm32_setleds(uint8_t ledset) { - stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0); - stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0); - stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0); - stm32_gpiowrite(BOARD_LED4, (ledset & BOARD_LED4_BIT) == 0); + stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0); + stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0); + stm32_gpiowrite(GPIO_LED3, (ledset & BOARD_LED3_BIT) == 0); + stm32_gpiowrite(GPIO_LED4, (ledset & BOARD_LED4_BIT) == 0); } #endif /* !CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/fire-stm32v2/src/up_userleds.c b/nuttx/configs/fire-stm32v2/src/up_userleds.c index da43d03ad..3dd1843ee 100644 --- a/nuttx/configs/fire-stm32v2/src/up_userleds.c +++ b/nuttx/configs/fire-stm32v2/src/up_userleds.c @@ -131,9 +131,9 @@ void stm32_setled(int led, bool ledon) void stm32_setleds(uint8_t ledset) { - stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0); - stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0); - stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0); + stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0); + stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0); + stm32_gpiowrite(GPIO_LED3, (ledset & BOARD_LED3_BIT) == 0); } #endif /* !CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/lpc4330-xplorer/src/up_userleds.c b/nuttx/configs/lpc4330-xplorer/src/up_userleds.c index e7b4b1189..2d8b5b511 100644 --- a/nuttx/configs/lpc4330-xplorer/src/up_userleds.c +++ b/nuttx/configs/lpc4330-xplorer/src/up_userleds.c @@ -140,8 +140,8 @@ void lpc43_ledinit(void) void lpc43_setled(int led, bool ledon) { - uint16_t gpiocfg = (led == BOARD_LED1 ? BOARD_LED1 : BOARD_LED2); - lpc43_gpio_write(GPIO_LED1, !ledon); + uint16_t gpiocfg = (led == BOARD_LED1 ? GPIO_LED1 : GPIO_LED2); + lpc43_gpio_write(gpiocfg, !ledon); } /**************************************************************************** @@ -150,8 +150,8 @@ void lpc43_setled(int led, bool ledon) void lpc43_setleds(uint8_t ledset) { - lpc43_gpio_write(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0); - lpc43_gpio_write(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0); + lpc43_gpio_write(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0); + lpc43_gpio_write(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0); } #endif /* !CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/shenzhou/src/up_userleds.c b/nuttx/configs/shenzhou/src/up_userleds.c index 0ba029228..4e1493a8d 100644 --- a/nuttx/configs/shenzhou/src/up_userleds.c +++ b/nuttx/configs/shenzhou/src/up_userleds.c @@ -122,10 +122,10 @@ void stm32_setled(int led, bool ledon) void stm32_setleds(uint8_t ledset) { - stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0); - stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0); - stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0); - stm32_gpiowrite(BOARD_LED4, (ledset & BOARD_LED4_BIT) == 0); + stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0); + stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0); + stm32_gpiowrite(GPIO_LED3, (ledset & BOARD_LED3_BIT) == 0); + stm32_gpiowrite(GPIO_LED4, (ledset & BOARD_LED4_BIT) == 0); } #endif /* !CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/stm3220g-eval/src/up_userleds.c b/nuttx/configs/stm3220g-eval/src/up_userleds.c index 6dc3db135..84510c703 100644 --- a/nuttx/configs/stm3220g-eval/src/up_userleds.c +++ b/nuttx/configs/stm3220g-eval/src/up_userleds.c @@ -122,10 +122,10 @@ void stm32_setled(int led, bool ledon) void stm32_setleds(uint8_t ledset) { - stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0); - stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0); - stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0); - stm32_gpiowrite(BOARD_LED4, (ledset & BOARD_LED4_BIT) == 0); + stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0); + stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0); + stm32_gpiowrite(GPIO_LED3, (ledset & BOARD_LED3_BIT) == 0); + stm32_gpiowrite(GPIO_LED4, (ledset & BOARD_LED4_BIT) == 0); } #endif /* !CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/stm3240g-eval/src/up_userleds.c b/nuttx/configs/stm3240g-eval/src/up_userleds.c index 59be38561..01c4b36d6 100644 --- a/nuttx/configs/stm3240g-eval/src/up_userleds.c +++ b/nuttx/configs/stm3240g-eval/src/up_userleds.c @@ -122,10 +122,10 @@ void stm32_setled(int led, bool ledon) void stm32_setleds(uint8_t ledset) { - stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0); - stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0); - stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0); - stm32_gpiowrite(BOARD_LED4, (ledset & BOARD_LED4_BIT) == 0); + stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0); + stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0); + stm32_gpiowrite(GPIO_LED3, (ledset & BOARD_LED3_BIT) == 0); + stm32_gpiowrite(GPIO_LED4, (ledset & BOARD_LED4_BIT) == 0); } #endif /* !CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index e34168224..e9c0e81c2 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -269,7 +269,7 @@ LEDs ==== The STM32F4Discovery board has four LEDs; green, organge, red and blue on the -board.. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is +board. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is defined. In that case, the usage by the board port is defined in include/board.h and src/up_leds.c. The LEDs are used to encode OS-related events as follows: diff --git a/nuttx/configs/stm32f4discovery/src/up_userleds.c b/nuttx/configs/stm32f4discovery/src/up_userleds.c index 90adb4882..173c12696 100644 --- a/nuttx/configs/stm32f4discovery/src/up_userleds.c +++ b/nuttx/configs/stm32f4discovery/src/up_userleds.c @@ -222,10 +222,10 @@ void stm32_setled(int led, bool ledon) void stm32_setleds(uint8_t ledset) { - stm32_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0); - stm32_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0); - stm32_gpiowrite(BOARD_LED3, (ledset & BOARD_LED3_BIT) == 0); - stm32_gpiowrite(BOARD_LED4, (ledset & BOARD_LED4_BIT) == 0); + stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) == 0); + stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) == 0); + stm32_gpiowrite(GPIO_LED3, (ledset & BOARD_LED3_BIT) == 0); + stm32_gpiowrite(GPIO_LED4, (ledset & BOARD_LED4_BIT) == 0); } /**************************************************************************** -- cgit v1.2.3 From 12af0cacd651e051a01db21092c6c3aff07ebd97 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 28 Jan 2013 17:43:55 +0000 Subject: Misc SYSLOG and STM32 serial fixes git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5576 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 11 ++++++- nuttx/arch/arm/src/stm32/stm32_serial.c | 12 ++++---- nuttx/configs/stm32f4discovery/README.txt | 32 +------------------- nuttx/fs/fs_syslog.c | 49 +++++++++++++++++++++---------- nuttx/libc/stdio/lib_syslogstream.c | 16 +++++----- 5 files changed, 61 insertions(+), 59 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index c2ce13738..039a79f62 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4057,4 +4057,13 @@ Serial was driver was not being built if there is no console device. Obviously, the serial driver may be needed even in this case. - + * arch/arm/src/stm32/stm32_serial.c: If there is a serial console, + it would be ttyS0 and the others would be ttyS1-5. If there + is not serial console, was labeling them ttyS1-6; now labels them + ttyS0-5. + * fs/fs_syslog.c: Can't handle SYSLOG output to character device from + the IDLE task (because it can't block). syslog_putc now returns EOF + on failure and sets errno. Fixed some errors in error handling. + * libc/stdio/lib_syslogstream.c: Checking of return value from + syslog_putc was bogus. Switching to EOF for all errors solves + this. diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c index 0151bd247..12da1ee10 100644 --- a/nuttx/arch/arm/src/stm32/stm32_serial.c +++ b/nuttx/arch/arm/src/stm32/stm32_serial.c @@ -1998,7 +1998,8 @@ void up_serialinit(void) { #ifdef HAVE_UART char devname[16]; - unsigned i, j; + unsigned i; + unsigned minor = 0; #ifdef CONFIG_PM int ret; #endif @@ -2015,6 +2016,7 @@ void up_serialinit(void) #if CONSOLE_UART > 0 (void)uart_register("/dev/console", &uart_devs[CONSOLE_UART - 1]->dev); (void)uart_register("/dev/ttyS0", &uart_devs[CONSOLE_UART - 1]->dev); + minor = 1; /* If we need to re-initialise the console to enable DMA do that here. */ @@ -2028,19 +2030,19 @@ void up_serialinit(void) strcpy(devname, "/dev/ttySx"); - for (i = 0, j = 1; i < STM32_NUSART; i++) + for (i = 0; i < STM32_NUSART; i++) { - /* don't create a device for the console - we did that above */ + /* Don't create a device for the console - we did that above */ if ((uart_devs[i] == 0) || (uart_devs[i]->dev.isconsole)) { continue; } - /* register USARTs as devices in increasing order */ + /* Register USARTs as devices in increasing order */ - devname[9] = '0' + j++; + devname[9] = '0' + minor++; (void)uart_register(devname, &uart_devs[i]->dev); } #endif /* HAVE UART */ diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index e9c0e81c2..378509be8 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1254,40 +1254,10 @@ Where is one of the following: CONFIG_CDCACM=y : The CDC/ACM driver must be built CONFIG_CDCACM_CONSOLE=y : Enable the CDC/ACM USB console. - However, that configuration does not work. It fails early probably because - of some dependency on /dev/console before the USB connection is established. - - But there is a work around for this that works better (but has some side - effects). The following configuration will also create a NSH USB console - but this version will will use /dev/console. Instead, it will use the - normal /dev/ttyACM0 USB serial device for the console: - - CONFIG_STM32_OTGFS=y : STM32 OTG FS support - CONFIG_USART2_SERIAL_CONSOLE=n : Disable the USART2 console - CONFIG_USBDEV=y : USB device support must be enabled - CONFIG_CDCACM=y : The CDC/ACM driver must be built - CONFIG_CDCACM_CONSOLE=n : Don't use the CDC/ACM USB console. - CONFIG_NSH_USBCONSOLE=y : Instead use some other USB device for the console - - The particular USB device that is used is: - - CONFIG_NSH_USBCONDEV="/dev/ttyACM0" - - NOTE 1: When you first start the USB console, you have hit ENTER a few + NOTE: When you first start the USB console, you have hit ENTER a few times before NSH starts. The logic does this to prevent sending USB data before there is anything on the host side listening for USB serial input. - Now the side effects: - - NOTE 2. When any other device other than /dev/console is used for a user - interface, linefeeds (\n) will not be expanded to carriage return / - linefeeds (\r\n). You will need to set your terminal program to account - for this. - - NOTE 3: /dev/console still exists and still refers to the serial port. So - you can still use certain kinds of debug output (see include/debug.h, all - of the interfaces based on lib_lowprintf will work in this configuration). - 9. USB OTG FS Host Support. The following changes will enable support for a USB host on the STM32F4Discovery, including support for a mass storage class driver: diff --git a/nuttx/fs/fs_syslog.c b/nuttx/fs/fs_syslog.c index f348bdb03..ab6cec51e 100644 --- a/nuttx/fs/fs_syslog.c +++ b/nuttx/fs/fs_syslog.c @@ -42,6 +42,7 @@ #include #include +#include #include #include #include @@ -282,7 +283,7 @@ int syslog_initialize(void) if (!INODE_IS_DRIVER(inode)) #endif { - ret = ENXIO; + ret = -ENXIO; goto errout_with_inode; } @@ -290,7 +291,7 @@ int syslog_initialize(void) if (!inode->u.i_ops || !inode->u.i_ops->write) { - return -EACCES; + ret = -EACCES; goto errout_with_inode; } @@ -346,8 +347,8 @@ int syslog_initialize(void) return OK; errout_with_inode: - g_sysdev.sl_state = SYSLOG_FAILURE; inode_release(inode); + g_sysdev.sl_state = SYSLOG_FAILURE; return ret; } @@ -366,6 +367,8 @@ int syslog_initialize(void) int syslog_putc(int ch) { ssize_t nbytes; + uint8_t uch; + int errcode; int ret; /* Ignore any output: @@ -382,7 +385,10 @@ int syslog_putc(int ch) * (4) Any debug output generated from interrupt handlers. A disadvantage * of using the generic character device for the SYSLOG is that it * cannot handle debug output generated from interrupt level handlers. - * (5) If an irrecoverable failure occurred during initialization. In + * (5) Any debug output generated from the IDLE loop. The character + * driver interface is blocking and the IDLE thread is not permitted + * to block. + * (6) If an irrecoverable failure occurred during initialization. In * this case, we won't ever bother to try again (ever). * * NOTE: That the third case is different. It applies only to the thread @@ -390,11 +396,12 @@ int syslog_putc(int ch) * that is why that case is handled in syslog_semtake(). */ - /* Case (4) */ + /* Cases (4) and (5) */ - if (up_interrupt_context()) + if (up_interrupt_context() || getpid() == 0) { - return -ENOSYS; /* Not supported */ + errcode = ENOSYS; + goto errout_with_errcode; } /* We can save checks in the usual case: That after the SYSLOG device @@ -408,14 +415,16 @@ int syslog_putc(int ch) if (g_sysdev.sl_state == SYSLOG_UNINITIALIZED || g_sysdev.sl_state == SYSLOG_INITIALIZING) { - return -EAGAIN; /* Can't access the SYSLOG now... maybe next time? */ + errcode = EAGAIN; /* Can't access the SYSLOG now... maybe next time? */ + goto errout_with_errcode; } - /* Case (5) */ + /* Case (6) */ if (g_sysdev.sl_state == SYSLOG_FAILURE) { - return -ENXIO; /* There is no SYSLOG device */ + errcode = ENXIO; /* There is no SYSLOG device */ + goto errout_with_errcode; } /* syslog_initialize() is called as soon as enough of the operating @@ -443,7 +452,8 @@ int syslog_putc(int ch) if (ret < 0) { sched_unlock(); - return ret; + errcode = -ret; + goto errout_with_errcode; } } @@ -471,7 +481,8 @@ int syslog_putc(int ch) * way, we are outta here. */ - return ret; + errcode = -ret; + goto errout_with_errcode; } /* Pre-pend a newline with a carriage return. */ @@ -497,19 +508,27 @@ int syslog_putc(int ch) { /* Write the non-newline character (and don't flush) */ - nbytes = syslog_write(&ch, 1); + uch = (uint8_t)ch; + nbytes = syslog_write(&uch, 1); } syslog_givesem(); - /* Check if the write was successful */ + /* Check if the write was successful. If not, nbytes will be + * a negated errno value. + */ if (nbytes < 0) { - return nbytes; + errcode = -ret; + goto errout_with_errcode; } return ch; + +errout_with_errcode: + set_errno(errcode); + return EOF; } #endif /* CONFIG_SYSLOG && CONFIG_SYSLOG_CHAR */ diff --git a/nuttx/libc/stdio/lib_syslogstream.c b/nuttx/libc/stdio/lib_syslogstream.c index 5529c5de8..121227d3c 100644 --- a/nuttx/libc/stdio/lib_syslogstream.c +++ b/nuttx/libc/stdio/lib_syslogstream.c @@ -63,6 +63,7 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) { + int errcode; int ret; /* Try writing until the write was successful or until an irrecoverable @@ -71,22 +72,23 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) do { - /* Write the character to the supported logging device */ + /* Write the character to the supported logging device. On failure, + * syslog_putc returns EOF with the errno value set; + */ ret = syslog_putc(ch); - if (ret == OK) + if (ret != EOF) { this->nput++; return; } - /* On failure syslog_putc will return a negated errno value. The - * errno variable will not be set. The special value -EINTR means that - * syslog_putc() was awakened by a signal. This is not a real error and - * must be ignored in this context. + /* The special errno value -EINTR means that syslog_putc() was + * awakened by a signal. This is not a real error and must be + * ignored in this context. */ } - while (ret == -EINTR); + while (errno == -EINTR); } /**************************************************************************** -- cgit v1.2.3 From 433dae74225a98c5ed65834b8574eea90259e220 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 28 Jan 2013 18:45:09 +0000 Subject: Beginning of apps/system/usbmonitor (incomplete); more LM4F changes from JP git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5577 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 2 + apps/system/Kconfig | 4 + apps/system/Make.defs | 3 + apps/system/Makefile | 2 +- apps/system/free/README.txt | 6 -- apps/system/poweroff/README.txt | 5 - apps/system/ramtron/README.txt | 7 -- apps/system/sdcard/README.txt | 7 -- apps/system/sysinfo/README.txt | 6 -- apps/system/usbmonitor/Kconfig | 33 ++++++ apps/system/usbmonitor/Makefile | 116 ++++++++++++++++++++ apps/system/usbmonitor/usbmonitor.c | 162 ++++++++++++++++++++++++++++ nuttx/ChangeLog | 3 + nuttx/Documentation/README.html | 8 +- nuttx/README.txt | 12 +-- nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h | 18 ++-- nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h | 89 ++++++++++++++- 17 files changed, 421 insertions(+), 62 deletions(-) delete mode 100644 apps/system/free/README.txt delete mode 100644 apps/system/poweroff/README.txt delete mode 100644 apps/system/ramtron/README.txt delete mode 100644 apps/system/sdcard/README.txt delete mode 100644 apps/system/sysinfo/README.txt create mode 100644 apps/system/usbmonitor/Kconfig create mode 100644 apps/system/usbmonitor/Makefile create mode 100644 apps/system/usbmonitor/usbmonitor.c (limited to 'nuttx/arch') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 494ce34eb..778f1fcf2 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -495,3 +495,5 @@ * apps/examples/nettest and poll: Complete Kconfig files. * apps/examples/ostest/waitpid.c: Need to use WEXITSTATUS() to decode the correct exit status. + * system/usbmonitor: A daemon that can be used to monitor USB + trace outpout. diff --git a/apps/system/Kconfig b/apps/system/Kconfig index d4d434665..6c8651088 100644 --- a/apps/system/Kconfig +++ b/apps/system/Kconfig @@ -34,3 +34,7 @@ endmenu menu "Sysinfo" source "$APPSDIR/system/sysinfo/Kconfig" endmenu + +menu "USB Monitor" +source "$APPSDIR/system/usbmonitor/Kconfig" +endmenu diff --git a/apps/system/Make.defs b/apps/system/Make.defs index 3d10f84e5..3c679f112 100644 --- a/apps/system/Make.defs +++ b/apps/system/Make.defs @@ -66,3 +66,6 @@ ifeq ($(CONFIG_SYSTEM_SYSINFO),y) CONFIGURED_APPS += system/sysinfo endif +ifeq ($(CONFIG_SYSTEM_USBMONITOR),y) +CONFIGURED_APPS += system/usbmonitor +endif diff --git a/apps/system/Makefile b/apps/system/Makefile index 057fbcf77..f39eedec4 100644 --- a/apps/system/Makefile +++ b/apps/system/Makefile @@ -37,7 +37,7 @@ # Sub-directories containing system task -SUBDIRS = free i2c install readline poweroff ramtron sdcard sysinfo +SUBDIRS = free i2c install readline poweroff ramtron sdcard sysinfo usbmonitor # Create the list of installed runtime modules (INSTALLED_DIRS) diff --git a/apps/system/free/README.txt b/apps/system/free/README.txt deleted file mode 100644 index 1c2d380d4..000000000 --- a/apps/system/free/README.txt +++ /dev/null @@ -1,6 +0,0 @@ - -This application provides UNIX style memory free information. - - Source: NuttX - Author: Gregory Nutt - Date: 17. March 2011 diff --git a/apps/system/poweroff/README.txt b/apps/system/poweroff/README.txt deleted file mode 100644 index e02180e5a..000000000 --- a/apps/system/poweroff/README.txt +++ /dev/null @@ -1,5 +0,0 @@ - -This application provides poweroff command - - Source: NuttX - Date: 13. March 2011 diff --git a/apps/system/ramtron/README.txt b/apps/system/ramtron/README.txt deleted file mode 100644 index 152774b66..000000000 --- a/apps/system/ramtron/README.txt +++ /dev/null @@ -1,7 +0,0 @@ - -This application provides RAMTRON tool/lib to start, stop or to perform -RAMTRON custom operations. - - Source: NuttX - Author: Uros Platise - Date: 18. March 2011 diff --git a/apps/system/sdcard/README.txt b/apps/system/sdcard/README.txt deleted file mode 100644 index 332aa26cf..000000000 --- a/apps/system/sdcard/README.txt +++ /dev/null @@ -1,7 +0,0 @@ - -This application provides SDcard tool/lib to start, stop, eject or insert -a memory card. - - Source: NuttX - Author: Uros Platise - Date: 18. March 2011 diff --git a/apps/system/sysinfo/README.txt b/apps/system/sysinfo/README.txt deleted file mode 100644 index 3792f4a59..000000000 --- a/apps/system/sysinfo/README.txt +++ /dev/null @@ -1,6 +0,0 @@ - -This application provides access to System Information - - Source: NuttX - Date: 15. April 2011 - Author: Uros Platise diff --git a/apps/system/usbmonitor/Kconfig b/apps/system/usbmonitor/Kconfig new file mode 100644 index 000000000..7199845b1 --- /dev/null +++ b/apps/system/usbmonitor/Kconfig @@ -0,0 +1,33 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config SYSTEM_USBMONITOR + bool "USB Monitor" + default n + depends on USBDEV && USBDEV_TRACE && SYSLOG + ---help--- + If USB device tracing is enabled (USBDEV_TRACE), then this option + will select the USB monitor. The USB monitor is a daemon that will + periodically collect the buffered USB trace data and dump it to the + SYSLOG device. + +if SYSTEM_USBMONITOR + +config SYSTEM_USBMONITOR_STACKSIZE + int "USB Monitor Stack Size" + default 2048 + depends on NSH_BUILTIN_APPS + ---help--- + The stack size to use the the USB monitor daemon. Default: 2048 + +config SYSTEM_USBMONITOR_PRIORITY + int "USB Monitor Stack Size" + default 50 + depends on NSH_BUILTIN_APPS + ---help--- + The priority to use the the USB monitor daemon. Default: 50 + +endif + diff --git a/apps/system/usbmonitor/Makefile b/apps/system/usbmonitor/Makefile new file mode 100644 index 000000000..04fcaf0ac --- /dev/null +++ b/apps/system/usbmonitor/Makefile @@ -0,0 +1,116 @@ +############################################################################ +# apps/system/usbmonitor/Makefile +# +# Copyright (C) 2013 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 NuttX 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +ifeq ($(WINTOOL),y) +INCDIROPT = -w +endif + +# Hello Application +# TODO: appname can be automatically extracted from the directory name + +APPNAME = usbmon +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 768 + +ASRCS = +CSRCS = usbmonitor.c + +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + BIN = ..\..\libapps$(LIBEXT) +else +ifeq ($(WINTOOL),y) + BIN = ..\\..\\libapps$(LIBEXT) +else + BIN = ../../libapps$(LIBEXT) +endif +endif + +ROOTDEPPATH = --dep-path . + +# Common build + +VPATH = + +all: .built +.PHONY: context depend clean distclean + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +.built: $(OBJS) + $(call ARCHIVE, $(BIN), $(OBJS)) + $(Q) touch .built + +# Register application + +ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) +$(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat: $(DEPCONFIG) Makefile + $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) + +context: $(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat +else +context: +endif + +# Create dependencies + +.depend: Makefile $(SRCS) + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ + +depend: .depend + +clean: + $(call DELFILE, .built) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep diff --git a/apps/system/usbmonitor/usbmonitor.c b/apps/system/usbmonitor/usbmonitor.c new file mode 100644 index 000000000..b101b128c --- /dev/null +++ b/apps/system/usbmonitor/usbmonitor.c @@ -0,0 +1,162 @@ +/**************************************************************************** + * apps/system/free/free.c + * + * Copyright (C) 2013 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 NuttX 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 + +/**************************************************************************** + * Private Typs + ****************************************************************************/ + +struct usbmon_state_s +{ +#ifdef CONFIG_NSH_BUILTIN_APPS + volatile bool started; + volatile bool stop; + pid_t pid; +#endif +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct usbmon_state_s g_usbmonitor; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int usbmonitor_daemon(int argc, char **argv) +{ +#ifdef CONFIG_NSH_BUILTIN_APPS + print("USB Monitor running: %d\n", g_usbmonitor.pid); +#endif + +#ifdef CONFIG_NSH_BUILTIN_APPS + /* If we are running as an NSH command, then loop until we detect that + * there is a request to stop. + */ + + while (!g_usbmonitor.stop) +#else + /* If we are running as a standalone program, then loop forever */ + + for (;;) +#endif + { +#warning "Missing logic" + } + + /* Stopped */ + +#ifdef CONFIG_NSH_BUILTIN_APPS + g_usbmonitor.stop = false; + g_usbmonitor.started = false; + print("USB Monitor stopped: %d\n", g_usbmonitor.pid); +#endif + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int usbmonitor_main(int argc, char **argv) +{ +#ifdef CONFIG_NSH_BUILTIN_APPS + /* Has the monitor already started? */ + + sched_lock(); + if (!g_usbmonitor.started) + { + int ret; + + /* No.. start it now */ + + g_usbmonitor.started = true; + g_usbmonitor.stop = false; + + ret = TASK_CREATE("USB Monitor", CONFIG_SYSTEM_USBMONITOR_PRIORITY, + CONFIG_SYSTEM_USBMONITOR_STACKSIZE, + (main_t)usbmonitor_daemon, (const char **)NULL); + if (ret < 0) + { + int errcode = errno; + fprintf(stderr, "ERROR: Failed to start the USB monitor: %d\n", + errcode); + } + else + { + g_usbmonitor.pid = ret; + print("USB Monitor started: %d\n", g_usbmonitor.pid); + } + + sched_unlock(); + return 0; + } + + sched_unlock(); + print("USB Monitor running: %d\n", g_usbmonitor.pid); + return 0; +#else + return usbmonitor_daemon(argc, argv); +#endif +} + +#ifdef CONFIG_NSH_BUILTIN_APPS +int usbmonitor_stop(int argc, char **argv) +{ + /* Has the monitor already started? */ + + if (g_usbmonitor.started) + { + print("USB Monitor stopping: %d\n", g_usbmonitor.pid); + g_usbmonitor.stop = true; + return 0; + } + + print("USB Monitor stopped: %d\n", g_usbmonitor.pid); + return 0; +} +#endif + diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 039a79f62..759177fca 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4067,3 +4067,6 @@ * libc/stdio/lib_syslogstream.c: Checking of return value from syslog_putc was bogus. Switching to EOF for all errors solves this. + * arch/arm/src/lm/chip/lm4f_memorymap.h: More LM4F changes from + Jose Pablo Carballo. + diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html index 281b738b8..44b663188 100644 --- a/nuttx/Documentation/README.html +++ b/nuttx/Documentation/README.html @@ -278,13 +278,7 @@ | | `- README.txt | `- system/ | |- i2c/README.txt - | |- free/README.txt - | |- install/README.txt - | |- poweroff/README.txt - | |- ramtron/README.txt - | |- sdcard/README.txt - | |- sysinfo/README.txt - | `- README.txt + | `- install/README.txt `- NxWidgets |- Doxygen | `- README.txt diff --git a/nuttx/README.txt b/nuttx/README.txt index c597091dc..340087791 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -1181,17 +1181,9 @@ apps |- NxWidgets/ | `- README.txt |- system/ - | |- i2c/README.txt - | |- free/README.txt - | |- install + | |- i2c | | `- README.txt - | |- poweroff - | | `- README.txt - | |- ramtron - | | `- README.txt - | |- sdcard - | | `- README.txt - | `- sysinfo + | `- install | `- README.txt `- README.txt diff --git a/nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h b/nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h index 32b7a9f18..8caeada17 100644 --- a/nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h +++ b/nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h @@ -58,7 +58,7 @@ /* -0x3fffffff: Reserved */ # define LM_PERIPH_BASE 0x40000000 /* -0x4001ffff: FiRM Peripherals */ /* -0x41ffffff: Peripherals */ -# define LM_APERIPH_BASE 0x42000000 /* -0x43ffffff: Bit-band alise of 40000000- */ +# define LM_APERIPH_BASE 0x42000000 /* -0x43ffffff: Bit-band alias of 40000000- */ /* -0xdfffffff: Reserved */ # define LM_ITM_BASE 0xe0000000 /* -0xe0000fff: Instrumentation Trace Macrocell */ # define LM_DWT_BASE 0xe0001000 /* -0xe0001fff: Data Watchpoint and Trace */ @@ -327,19 +327,19 @@ /* -0x57fff: Reserved */ # define LM_GPIOAAHB_BASE (LM_PERIPH_BASE + 0x58000) /* -0x58fff: GPIO Port A (AHB aperture) */ # define LM_GPIOBAHB_BASE (LM_PERIPH_BASE + 0x59000) /* -0x59fff: GPIO Port B (AHB aperture) */ -# define LM_GPIOCAHB_BASE (LM_PERIPH_BASE + 0x5A000) /* -0x5afff: GPIO Port C (AHB aperture) */ -# define LM_GPIODAHB_BASE (LM_PERIPH_BASE + 0x5B000) /* -0x5bfff: GPIO Port D (AHB aperture) */ -# define LM_GPIOEAHB_BASE (LM_PERIPH_BASE + 0x5C000) /* -0x5cfff: GPIO Port E (AHB aperture) */ -# define LM_GPIOFAHB_BASE (LM_PERIPH_BASE + 0x5D000) /* -0x5dfff: GPIO Port F (AHB aperture) */ -# define LM_GPIOGAHB_BASE (LM_PERIPH_BASE + 0x5E000) /* -0x5efff: GPIO Port G (AHB aperture) */ -# define LM_GPIOHAHB_BASE (LM_PERIPH_BASE + 0x5F000) /* -0x5ffff: GPIO Port H (AHB aperture) */ +# define LM_GPIOCAHB_BASE (LM_PERIPH_BASE + 0x5a000) /* -0x5afff: GPIO Port C (AHB aperture) */ +# define LM_GPIODAHB_BASE (LM_PERIPH_BASE + 0x5b000) /* -0x5bfff: GPIO Port D (AHB aperture) */ +# define LM_GPIOEAHB_BASE (LM_PERIPH_BASE + 0x5c000) /* -0x5cfff: GPIO Port E (AHB aperture) */ +# define LM_GPIOFAHB_BASE (LM_PERIPH_BASE + 0x5d000) /* -0x5dfff: GPIO Port F (AHB aperture) */ +# define LM_GPIOGAHB_BASE (LM_PERIPH_BASE + 0x5e000) /* -0x5efff: GPIO Port G (AHB aperture) */ +# define LM_GPIOHAHB_BASE (LM_PERIPH_BASE + 0x5f000) /* -0x5ffff: GPIO Port H (AHB aperture) */ # define LM_GPIOJAHB_BASE (LM_PERIPH_BASE + 0x60000) /* -0x60fff: GPIO Port J (AHB aperture) */ /* -0xcffff: Reserved */ -# define LM_EPI0_BASE (LM_PERIPH_BASE + 0xD0000) /* -0xd0fff: EPI 0 */ +# define LM_EPI0_BASE (LM_PERIPH_BASE + 0xd0000) /* -0xd0fff: EPI 0 */ /* -0xfcfff: Reserved */ # define LM_FLASHCON_BASE (LM_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */ # define LM_SYSCON_BASE (LM_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */ -# define LM_UDMA_BASE (LM_PERIPH_BASE + 0xff000) /* -0xfffff: System Control */ +# define LM_UDMA_BASE (LM_PERIPH_BASE + 0xff000) /* -0xfffff: Micro Direct Memory Access */ /* -0x1ffffff: Reserved */ #else # error "Peripheral base addresses not specified for this Stellaris chip" diff --git a/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h index 6963545fe..c8c62d4b4 100644 --- a/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h +++ b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h @@ -1,5 +1,5 @@ /************************************************************************************ - * arch/arm/src/lm/chip/lm3s_memorymap.h + * arch/arm/src/lm/chip/lm4f_memorymap.h * * Copyright (C) 2013 Gregory Nutt. All rights reserved. * Authors: Gregory Nutt @@ -55,9 +55,21 @@ # define LM_ROM_BASE 0x01000000 /* -0x1fffffff: Reserved for ROM */ # define LM_SRAM_BASE 0x20000000 /* -0x20007fff: Bit-banded on-chip SRAM */ /* -0x21ffffff: Reserved */ -/* @TODO */ -#endif - +# define LM_ASRAM_BASE 0x22000000 /* -0x220fffff: Bit-band alias of 20000000- */ + /* -0x3fffffff: Reserved */ +# define LM_PERIPH_BASE 0x40000000 /* -0x4001ffff: FiRM Peripherals */ + /* -0x41ffffff: Peripherals */ +# define LM_APERIPH_BASE 0x42000000 /* -0x43ffffff: Bit-band alias of 40000000- */ + /* -0xdfffffff: Reserved */ +# define LM_ITM_BASE 0xe0000000 /* -0xe0000fff: Instrumentation Trace Macrocell */ +# define LM_DWT_BASE 0xe0001000 /* -0xe0001fff: Data Watchpoint and Trace */ +# define LM_FPB_BASE 0xe0002000 /* -0xe0002fff: Flash Patch and Breakpoint */ + /* -0xe000dfff: Reserved */ +# define LM_NVIC_BASE 0xe000e000 /* -0xe000efff: Nested Vectored Interrupt Controller */ + /* -0xe003ffff: Reserved */ +# define LM_TPIU_BASE 0xe0040000 /* -0xe0040fff: Trace Port Interface Unit */ +# define LM_ETM_BASE 0xe0041000 /* -0xe0041fff: Embedded Trace Macrocell */ + /* -0xffffffff: Reserved */ #else # error "Memory map not specified for this LM4F chip" #endif @@ -65,6 +77,75 @@ /* Peripheral base addresses ********************************************************/ #if defined(CONFIG_ARCH_CHIP_LM4F120) +/* FiRM Peripheral Base Addresses */ + +# define LM_WDOG0_BASE (LM_PERIPH_BASE + 0x00000) /* -0x00fff: Watchdog Timer 0 */ +# define LM_WDOG1_BASE (LM_PERIPH_BASE + 0x01000) /* -0x00fff: Watchdog Timer 1 */ + /* -0x03fff: Reserved */ +# define LM_GPIOA_BASE (LM_PERIPH_BASE + 0x04000) /* -0x04fff: GPIO Port A */ +# define LM_GPIOB_BASE (LM_PERIPH_BASE + 0x05000) /* -0x05fff: GPIO Port B */ +# define LM_GPIOC_BASE (LM_PERIPH_BASE + 0x06000) /* -0x06fff: GPIO Port C */ +# define LM_GPIOD_BASE (LM_PERIPH_BASE + 0x07000) /* -0x07fff: GPIO Port D */ +# define LM_SSI0_BASE (LM_PERIPH_BASE + 0x08000) /* -0x08fff: SSI0 */ +# define LM_SSI1_BASE (LM_PERIPH_BASE + 0x09000) /* -0x09fff: SSI1 */ +# define LM_SSI2_BASE (LM_PERIPH_BASE + 0x0a000) /* -0x0afff: SSI2 */ +# define LM_SSI3_BASE (LM_PERIPH_BASE + 0x0b000) /* -0x0bfff: SSI3 */ +# define LM_UART0_BASE (LM_PERIPH_BASE + 0x0c000) /* -0x0cfff: UART0 */ +# define LM_UART1_BASE (LM_PERIPH_BASE + 0x0d000) /* -0x0dfff: UART1 */ +# define LM_UART2_BASE (LM_PERIPH_BASE + 0x0e000) /* -0x0efff: UART2 */ +# define LM_UART3_BASE (LM_PERIPH_BASE + 0x0f000) /* -0x0ffff: UART3 */ +# define LM_UART4_BASE (LM_PERIPH_BASE + 0x10000) /* -0x10fff: UART4 */ +# define LM_UART5_BASE (LM_PERIPH_BASE + 0x11000) /* -0x11fff: UART5 */ +# define LM_UART6_BASE (LM_PERIPH_BASE + 0x12000) /* -0x12fff: UART6 */ +# define LM_UART7_BASE (LM_PERIPH_BASE + 0x13000) /* -0x13fff: UART7 */ + /* -0x1ffff: Reserved */ +/* Peripheral Base Addresses */ + +# define LM_I2CM0_BASE (LM_PERIPH_BASE + 0x20000) /* -0x207ff: I2C Master 0 */ +# define LM_I2CS0_BASE (LM_PERIPH_BASE + 0x20800) /* -0x20fbf: I2C Slave 0 */ +# define LM_I2CSC0_BASE (LM_PERIPH_BASE + 0x20fc0) /* -0x20fff: I2C Status and Control 0 */ +# define LM_I2CM1_BASE (LM_PERIPH_BASE + 0x21000) /* -0x217ff: I2C Master 1 */ +# define LM_I2CS1_BASE (LM_PERIPH_BASE + 0x21800) /* -0x21fbf: I2C Slave 1 */ +# define LM_I2CSC1_BASE (LM_PERIPH_BASE + 0x21fc0) /* -0x21fff: I2C Status and Control 1 */ +# define LM_I2CM2_BASE (LM_PERIPH_BASE + 0x22000) /* -0x227ff: I2C Master 2 */ +# define LM_I2CS2_BASE (LM_PERIPH_BASE + 0x22800) /* -0x22fbf: I2C Slave 2 */ +# define LM_I2CSC2_BASE (LM_PERIPH_BASE + 0x22fc0) /* -0x22fff: I2C Status and Control 2 */ +# define LM_I2CM3_BASE (LM_PERIPH_BASE + 0x23000) /* -0x237ff: I2C Master 3 */ +# define LM_I2CS3_BASE (LM_PERIPH_BASE + 0x23800) /* -0x23fbf: I2C Slave 3 */ +# define LM_I2CSC3_BASE (LM_PERIPH_BASE + 0x23fc0) /* -0x23fff: I2C Status and Control 3 */ +# define LM_GPIOE_BASE (LM_PERIPH_BASE + 0x24000) /* -0x24fff: GPIO Port E */ +# define LM_GPIOF_BASE (LM_PERIPH_BASE + 0x25000) /* -0x25fff: GPIO Port F */ + /* -0x2ffff: Reserved */ +# define LM_TIMER0_BASE (LM_PERIPH_BASE + 0x30000) /* -0x30fff: 16/32 Timer 0 */ +# define LM_TIMER1_BASE (LM_PERIPH_BASE + 0x31000) /* -0x31fff: 16/32 Timer 1 */ +# define LM_TIMER2_BASE (LM_PERIPH_BASE + 0x32000) /* -0x32fff: 16/32 Timer 2 */ +# define LM_TIMER3_BASE (LM_PERIPH_BASE + 0x33000) /* -0x33fff: 16/32 Timer 3 */ +# define LM_TIMER4_BASE (LM_PERIPH_BASE + 0x34000) /* -0x34fff: 16/32 Timer 4 */ +# define LM_TIMER5_BASE (LM_PERIPH_BASE + 0x35000) /* -0x35fff: 16/32 Timer 5 */ +# define LM_WTIMER0_BASE (LM_PERIPH_BASE + 0x36000) /* -0x36fff: 32/64 Wide Timer 0 */ +# define LM_WTIMER1_BASE (LM_PERIPH_BASE + 0x37000) /* -0x37fff: 32/64 Wide Timer 1 */ +# define LM_ADC0_BASE (LM_PERIPH_BASE + 0x38000) /* -0x38fff: ADC 0 */ +# define LM_ADC1_BASE (LM_PERIPH_BASE + 0x39000) /* -0x39fff: ADC 1 */ + /* -0x3bfff: Reserved */ +# define LM_COMPARE_BASE (LM_PERIPH_BASE + 0x3c000) /* -0x3cfff: Analog Comparators */ + /* -0x43fff: Reserved */ +# define LM_CANCON_BASE (LM_PERIPH_BASE + 0x40000) /* -0x40fff: CAN Controller */ + /* -0x4bfff: Reserved */ +# define LM_WTIMER2_BASE (LM_PERIPH_BASE + 0x4c000) /* -0x4cfff: 32/64 Wide Timer 2 */ +# define LM_WTIMER3_BASE (LM_PERIPH_BASE + 0x4d000) /* -0x4dfff: 32/64 Wide Timer 3 */ +# define LM_WTIMER4_BASE (LM_PERIPH_BASE + 0x4e000) /* -0x4efff: 32/64 Wide Timer 4 */ +# define LM_WTIMER5_BASE (LM_PERIPH_BASE + 0x4f000) /* -0x4ffff: 32/64 Wide Timer 5 */ +# define LM_USB_BASE (LM_PERIPH_BASE + 0x50000) /* -0x50fff: USB */ + /* -0x57fff: Reserved */ +# define LM_GPIOAAHB_BASE (LM_PERIPH_BASE + 0x58000) /* -0x58fff: GPIO Port A (AHB aperture) */ +# define LM_GPIOBAHB_BASE (LM_PERIPH_BASE + 0x59000) /* -0x59fff: GPIO Port B (AHB aperture) */ +# define LM_GPIOCAHB_BASE (LM_PERIPH_BASE + 0x5A000) /* -0x5afff: GPIO Port C (AHB aperture) */ +# define LM_GPIODAHB_BASE (LM_PERIPH_BASE + 0x5B000) /* -0x5bfff: GPIO Port D (AHB aperture) */ +# define LM_GPIOEAHB_BASE (LM_PERIPH_BASE + 0x5C000) /* -0x5cfff: GPIO Port E (AHB aperture) */ +# define LM_GPIOFAHB_BASE (LM_PERIPH_BASE + 0x5D000) /* -0x5dfff: GPIO Port F (AHB aperture) */ + /* -0xaefff: Reserved */ +# define LM_EEPROM_BASE (LM_PERIPH_BASE + 0xaf000) /* -0xaffff: EEPROM and Key Locker */ + /* -0xf8fff: Reserved */ /* @TODO */ #else # error "Peripheral base addresses not specified for this Stellaris chip" -- cgit v1.2.3 From 79ccfa4ae6db4b085703b12c8f6846716fc69df7 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 28 Jan 2013 21:55:16 +0000 Subject: Add syslog.h; rename lib_rawprintf() to syslog() git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5578 42af7a65-404d-4744-a932-0658087f49c3 --- .../UnitTests/CButtonArray/cbuttonarraytest.hxx | 4 +- NxWidgets/UnitTests/CCheckBox/ccheckboxtest.hxx | 4 +- .../UnitTests/CGlyphButton/cglyphbuttontest.hxx | 4 +- NxWidgets/UnitTests/CImage/cimagetest.hxx | 4 +- NxWidgets/UnitTests/CKeypad/ckeypadtest.hxx | 4 +- .../CLatchButtonArray/clatchbuttonarraytest.hxx | 4 +- NxWidgets/UnitTests/CListBox/clistboxtest.hxx | 4 +- .../UnitTests/CProgressBar/cprogressbartest.hxx | 4 +- .../UnitTests/CRadioButton/cradiobuttontest.hxx | 4 +- .../cscrollbarhorizontaltest.hxx | 4 +- .../CScrollbarVertical/cscrollbarverticaltest.hxx | 4 +- .../CSliderHorizonal/csliderhorizontaltest.hxx | 4 +- .../CSliderVertical/csliderverticaltest.hxx | 4 +- apps/examples/adc/adc.h | 4 +- apps/examples/buttons/buttons_main.c | 28 ++-- apps/examples/can/can.h | 4 +- apps/examples/cdcacm/cdcacm.h | 4 +- apps/examples/composite/composite.h | 4 +- apps/examples/igmp/igmp.h | 6 +- apps/examples/nettest/nettest.h | 6 +- apps/examples/nx/nx_internal.h | 4 +- apps/examples/nxconsole/nxcon_internal.h | 4 +- apps/examples/nxffs/nxffs_main.c | 2 +- apps/examples/nxhello/nxhello.h | 4 +- apps/examples/nximage/nximage.h | 4 +- apps/examples/nxlines/nxlines.h | 4 +- apps/examples/nxtext/nxtext_internal.h | 4 +- apps/examples/poll/poll_internal.h | 6 +- apps/examples/pwm/pwm.h | 4 +- apps/examples/qencoder/qe.h | 4 +- apps/examples/thttpd/thttpd_main.c | 4 +- apps/examples/touchscreen/tc.h | 4 +- apps/examples/udp/udp-internal.h | 4 +- apps/examples/uip/uip_main.c | 4 +- apps/examples/usbserial/usbserial_main.c | 8 +- apps/examples/usbstorage/usbmsc.h | 4 +- apps/examples/usbterm/usbterm.h | 8 +- apps/examples/watchdog/watchdog.h | 4 +- apps/include/usbmonitor.h | 96 +++++++++++++ apps/nshlib/nsh_usbdev.c | 2 +- apps/system/usbmonitor/Makefile | 4 +- apps/system/usbmonitor/usbmonitor.c | 68 ++++----- misc/tools/README.txt | 4 +- nuttx/Documentation/NuttxPortingGuide.html | 10 +- nuttx/Kconfig | 5 +- nuttx/TODO | 17 +-- nuttx/arch/arm/src/arm/up_assert.c | 4 +- nuttx/arch/arm/src/arm/up_dataabort.c | 2 +- nuttx/arch/arm/src/arm/up_prefetchabort.c | 2 +- nuttx/arch/arm/src/arm/up_syscall.c | 2 +- nuttx/arch/arm/src/arm/up_undefinedinsn.c | 2 +- nuttx/arch/arm/src/armv7-m/up_assert.c | 4 +- nuttx/arch/arm/src/dm320/dm320_decodeirq.c | 2 +- nuttx/arch/arm/src/imx/imx_decodeirq.c | 2 +- nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c | 2 +- nuttx/arch/arm/src/lpc2378/lpc23xx_decodeirq.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c | 2 +- nuttx/arch/arm/src/stm32/stm32_i2c.c | 6 +- nuttx/arch/arm/src/str71x/str71x_decodeirq.c | 2 +- nuttx/arch/avr/src/avr/up_dumpstate.c | 2 +- nuttx/arch/avr/src/avr32/up_dumpstate.c | 2 +- nuttx/arch/avr/src/common/up_assert.c | 4 +- nuttx/arch/hc/src/m9s12/m9s12_assert.c | 4 +- nuttx/arch/mips/src/mips32/up_assert.c | 4 +- nuttx/arch/mips/src/mips32/up_dumpstate.c | 2 +- nuttx/arch/sh/src/common/up_assert.c | 2 +- nuttx/arch/sh/src/m16c/m16c_dumpstate.c | 2 +- nuttx/arch/sh/src/sh1/sh1_dumpstate.c | 2 +- nuttx/arch/sim/src/up_initialize.c | 4 +- nuttx/arch/sim/src/up_tapdev.c | 26 ++-- nuttx/arch/x86/src/common/up_assert.c | 4 +- nuttx/arch/x86/src/i486/up_regdump.c | 2 +- nuttx/arch/z16/src/common/up_assert.c | 2 +- nuttx/arch/z16/src/common/up_registerdump.c | 2 +- nuttx/arch/z16/src/common/up_stackdump.c | 2 +- nuttx/arch/z16/src/z16f/z16f_sysexec.c | 4 +- nuttx/arch/z80/src/common/up_assert.c | 2 +- nuttx/arch/z80/src/common/up_doirq.c | 2 +- nuttx/arch/z80/src/common/up_stackdump.c | 2 +- nuttx/arch/z80/src/ez80/ez80_registerdump.c | 2 +- nuttx/arch/z80/src/z180/z180_registerdump.c | 2 +- nuttx/arch/z80/src/z8/z8_registerdump.c | 2 +- nuttx/arch/z80/src/z80/z80_registerdump.c | 2 +- nuttx/binfmt/libelf/libelf_read.c | 2 +- nuttx/binfmt/libnxflat/libnxflat_read.c | 2 +- nuttx/configs/README.txt | 2 +- nuttx/configs/cloudctrl/src/up_nsh.c | 4 +- nuttx/configs/cloudctrl/src/up_usbmsc.c | 4 +- nuttx/configs/demo9s12ne64/src/up_nsh.c | 4 +- nuttx/configs/ea3131/src/up_nsh.c | 4 +- nuttx/configs/ea3131/src/up_usbmsc.c | 4 +- nuttx/configs/ea3152/src/up_nsh.c | 4 +- nuttx/configs/ea3152/src/up_usbmsc.c | 4 +- nuttx/configs/eagle100/src/up_nsh.c | 4 +- nuttx/configs/ekk-lm3s9b96/src/up_nsh.c | 4 +- nuttx/configs/ez80f910200kitg/ostest/defconfig | 2 +- nuttx/configs/ez80f910200zco/ostest/defconfig | 2 +- nuttx/configs/fire-stm32v2/src/up_composite.c | 4 +- nuttx/configs/fire-stm32v2/src/up_nsh.c | 4 +- nuttx/configs/fire-stm32v2/src/up_usbmsc.c | 4 +- nuttx/configs/hymini-stm32v/src/up_nsh.c | 4 +- nuttx/configs/hymini-stm32v/src/up_usbmsc.c | 4 +- nuttx/configs/kwikstik-k40/src/up_nsh.c | 4 +- nuttx/configs/kwikstik-k40/src/up_usbmsc.c | 4 +- nuttx/configs/lincoln60/src/up_nsh.c | 4 +- nuttx/configs/lm3s6432-s2e/src/up_nsh.c | 4 +- nuttx/configs/lm3s6965-ek/src/up_nsh.c | 4 +- nuttx/configs/lm3s8962-ek/src/up_nsh.c | 4 +- nuttx/configs/lpcxpresso-lpc1768/src/up_nsh.c | 4 +- nuttx/configs/lpcxpresso-lpc1768/src/up_usbmsc.c | 4 +- nuttx/configs/mbed/src/up_nsh.c | 4 +- nuttx/configs/mcu123-lpc214x/src/up_composite.c | 4 +- nuttx/configs/mcu123-lpc214x/src/up_nsh.c | 4 +- nuttx/configs/mcu123-lpc214x/src/up_usbmsc.c | 4 +- nuttx/configs/ne64badge/src/up_nsh.c | 4 +- nuttx/configs/nucleus2g/src/up_nsh.c | 4 +- nuttx/configs/nucleus2g/src/up_usbmsc.c | 4 +- nuttx/configs/olimex-lpc1766stk/src/up_nsh.c | 4 +- nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c | 4 +- nuttx/configs/olimex-lpc2378/src/up_nsh.c | 4 +- nuttx/configs/olimex-strp711/src/up_nsh.c | 4 +- nuttx/configs/pic32-starterkit/src/up_nsh.c | 4 +- nuttx/configs/pic32-starterkit/src/up_usbmsc.c | 4 +- nuttx/configs/pic32mx7mmb/src/up_nsh.c | 4 +- nuttx/configs/pic32mx7mmb/src/up_usbmsc.c | 4 +- nuttx/configs/rgmp/include/README.txt | 2 +- nuttx/configs/rgmp/src/README.txt | 2 +- nuttx/configs/sam3u-ek/src/up_nsh.c | 4 +- nuttx/configs/sam3u-ek/src/up_usbmsc.c | 4 +- nuttx/configs/shenzhou/src/up_composite.c | 4 +- nuttx/configs/shenzhou/src/up_ili93xx.c | 6 +- nuttx/configs/shenzhou/src/up_nsh.c | 4 +- nuttx/configs/shenzhou/src/up_usbmsc.c | 4 +- nuttx/configs/sim/cxxtest/defconfig | 2 +- nuttx/configs/sim/ostest/defconfig | 2 +- nuttx/configs/stm3210e-eval/src/up_composite.c | 4 +- nuttx/configs/stm3210e-eval/src/up_lcd.c | 6 +- nuttx/configs/stm3210e-eval/src/up_nsh.c | 4 +- nuttx/configs/stm3210e-eval/src/up_pmbuttons.c | 6 +- nuttx/configs/stm3210e-eval/src/up_usbmsc.c | 4 +- nuttx/configs/stm3220g-eval/src/up_lcd.c | 6 +- nuttx/configs/stm3220g-eval/src/up_nsh.c | 4 +- nuttx/configs/stm3240g-eval/discover/defconfig | 2 +- nuttx/configs/stm3240g-eval/src/up_lcd.c | 6 +- nuttx/configs/stm3240g-eval/src/up_nsh.c | 4 +- nuttx/configs/stm3240g-eval/xmlrpc/defconfig | 2 +- nuttx/configs/stm32f4discovery/src/up_nsh.c | 4 +- nuttx/configs/stm32f4discovery/src/up_pmbuttons.c | 2 +- nuttx/configs/sure-pic32mx/src/up_nsh.c | 4 +- nuttx/configs/teensy/src/up_usbmsc.c | 4 +- nuttx/configs/twr-k60n512/src/up_nsh.c | 4 +- nuttx/configs/twr-k60n512/src/up_usbmsc.c | 4 +- nuttx/configs/ubw32/src/up_nsh.c | 4 +- nuttx/configs/vsn/src/usbmsc.c | 4 +- nuttx/configs/vsn/src/vsn.h | 4 +- nuttx/configs/z16f2800100zcog/ostest/defconfig | 2 +- nuttx/configs/z16f2800100zcog/pashello/README.txt | 24 ++-- nuttx/configs/z16f2800100zcog/pashello/defconfig | 2 +- nuttx/configs/z8encore000zco/ostest/defconfig | 2 +- nuttx/configs/z8f64200100kit/ostest/defconfig | 2 +- nuttx/drivers/lcd/mio283qt2.c | 6 +- nuttx/drivers/lcd/ssd1289.c | 6 +- nuttx/drivers/mmcsd/mmcsd_debug.c | 4 +- nuttx/drivers/net/enc28j60.c | 96 ++++++------- nuttx/drivers/syslog/ramlog.c | 6 +- nuttx/drivers/usbdev/usbdev_trace.c | 4 +- nuttx/drivers/usbdev/usbmsc.h | 8 +- nuttx/fs/fs_syslog.c | 6 +- nuttx/fs/nxffs/nxffs_dump.c | 2 +- nuttx/include/debug.h | 37 ++--- nuttx/include/nuttx/syslog.h | 6 +- nuttx/include/syslog.h | 94 +++++++++++++ nuttx/libc/lib.csv | 6 +- nuttx/libc/lib_internal.h | 12 +- nuttx/libc/misc/lib_dbg.c | 36 ++--- nuttx/libc/misc/lib_dumpbuffer.c | 8 +- nuttx/libc/stdio/Make.defs | 2 +- nuttx/libc/stdio/lib_lowprintf.c | 130 ----------------- nuttx/libc/stdio/lib_lowsyslog.c | 130 +++++++++++++++++ nuttx/libc/stdio/lib_printf.c | 4 +- nuttx/libc/stdio/lib_rawprintf.c | 154 --------------------- nuttx/libc/stdio/lib_syslog.c | 154 +++++++++++++++++++++ 182 files changed, 943 insertions(+), 786 deletions(-) create mode 100644 apps/include/usbmonitor.h create mode 100644 nuttx/include/syslog.h delete mode 100644 nuttx/libc/stdio/lib_lowprintf.c create mode 100644 nuttx/libc/stdio/lib_lowsyslog.c delete mode 100644 nuttx/libc/stdio/lib_rawprintf.c create mode 100644 nuttx/libc/stdio/lib_syslog.c (limited to 'nuttx/arch') diff --git a/NxWidgets/UnitTests/CButtonArray/cbuttonarraytest.hxx b/NxWidgets/UnitTests/CButtonArray/cbuttonarraytest.hxx index b8a9e15e5..1dc794a48 100644 --- a/NxWidgets/UnitTests/CButtonArray/cbuttonarraytest.hxx +++ b/NxWidgets/UnitTests/CButtonArray/cbuttonarraytest.hxx @@ -75,11 +75,11 @@ # define CONFIG_CBUTTONARRAYTEST_FONTCOLOR CONFIG_NXWIDGETS_DEFAULT_FONTCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CCheckBox/ccheckboxtest.hxx b/NxWidgets/UnitTests/CCheckBox/ccheckboxtest.hxx index 0397b37dd..58099acdf 100644 --- a/NxWidgets/UnitTests/CCheckBox/ccheckboxtest.hxx +++ b/NxWidgets/UnitTests/CCheckBox/ccheckboxtest.hxx @@ -69,11 +69,11 @@ # define CONFIG_CCHECKBOXTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CGlyphButton/cglyphbuttontest.hxx b/NxWidgets/UnitTests/CGlyphButton/cglyphbuttontest.hxx index b3e5bb656..2c21d4cb1 100644 --- a/NxWidgets/UnitTests/CGlyphButton/cglyphbuttontest.hxx +++ b/NxWidgets/UnitTests/CGlyphButton/cglyphbuttontest.hxx @@ -76,11 +76,11 @@ # define CONFIG_CGLYPHBUTTONTEST_FONTCOLOR CONFIG_NXWIDGETS_DEFAULT_FONTCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CImage/cimagetest.hxx b/NxWidgets/UnitTests/CImage/cimagetest.hxx index 9592f2936..5b5901bb1 100644 --- a/NxWidgets/UnitTests/CImage/cimagetest.hxx +++ b/NxWidgets/UnitTests/CImage/cimagetest.hxx @@ -71,11 +71,11 @@ # define CONFIG_CIMAGETEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CKeypad/ckeypadtest.hxx b/NxWidgets/UnitTests/CKeypad/ckeypadtest.hxx index d11c92375..12d7e18fa 100644 --- a/NxWidgets/UnitTests/CKeypad/ckeypadtest.hxx +++ b/NxWidgets/UnitTests/CKeypad/ckeypadtest.hxx @@ -72,11 +72,11 @@ # define CONFIG_CKEYPADTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CLatchButtonArray/clatchbuttonarraytest.hxx b/NxWidgets/UnitTests/CLatchButtonArray/clatchbuttonarraytest.hxx index 98c0a3bb3..80bf8fb71 100644 --- a/NxWidgets/UnitTests/CLatchButtonArray/clatchbuttonarraytest.hxx +++ b/NxWidgets/UnitTests/CLatchButtonArray/clatchbuttonarraytest.hxx @@ -75,11 +75,11 @@ # define CONFIG_CLATCHBUTTONARRAYTEST_FONTCOLOR CONFIG_NXWIDGETS_DEFAULT_FONTCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CListBox/clistboxtest.hxx b/NxWidgets/UnitTests/CListBox/clistboxtest.hxx index a19a2fabc..dfe179503 100644 --- a/NxWidgets/UnitTests/CListBox/clistboxtest.hxx +++ b/NxWidgets/UnitTests/CListBox/clistboxtest.hxx @@ -69,11 +69,11 @@ # define CONFIG_CLISTBOXTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CProgressBar/cprogressbartest.hxx b/NxWidgets/UnitTests/CProgressBar/cprogressbartest.hxx index a7a4238e7..2223d8081 100644 --- a/NxWidgets/UnitTests/CProgressBar/cprogressbartest.hxx +++ b/NxWidgets/UnitTests/CProgressBar/cprogressbartest.hxx @@ -69,11 +69,11 @@ # define CONFIG_CPROGRESSBARTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CRadioButton/cradiobuttontest.hxx b/NxWidgets/UnitTests/CRadioButton/cradiobuttontest.hxx index 540d5019b..3f81371db 100644 --- a/NxWidgets/UnitTests/CRadioButton/cradiobuttontest.hxx +++ b/NxWidgets/UnitTests/CRadioButton/cradiobuttontest.hxx @@ -70,11 +70,11 @@ # define CONFIG_CRADIOBUTTONTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CScrollbarHorizontal/cscrollbarhorizontaltest.hxx b/NxWidgets/UnitTests/CScrollbarHorizontal/cscrollbarhorizontaltest.hxx index 774225091..30f66ca45 100644 --- a/NxWidgets/UnitTests/CScrollbarHorizontal/cscrollbarhorizontaltest.hxx +++ b/NxWidgets/UnitTests/CScrollbarHorizontal/cscrollbarhorizontaltest.hxx @@ -69,11 +69,11 @@ # define CONFIG_CSCROLLBARHORIZONTALTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CScrollbarVertical/cscrollbarverticaltest.hxx b/NxWidgets/UnitTests/CScrollbarVertical/cscrollbarverticaltest.hxx index 8b9fb1ee8..6323b0f26 100644 --- a/NxWidgets/UnitTests/CScrollbarVertical/cscrollbarverticaltest.hxx +++ b/NxWidgets/UnitTests/CScrollbarVertical/cscrollbarverticaltest.hxx @@ -69,11 +69,11 @@ # define CONFIG_CSCROLLBARVERTICALTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CSliderHorizonal/csliderhorizontaltest.hxx b/NxWidgets/UnitTests/CSliderHorizonal/csliderhorizontaltest.hxx index 9709a2b7c..fd333af5c 100644 --- a/NxWidgets/UnitTests/CSliderHorizonal/csliderhorizontaltest.hxx +++ b/NxWidgets/UnitTests/CSliderHorizonal/csliderhorizontaltest.hxx @@ -69,11 +69,11 @@ # define CONFIG_CSLIDERHORIZONTALTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/NxWidgets/UnitTests/CSliderVertical/csliderverticaltest.hxx b/NxWidgets/UnitTests/CSliderVertical/csliderverticaltest.hxx index 3bb174ba0..6a893e395 100644 --- a/NxWidgets/UnitTests/CSliderVertical/csliderverticaltest.hxx +++ b/NxWidgets/UnitTests/CSliderVertical/csliderverticaltest.hxx @@ -69,11 +69,11 @@ # define CONFIG_CSLIDERVERTICALTEST_BGCOLOR CONFIG_NXWIDGETS_DEFAULT_BACKGROUNDCOLOR #endif -// If debug is enabled, use the debug function, lib_rawprintf() instead +// If debug is enabled, use the debug function, syslog() instead // of printf() so that the output is synchronized. #ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog #else # define message printf #endif diff --git a/apps/examples/adc/adc.h b/apps/examples/adc/adc.h index 9f79db92a..2d8af87e1 100644 --- a/apps/examples/adc/adc.h +++ b/apps/examples/adc/adc.h @@ -74,7 +74,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -82,7 +82,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_rawprintf +# define message syslog # define msgflush() # else # define message printf diff --git a/apps/examples/buttons/buttons_main.c b/apps/examples/buttons/buttons_main.c index 5f25c1ef1..655080def 100644 --- a/apps/examples/buttons/buttons_main.c +++ b/apps/examples/buttons/buttons_main.c @@ -299,11 +299,11 @@ static void show_buttons(uint8_t oldset, uint8_t newset) state = "released"; } - /* Use lib_lowprintf() because we make be executing from an + /* Use lowsyslog() because we make be executing from an * interrupt handler. */ - lib_lowprintf(" %s %s\n", g_buttoninfo[BUTTON_INDEX(i)].name, state); + lowsyslog(" %s %s\n", g_buttoninfo[BUTTON_INDEX(i)].name, state); } } } @@ -313,8 +313,8 @@ static void button_handler(int id, int irq) { uint8_t newset = up_buttons(); - lib_lowprintf("IRQ:%d Button %d:%s SET:%02x:\n", - irq, id, g_buttoninfo[BUTTON_INDEX(id)].name, newset); + lowsyslog("IRQ:%d Button %d:%s SET:%02x:\n", + irq, id, g_buttoninfo[BUTTON_INDEX(id)].name, newset); show_buttons(g_oldset, newset); g_oldset = newset; } @@ -409,7 +409,7 @@ int buttons_main(int argc, char *argv[]) { maxbuttons = strtol(argv[1], NULL, 10); } - lib_lowprintf("maxbuttons: %d\n", maxbuttons); + lowsyslog("maxbuttons: %d\n", maxbuttons); #endif /* Initialize the button GPIOs */ @@ -423,11 +423,11 @@ int buttons_main(int argc, char *argv[]) { xcpt_t oldhandler = up_irqbutton(i, g_buttoninfo[BUTTON_INDEX(i)].handler); - /* Use lib_lowprintf() for compatibility with interrrupt handler output. */ + /* Use lowsyslog() for compatibility with interrrupt handler output. */ - lib_lowprintf("Attached handler at %p to button %d [%s], oldhandler:%p\n", - g_buttoninfo[BUTTON_INDEX(i)].handler, i, - g_buttoninfo[BUTTON_INDEX(i)].name, oldhandler); + lowsyslog("Attached handler at %p to button %d [%s], oldhandler:%p\n", + g_buttoninfo[BUTTON_INDEX(i)].handler, i, + g_buttoninfo[BUTTON_INDEX(i)].name, oldhandler); /* Some hardware multiplexes different GPIO button sources to the same * physical interrupt. If we register multiple such multiplexed button @@ -438,9 +438,9 @@ int buttons_main(int argc, char *argv[]) if (oldhandler != NULL) { - lib_lowprintf("WARNING: oldhandler:%p is not NULL! " - "Button events may be lost or aliased!\n", - oldhandler); + lowsyslog("WARNING: oldhandler:%p is not NULL! " + "Button events may be lost or aliased!\n", + oldhandler); } } #endif @@ -468,11 +468,11 @@ int buttons_main(int argc, char *argv[]) flags = irqsave(); - /* Use lib_lowprintf() for compatibility with interrrupt handler + /* Use lowsyslog() for compatibility with interrrupt handler * output. */ - lib_lowprintf("POLL SET:%02x:\n", newset); + lowsyslog("POLL SET:%02x:\n", newset); show_buttons(g_oldset, newset); g_oldset = newset; irqrestore(flags); diff --git a/apps/examples/can/can.h b/apps/examples/can/can.h index 53a6b63ea..d9f9236f7 100644 --- a/apps/examples/can/can.h +++ b/apps/examples/can/can.h @@ -89,7 +89,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -97,7 +97,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_rawprintf +# define message syslog # define msgflush() # else # define message printf diff --git a/apps/examples/cdcacm/cdcacm.h b/apps/examples/cdcacm/cdcacm.h index 18570bff0..1b3b2511c 100644 --- a/apps/examples/cdcacm/cdcacm.h +++ b/apps/examples/cdcacm/cdcacm.h @@ -112,7 +112,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -120,7 +120,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/composite/composite.h b/apps/examples/composite/composite.h index 73a4453be..3f7f7ebad 100644 --- a/apps/examples/composite/composite.h +++ b/apps/examples/composite/composite.h @@ -173,7 +173,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -181,7 +181,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/igmp/igmp.h b/apps/examples/igmp/igmp.h index 093f58c1f..5e1fa8d95 100644 --- a/apps/examples/igmp/igmp.h +++ b/apps/examples/igmp/igmp.h @@ -46,12 +46,12 @@ * Definitions ****************************************************************************/ -/* Used lib_rawprintf() so that there is no confusion from buffered IO */ +/* Used syslog() so that there is no confusion from buffered IO */ #ifdef CONFIG_CPP_HAVE_VARARGS -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) #else -# define message lib_rawprintf +# define message syslog #endif /**************************************************************************** diff --git a/apps/examples/nettest/nettest.h b/apps/examples/nettest/nettest.h index 37ac470d1..5021e05d6 100644 --- a/apps/examples/nettest/nettest.h +++ b/apps/examples/nettest/nettest.h @@ -69,12 +69,12 @@ #else - /* Used lib_rawprintf() so that there is not confusion from buffered IO */ + /* Used syslog() so that there is not confusion from buffered IO */ # ifdef CONFIG_CPP_HAVE_VARARGS -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # else -# define message lib_rawprintf +# define message syslog # endif /* At present, uIP does only abortive disconnects */ diff --git a/apps/examples/nx/nx_internal.h b/apps/examples/nx/nx_internal.h index d9a6a2ade..53f1763b4 100644 --- a/apps/examples/nx/nx_internal.h +++ b/apps/examples/nx/nx_internal.h @@ -168,7 +168,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -176,7 +176,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/nxconsole/nxcon_internal.h b/apps/examples/nxconsole/nxcon_internal.h index c5ad760ad..c921bed38 100644 --- a/apps/examples/nxconsole/nxcon_internal.h +++ b/apps/examples/nxconsole/nxcon_internal.h @@ -239,7 +239,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -247,7 +247,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/nxffs/nxffs_main.c b/apps/examples/nxffs/nxffs_main.c index 5401fc932..8bb5cd1fe 100644 --- a/apps/examples/nxffs/nxffs_main.c +++ b/apps/examples/nxffs/nxffs_main.c @@ -120,7 +120,7 @@ #endif #if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS) -# define message lib_rawprintf +# define message syslog # define msgflush() #else # define message printf diff --git a/apps/examples/nxhello/nxhello.h b/apps/examples/nxhello/nxhello.h index 2dce7bf6c..f395b7018 100644 --- a/apps/examples/nxhello/nxhello.h +++ b/apps/examples/nxhello/nxhello.h @@ -96,7 +96,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -104,7 +104,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/nximage/nximage.h b/apps/examples/nximage/nximage.h index eac0f5dc2..ef475ca29 100644 --- a/apps/examples/nximage/nximage.h +++ b/apps/examples/nximage/nximage.h @@ -111,7 +111,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -119,7 +119,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/nxlines/nxlines.h b/apps/examples/nxlines/nxlines.h index a26db9f29..c9101124e 100644 --- a/apps/examples/nxlines/nxlines.h +++ b/apps/examples/nxlines/nxlines.h @@ -120,7 +120,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -128,7 +128,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/nxtext/nxtext_internal.h b/apps/examples/nxtext/nxtext_internal.h index f0001e0bb..1e64193a3 100644 --- a/apps/examples/nxtext/nxtext_internal.h +++ b/apps/examples/nxtext/nxtext_internal.h @@ -194,7 +194,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -202,7 +202,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/poll/poll_internal.h b/apps/examples/poll/poll_internal.h index b2400932e..759d23f1c 100644 --- a/apps/examples/poll/poll_internal.h +++ b/apps/examples/poll/poll_internal.h @@ -71,7 +71,7 @@ # undef HAVE_NETPOLL #endif -/* If debug is enabled, then use lib_rawprintf so that OS debug output and +/* If debug is enabled, then use syslog so that OS debug output and * the test output are synchronized. * * These macros will differ depending upon if the toolchain supports @@ -80,7 +80,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -88,7 +88,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_rawprintf +# define message syslog # define msgflush() # else # define message printf diff --git a/apps/examples/pwm/pwm.h b/apps/examples/pwm/pwm.h index 5c049a8f8..a6132ca8b 100644 --- a/apps/examples/pwm/pwm.h +++ b/apps/examples/pwm/pwm.h @@ -92,7 +92,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -100,7 +100,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_rawprintf +# define message syslog # define msgflush() # else # define message printf diff --git a/apps/examples/qencoder/qe.h b/apps/examples/qencoder/qe.h index 4c03689ab..3c20511ca 100644 --- a/apps/examples/qencoder/qe.h +++ b/apps/examples/qencoder/qe.h @@ -77,7 +77,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -85,7 +85,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_rawprintf +# define message syslog # define msgflush() # else # define message printf diff --git a/apps/examples/thttpd/thttpd_main.c b/apps/examples/thttpd/thttpd_main.c index 97f922a76..9d08824e6 100644 --- a/apps/examples/thttpd/thttpd_main.c +++ b/apps/examples/thttpd/thttpd_main.c @@ -125,7 +125,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -133,7 +133,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/touchscreen/tc.h b/apps/examples/touchscreen/tc.h index 654b1d874..dddff11c3 100644 --- a/apps/examples/touchscreen/tc.h +++ b/apps/examples/touchscreen/tc.h @@ -82,7 +82,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -90,7 +90,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_rawprintf +# define message syslog # define msgflush() # else # define message printf diff --git a/apps/examples/udp/udp-internal.h b/apps/examples/udp/udp-internal.h index 2a966c746..c8010e6c8 100644 --- a/apps/examples/udp/udp-internal.h +++ b/apps/examples/udp/udp-internal.h @@ -63,12 +63,12 @@ #else - /* If debug is enabled, use the synchronous lib_lowprintf so that the + /* If debug is enabled, use the synchronous lowsyslog so that the * program output does not get disassociated in the debug output. */ # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif diff --git a/apps/examples/uip/uip_main.c b/apps/examples/uip/uip_main.c index 6c2f96f39..8e485441c 100644 --- a/apps/examples/uip/uip_main.c +++ b/apps/examples/uip/uip_main.c @@ -86,13 +86,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message (void) # endif diff --git a/apps/examples/usbserial/usbserial_main.c b/apps/examples/usbserial/usbserial_main.c index 016c8b292..dc7e1959a 100644 --- a/apps/examples/usbserial/usbserial_main.c +++ b/apps/examples/usbserial/usbserial_main.c @@ -109,16 +109,16 @@ TRACE_TRANSFER_BITS|TRACE_CONTROLLER_BITS|TRACE_INTERRUPT_BITS) #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) -# define trmessage lib_lowprintf +# define message(...) lowsyslog(__VA_ARGS__) +# define trmessage lowsyslog # else # define message(...) printf(__VA_ARGS__) # define trmessage printf # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf -# define trmessage lib_lowprintf +# define message lowsyslog +# define trmessage lowsyslog # else # define message printf # define trmessage printf diff --git a/apps/examples/usbstorage/usbmsc.h b/apps/examples/usbstorage/usbmsc.h index 9d48c4521..95453198a 100644 --- a/apps/examples/usbstorage/usbmsc.h +++ b/apps/examples/usbstorage/usbmsc.h @@ -85,7 +85,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -93,7 +93,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/apps/examples/usbterm/usbterm.h b/apps/examples/usbterm/usbterm.h index 2534c2f3c..560e55346 100644 --- a/apps/examples/usbterm/usbterm.h +++ b/apps/examples/usbterm/usbterm.h @@ -101,16 +101,16 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) -# define trmessage lib_rawprintf +# define message(...) syslog(__VA_ARGS__) +# define trmessage syslog # else # define message(...) printf(__VA_ARGS__) # define trmessage printf # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf -# define trmessage lib_lowprintf +# define message lowsyslog +# define trmessage lowsyslog # else # define message printf # define trmessage printf diff --git a/apps/examples/watchdog/watchdog.h b/apps/examples/watchdog/watchdog.h index dc2dea944..dd4daebb9 100644 --- a/apps/examples/watchdog/watchdog.h +++ b/apps/examples/watchdog/watchdog.h @@ -89,7 +89,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -97,7 +97,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_rawprintf +# define message syslog # define msgflush() # else # define message printf diff --git a/apps/include/usbmonitor.h b/apps/include/usbmonitor.h new file mode 100644 index 000000000..01fa060b0 --- /dev/null +++ b/apps/include/usbmonitor.h @@ -0,0 +1,96 @@ +/**************************************************************************** + * apps/include/usbmonitor.h + * + * Copyright (C) 2013 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 NuttX 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. + * + ****************************************************************************/ + +#ifndef __APPS_INCLUDE_USBMONITOR_H +#define __APPS_INCLUDE_USBMONITOR_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef CONFIG_SYSTEM_USBMONITOR + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: usbmon_start and usbmon_stop + * + * Start and top the USB monitor daemon. These are normally controlled + * from the USB command line, but the ability to control these + * programmatically is also helpful (for example, so that the daemon is + * running before NSH starts). + * + * Input Parameters: + * Standard task parameters. These can be called or spawned. Since the + * return almost immediately, it is fine to just call the functions. The + * parameters are not used so you can pass 0 and NULL, respectivley; this + * is done this way so that these functions can be NSH builtin + * applications. + * + * Returned values: + * Standard task return values (zero meaning success). + * + **************************************************************************/ + +int usbmonitor_start(int argc, char **argv); +int usbmonitor_stop(int argc, char **argv); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_SYSTEM_USBMONITOR */ +#endif /* __APPS_INCLUDE_USBMONITOR_H */ diff --git a/apps/nshlib/nsh_usbdev.c b/apps/nshlib/nsh_usbdev.c index 3d123532a..d137e3dae 100644 --- a/apps/nshlib/nsh_usbdev.c +++ b/apps/nshlib/nsh_usbdev.c @@ -63,7 +63,7 @@ ****************************************************************************/ #if defined(CONFIG_DEBUG) || defined(CONFIG_NSH_USBCONSOLE) -# define trmessage lib_lowprintf +# define trmessage lowsyslog #else # define trmessage printf #endif diff --git a/apps/system/usbmonitor/Makefile b/apps/system/usbmonitor/Makefile index 04fcaf0ac..b4c323eb7 100644 --- a/apps/system/usbmonitor/Makefile +++ b/apps/system/usbmonitor/Makefile @@ -44,7 +44,6 @@ endif # Hello Application # TODO: appname can be automatically extracted from the directory name -APPNAME = usbmon PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 768 @@ -90,7 +89,8 @@ $(COBJS): %$(OBJEXT): %.c ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) $(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat: $(DEPCONFIG) Makefile - $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) + $(call REGISTER,"usbmon_start",$(PRIORITY),$(STACKSIZE),usbmonitor_start) + $(call REGISTER,"usbmon_stop",$(PRIORITY),$(STACKSIZE),usbmonintor_stop) context: $(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat else diff --git a/apps/system/usbmonitor/usbmonitor.c b/apps/system/usbmonitor/usbmonitor.c index b101b128c..b615b99f9 100644 --- a/apps/system/usbmonitor/usbmonitor.c +++ b/apps/system/usbmonitor/usbmonitor.c @@ -40,20 +40,29 @@ #include #include -#include -#include +#include +#include +#include + +#include event, trace->value); + return 0; +} + static int usbmonitor_daemon(int argc, char **argv) { -#ifdef CONFIG_NSH_BUILTIN_APPS - print("USB Monitor running: %d\n", g_usbmonitor.pid); -#endif + syslog(USBMON_PREFIX "Running: %d\n", g_usbmonitor.pid); -#ifdef CONFIG_NSH_BUILTIN_APPS - /* If we are running as an NSH command, then loop until we detect that - * there is a request to stop. - */ + /* Loop until we detect that there is a request to stop. */ while (!g_usbmonitor.stop) -#else - /* If we are running as a standalone program, then loop forever */ - - for (;;) -#endif { -#warning "Missing logic" + (void)usbmonitor_enumerate(nsh_tracecallback, NULL); } /* Stopped */ -#ifdef CONFIG_NSH_BUILTIN_APPS g_usbmonitor.stop = false; g_usbmonitor.started = false; - print("USB Monitor stopped: %d\n", g_usbmonitor.pid); -#endif + syslog(USBMON_PREFIX "Stopped: %d\n", g_usbmonitor.pid); + return 0; } @@ -101,9 +105,8 @@ static int usbmonitor_daemon(int argc, char **argv) * Public Functions ****************************************************************************/ -int usbmonitor_main(int argc, char **argv) +int usbmonitor_start(int argc, char **argv) { -#ifdef CONFIG_NSH_BUILTIN_APPS /* Has the monitor already started? */ sched_lock(); @@ -122,13 +125,14 @@ int usbmonitor_main(int argc, char **argv) if (ret < 0) { int errcode = errno; - fprintf(stderr, "ERROR: Failed to start the USB monitor: %d\n", - errcode); + syslog(USBMON_PREFIX + "ERROR: Failed to start the USB monitor: %d\n", + errcode); } else { g_usbmonitor.pid = ret; - print("USB Monitor started: %d\n", g_usbmonitor.pid); + syslog(USBMON_PREFIX "Started: %d\n", g_usbmonitor.pid); } sched_unlock(); @@ -136,27 +140,23 @@ int usbmonitor_main(int argc, char **argv) } sched_unlock(); - print("USB Monitor running: %d\n", g_usbmonitor.pid); + syslog(USBMON_PREFIX "Running: %d\n", g_usbmonitor.pid); return 0; -#else - return usbmonitor_daemon(argc, argv); -#endif } -#ifdef CONFIG_NSH_BUILTIN_APPS int usbmonitor_stop(int argc, char **argv) { /* Has the monitor already started? */ if (g_usbmonitor.started) { - print("USB Monitor stopping: %d\n", g_usbmonitor.pid); + syslog(USBMON_PREFIX "Stopping: %d\n", g_usbmonitor.pid); g_usbmonitor.stop = true; return 0; } - print("USB Monitor stopped: %d\n", g_usbmonitor.pid); + syslog(USBMON_PREFIX "Stopped: %d\n", g_usbmonitor.pid); return 0; } -#endif +#endif /* CONFIG_SYSTEM_USBMONITOR */ diff --git a/misc/tools/README.txt b/misc/tools/README.txt index e1c67c5f0..1eb8790f1 100644 --- a/misc/tools/README.txt +++ b/misc/tools/README.txt @@ -45,14 +45,14 @@ kconfig-frontends To suppress the 'nconf' and the graphical front-ends which are not used by NuttX, you can add: - ./configure --enable-mconfig --disable-nconf --disable-gconf --disable-qconf + ./configure --enable-mconf --disable-nconf --disable-gconf --disable-qconf make make install To suppress the graphical interfaces, use static libraries, and disable creation of other utilities: - ./configure --disable-shared --enable-static --enable-mconfig --disable-nconf --disable-gconf --disable-qconf --disable-nconf --disable-utils + ./configure --disable-shared --enable-static --enable-mconf --disable-nconf --disable-gconf --disable-qconf --disable-nconf --disable-utils make make install diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index fd358f423..f2f7ada02 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -4324,17 +4324,17 @@ build
  • CONFIG_DEBUG: enables built-in debug options. This includes more extensive parameter checking, debug assertions, and other debug logic. - This option is also necessary (but not sufficient) to enable debug console output; - Debug console output must also be enabled on a subsystem-by-subsystem basis as described below. + This option is also necessary (but not sufficient) to enable debug syslog output; + Debug syslog output must also be enabled on a subsystem-by-subsystem basis as described below.
  • - CONFIG_DEBUG_VERBOSE: If debug console output is enabled, the option enables more verbose debug output. + CONFIG_DEBUG_VERBOSE: If debug syslog output is enabled, the option enables more verbose debug output. Ignored if CONFIG_DEBUG is not defined. If only CONFIG_DEBUG then the only output will be errors, warnings, and critical information. - If CONFIG_DEBUG_VERBOSE is defined in addition, then general debug comments will also be included in the console output. + If CONFIG_DEBUG_VERBOSE is defined in addition, then general debug comments will also be included in the syslog output.
  • - CONFIG_DEBUG_ENABLE: Support an interface to enable or disable debug output. + CONFIG_SYSLOG_ENABLE: Support an interface to enable or disable syslog output.
  • CONFIG_DEBUG_SYMBOLS: build without optimization and with debug symbols (needed for use with a debugger). diff --git a/nuttx/Kconfig b/nuttx/Kconfig index 10d624efb..937bab2be 100644 --- a/nuttx/Kconfig +++ b/nuttx/Kconfig @@ -312,11 +312,12 @@ config DEBUG_VERBOSE often annoying) output will be generated. This means there are two levels of debug output: errors-only and everything. -config DEBUG_ENABLE +config SYSLOG_ENABLE bool "Enable Debug Controls" default n ---help--- - Support an interface to dynamically enable or disable debug output. + Support an interface called syslog_enable to dynamically enable or + disable debug output. comment "Subsystem Debug Options" diff --git a/nuttx/TODO b/nuttx/TODO index 05e0fa99b..6b2c6c883 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 27, 2013) +NuttX TODO List (Last updated January 28, 2013) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -14,7 +14,7 @@ nuttx/ (6) Binary loaders (binfmt/) (16) Network (net/, drivers/net) (4) USB (drivers/usbdev, drivers/usbhost) - (12) Libraries (libc/, ) + (11) Libraries (libc/, ) (9) File system/Generic drivers (fs/, drivers/) (5) Graphics subystem (graphics/) (1) Pascal add-on (pcode/) @@ -812,19 +812,6 @@ o Libraries (libc/) Status: Open Priority: ?? - Title: SYSLOG INTEGRATION - Description: There are the beginnings of some system logging capabilities (see - drivers/syslog, fs/fs_syslog.c, and libc/stdio/lib_librawprintf.c and - lib_liblowprintf.c. For NuttX, SYSLOG is a concept and includes, - extends, and replaces the legacy NuttX debug ouput. Some additional - integration is required to formalized this. For example: - - o lib_rawprintf() shjould be renamed syslog(). - o debug.h should be renamed syslog.h - o And what about lib_lowprintf()? llsyslog? - Status: Open - Priority: Low -- more of a roadmap - Title: FLOATING POINT FORMATS Description: Only the %f floating point format is supported. Others are accepted but treated like %f. diff --git a/nuttx/arch/arm/src/arm/up_assert.c b/nuttx/arch/arm/src/arm/up_assert.c index 3d75a4655..3cc79df01 100644 --- a/nuttx/arch/arm/src/arm/up_assert.c +++ b/nuttx/arch/arm/src/arm/up_assert.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /* The following is just intended to keep some ugliness out of the mainline @@ -70,7 +70,7 @@ * * CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name * (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used) - * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used + * defined(CONFIG_ARCH_STACKDUMP) <-- Or lowsyslog() is used */ #undef CONFIG_PRINT_TASKNAME diff --git a/nuttx/arch/arm/src/arm/up_dataabort.c b/nuttx/arch/arm/src/arm/up_dataabort.c index f01941968..60ef8385e 100644 --- a/nuttx/arch/arm/src/arm/up_dataabort.c +++ b/nuttx/arch/arm/src/arm/up_dataabort.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/arm/src/arm/up_prefetchabort.c b/nuttx/arch/arm/src/arm/up_prefetchabort.c index 9af644fc0..9d028b0d4 100644 --- a/nuttx/arch/arm/src/arm/up_prefetchabort.c +++ b/nuttx/arch/arm/src/arm/up_prefetchabort.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/arm/src/arm/up_syscall.c b/nuttx/arch/arm/src/arm/up_syscall.c index 1bcd66502..eb9bac8ad 100644 --- a/nuttx/arch/arm/src/arm/up_syscall.c +++ b/nuttx/arch/arm/src/arm/up_syscall.c @@ -56,7 +56,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/arm/src/arm/up_undefinedinsn.c b/nuttx/arch/arm/src/arm/up_undefinedinsn.c index d61abe11b..88e3a79d9 100644 --- a/nuttx/arch/arm/src/arm/up_undefinedinsn.c +++ b/nuttx/arch/arm/src/arm/up_undefinedinsn.c @@ -54,7 +54,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/arm/src/armv7-m/up_assert.c b/nuttx/arch/arm/src/armv7-m/up_assert.c index ab30b09f3..8e29bfe80 100644 --- a/nuttx/arch/arm/src/armv7-m/up_assert.c +++ b/nuttx/arch/arm/src/armv7-m/up_assert.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /* The following is just intended to keep some ugliness out of the mainline @@ -70,7 +70,7 @@ * * CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name * (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used) - * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used + * defined(CONFIG_ARCH_STACKDUMP) <-- Or lowsyslog() is used */ #undef CONFIG_PRINT_TASKNAME diff --git a/nuttx/arch/arm/src/dm320/dm320_decodeirq.c b/nuttx/arch/arm/src/dm320/dm320_decodeirq.c index c7032c4b1..98ba76097 100644 --- a/nuttx/arch/arm/src/dm320/dm320_decodeirq.c +++ b/nuttx/arch/arm/src/dm320/dm320_decodeirq.c @@ -74,7 +74,7 @@ void up_decodeirq(uint32_t* regs) { #ifdef CONFIG_SUPPRESS_INTERRUPTS - lib_lowprintf("Unexpected IRQ\n"); + lowsyslog("Unexpected IRQ\n"); current_regs = regs; PANIC(OSERR_ERREXCEPTION); #else diff --git a/nuttx/arch/arm/src/imx/imx_decodeirq.c b/nuttx/arch/arm/src/imx/imx_decodeirq.c index ba37a60a2..230a4fc20 100644 --- a/nuttx/arch/arm/src/imx/imx_decodeirq.c +++ b/nuttx/arch/arm/src/imx/imx_decodeirq.c @@ -74,7 +74,7 @@ void up_decodeirq(uint32_t* regs) { #ifdef CONFIG_SUPPRESS_INTERRUPTS - lib_lowprintf("Unexpected IRQ\n"); + lowsyslog("Unexpected IRQ\n"); current_regs = regs; PANIC(OSERR_ERREXCEPTION); #else diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c b/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c index 652fe4d61..057e526c2 100644 --- a/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c +++ b/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c @@ -112,7 +112,7 @@ static void lpc214x_decodeirq( uint32_t *regs) #endif { #ifdef CONFIG_SUPPRESS_INTERRUPTS - lib_lowprintf("Unexpected IRQ\n"); + lowsyslog("Unexpected IRQ\n"); current_regs = regs; PANIC(OSERR_ERREXCEPTION); #else diff --git a/nuttx/arch/arm/src/lpc2378/lpc23xx_decodeirq.c b/nuttx/arch/arm/src/lpc2378/lpc23xx_decodeirq.c index a55ed339d..3a50beb50 100644 --- a/nuttx/arch/arm/src/lpc2378/lpc23xx_decodeirq.c +++ b/nuttx/arch/arm/src/lpc2378/lpc23xx_decodeirq.c @@ -111,7 +111,7 @@ static void lpc23xx_decodeirq(uint32_t *regs) #endif { #ifdef CONFIG_SUPPRESS_INTERRUPTS - lib_lowprintf("Unexpected IRQ\n"); + lowsyslog("Unexpected IRQ\n"); current_regs = regs; PANIC(OSERR_ERREXCEPTION); #else diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c b/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c index 41e1d3e13..0e73f131b 100644 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c @@ -77,7 +77,7 @@ void up_decodeirq(uint32_t *regs) { #ifdef CONFIG_SUPPRESS_INTERRUPTS - lib_lowprintf("Unexpected IRQ\n"); + lowsyslog("Unexpected IRQ\n"); current_regs = regs; PANIC(OSERR_ERREXCEPTION); #else diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c index 18687c6f4..c2d638dd4 100644 --- a/nuttx/arch/arm/src/stm32/stm32_i2c.c +++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c @@ -159,7 +159,7 @@ #endif /* I2C event trace logic. NOTE: trace uses the internal, non-standard, low-level - * debug interface lib_rawprintf() but does not require that any other debug + * debug interface syslog() but does not require that any other debug * is enabled. */ @@ -899,11 +899,11 @@ static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv) struct stm32_trace_s *trace; int i; - lib_rawprintf("Elapsed time: %d\n", clock_systimer() - priv->start_time); + syslog("Elapsed time: %d\n", clock_systimer() - priv->start_time); for (i = 0; i <= priv->tndx; i++) { trace = &priv->trace[i]; - lib_rawprintf("%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x TIME: %d\n", + syslog("%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x TIME: %d\n", i+1, trace->status, trace->count, trace->event, trace->parm, trace->time - priv->start_time); } diff --git a/nuttx/arch/arm/src/str71x/str71x_decodeirq.c b/nuttx/arch/arm/src/str71x/str71x_decodeirq.c index 326abd763..48c9aa7e4 100644 --- a/nuttx/arch/arm/src/str71x/str71x_decodeirq.c +++ b/nuttx/arch/arm/src/str71x/str71x_decodeirq.c @@ -91,7 +91,7 @@ void up_decodeirq(uint32_t *regs) { #ifdef CONFIG_SUPPRESS_INTERRUPTS up_ledon(LED_INIRQ); - lib_lowprintf("Unexpected IRQ\n"); + lowsyslog("Unexpected IRQ\n"); current_regs = regs; PANIC(OSERR_ERREXCEPTION); #else diff --git a/nuttx/arch/avr/src/avr/up_dumpstate.c b/nuttx/arch/avr/src/avr/up_dumpstate.c index 902c2ce9f..3ce595bf0 100644 --- a/nuttx/arch/avr/src/avr/up_dumpstate.c +++ b/nuttx/arch/avr/src/avr/up_dumpstate.c @@ -63,7 +63,7 @@ */ #undef lldbg -#define lldbg lib_lowprintf +#define lldbg lowsyslog /**************************************************************************** * Private Data diff --git a/nuttx/arch/avr/src/avr32/up_dumpstate.c b/nuttx/arch/avr/src/avr32/up_dumpstate.c index 15a3e7ef8..d6113d40b 100644 --- a/nuttx/arch/avr/src/avr32/up_dumpstate.c +++ b/nuttx/arch/avr/src/avr32/up_dumpstate.c @@ -63,7 +63,7 @@ */ #undef lldbg -#define lldbg lib_lowprintf +#define lldbg lowsyslog /**************************************************************************** * Private Data diff --git a/nuttx/arch/avr/src/common/up_assert.c b/nuttx/arch/avr/src/common/up_assert.c index 12bb564d3..3e90094eb 100644 --- a/nuttx/arch/avr/src/common/up_assert.c +++ b/nuttx/arch/avr/src/common/up_assert.c @@ -61,7 +61,7 @@ * * CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name * (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used) - * defined(CONFIG_ARCH_STACKDUMP)) <-- Or lib_lowprintf() is used + * defined(CONFIG_ARCH_STACKDUMP)) <-- Or lowsyslog() is used */ #undef CONFIG_PRINT_TASKNAME @@ -75,7 +75,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/hc/src/m9s12/m9s12_assert.c b/nuttx/arch/hc/src/m9s12/m9s12_assert.c index ff9ce5ca4..65cc75590 100644 --- a/nuttx/arch/hc/src/m9s12/m9s12_assert.c +++ b/nuttx/arch/hc/src/m9s12/m9s12_assert.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /* The following is just intended to keep some ugliness out of the mainline @@ -70,7 +70,7 @@ * * CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name * (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used) - * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used + * defined(CONFIG_ARCH_STACKDUMP) <-- Or lowsyslog() is used */ #undef CONFIG_PRINT_TASKNAME diff --git a/nuttx/arch/mips/src/mips32/up_assert.c b/nuttx/arch/mips/src/mips32/up_assert.c index ed4ee4cf7..7d98e7427 100644 --- a/nuttx/arch/mips/src/mips32/up_assert.c +++ b/nuttx/arch/mips/src/mips32/up_assert.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /* The following is just intended to keep some ugliness out of the mainline @@ -70,7 +70,7 @@ * * CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name * (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used) - * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used + * defined(CONFIG_ARCH_STACKDUMP) <-- Or lowsyslog() is used */ #undef CONFIG_PRINT_TASKNAME diff --git a/nuttx/arch/mips/src/mips32/up_dumpstate.c b/nuttx/arch/mips/src/mips32/up_dumpstate.c index 866c17b4f..1cd426767 100644 --- a/nuttx/arch/mips/src/mips32/up_dumpstate.c +++ b/nuttx/arch/mips/src/mips32/up_dumpstate.c @@ -63,7 +63,7 @@ */ #undef lldbg -#define lldbg lib_lowprintf +#define lldbg lowsyslog /**************************************************************************** * Private Data diff --git a/nuttx/arch/sh/src/common/up_assert.c b/nuttx/arch/sh/src/common/up_assert.c index ccc0c98e6..5b56e7731 100644 --- a/nuttx/arch/sh/src/common/up_assert.c +++ b/nuttx/arch/sh/src/common/up_assert.c @@ -61,7 +61,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/sh/src/m16c/m16c_dumpstate.c b/nuttx/arch/sh/src/m16c/m16c_dumpstate.c index 438ff21d2..38571a7e1 100644 --- a/nuttx/arch/sh/src/m16c/m16c_dumpstate.c +++ b/nuttx/arch/sh/src/m16c/m16c_dumpstate.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/sh/src/sh1/sh1_dumpstate.c b/nuttx/arch/sh/src/sh1/sh1_dumpstate.c index 296e20a45..f54ea46ce 100644 --- a/nuttx/arch/sh/src/sh1/sh1_dumpstate.c +++ b/nuttx/arch/sh/src/sh1/sh1_dumpstate.c @@ -61,7 +61,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/sim/src/up_initialize.c b/nuttx/arch/sim/src/up_initialize.c index de11c7947..f8ae563e0 100644 --- a/nuttx/arch/sim/src/up_initialize.c +++ b/nuttx/arch/sim/src/up_initialize.c @@ -85,13 +85,13 @@ void up_initialize(void) { - /* The real purpose of the following is to make sure that lib_rawprintf + /* The real purpose of the following is to make sure that syslog * is drawn into the link. It is needed by up_tapdev which is linked * separately. */ #ifdef CONFIG_NET - lib_rawprintf("SIM: Initializing"); + syslog("SIM: Initializing"); #endif /* Register devices */ diff --git a/nuttx/arch/sim/src/up_tapdev.c b/nuttx/arch/sim/src/up_tapdev.c index f2bbcc14a..197049a34 100644 --- a/nuttx/arch/sim/src/up_tapdev.c +++ b/nuttx/arch/sim/src/up_tapdev.c @@ -61,7 +61,7 @@ #include #include -extern int lib_rawprintf(const char *format, ...); +extern int syslog(const char *format, ...); extern int uipdriver_setmacaddr(unsigned char *macaddr); /**************************************************************************** @@ -119,14 +119,14 @@ static int gtapdevfd; #ifdef TAPDEV_DEBUG static inline void dump_ethhdr(const char *msg, unsigned char *buf, int buflen) { - lib_rawprintf("TAPDEV: %s %d bytes\n", msg, buflen); - lib_rawprintf(" %02x:%02x:%02x:%02x:%02x:%02x %02x:%02x:%02x:%02x:%02x:%02x %02x%02x\n", - buf[0], buf[1], buf[2], buf[3], buf[4], buf[5], - buf[6], buf[7], buf[8], buf[9], buf[10], buf[11], + syslog("TAPDEV: %s %d bytes\n", msg, buflen); + syslog(" %02x:%02x:%02x:%02x:%02x:%02x %02x:%02x:%02x:%02x:%02x:%02x %02x%02x\n", + buf[0], buf[1], buf[2], buf[3], buf[4], buf[5], + buf[6], buf[7], buf[8], buf[9], buf[10], buf[11], #ifdef CONFIG_ENDIAN_BIG - buf[13], buf[12]); + buf[13], buf[12]); #else - buf[12], buf[13]); + buf[12], buf[13]); #endif } #else @@ -179,7 +179,7 @@ void tapdev_init(void) gtapdevfd = open(DEVTAP, O_RDWR, 0644); if (gtapdevfd < 0) { - lib_rawprintf("TAPDEV: open failed: %d\n", -gtapdevfd ); + syslog("TAPDEV: open failed: %d\n", -gtapdevfd ); return; } @@ -190,7 +190,7 @@ void tapdev_init(void) ret = ioctl(gtapdevfd, TUNSETIFF, (unsigned long) &ifr); if (ret < 0) { - lib_rawprintf("TAPDEV: ioctl failed: %d\n", -ret ); + syslog("TAPDEV: ioctl failed: %d\n", -ret ); return; } @@ -235,7 +235,7 @@ unsigned int tapdev_read(unsigned char *buf, unsigned int buflen) ret = read(gtapdevfd, buf, buflen); if (ret < 0) { - lib_rawprintf("TAPDEV: read failed: %d\n", -ret); + syslog("TAPDEV: read failed: %d\n", -ret); return 0; } @@ -247,12 +247,12 @@ void tapdev_send(unsigned char *buf, unsigned int buflen) { int ret; #ifdef TAPDEV_DEBUG - lib_rawprintf("tapdev_send: sending %d bytes\n", buflen); + syslog("tapdev_send: sending %d bytes\n", buflen); gdrop++; if(gdrop % 8 == 7) { - lib_rawprintf("Dropped a packet!\n"); + syslog("Dropped a packet!\n"); return; } #endif @@ -260,7 +260,7 @@ void tapdev_send(unsigned char *buf, unsigned int buflen) ret = write(gtapdevfd, buf, buflen); if (ret < 0) { - lib_rawprintf("TAPDEV: write failed: %d", -ret); + syslog("TAPDEV: write failed: %d", -ret); exit(1); } dump_ethhdr("write", buf, buflen); diff --git a/nuttx/arch/x86/src/common/up_assert.c b/nuttx/arch/x86/src/common/up_assert.c index aa752f84e..87958baa6 100644 --- a/nuttx/arch/x86/src/common/up_assert.c +++ b/nuttx/arch/x86/src/common/up_assert.c @@ -63,7 +63,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /* The following is just intended to keep some ugliness out of the mainline @@ -71,7 +71,7 @@ * * CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name * (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used) - * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used + * defined(CONFIG_ARCH_STACKDUMP) <-- Or lowsyslog() is used */ #undef CONFIG_PRINT_TASKNAME diff --git a/nuttx/arch/x86/src/i486/up_regdump.c b/nuttx/arch/x86/src/i486/up_regdump.c index b7547aec4..e30670128 100644 --- a/nuttx/arch/x86/src/i486/up_regdump.c +++ b/nuttx/arch/x86/src/i486/up_regdump.c @@ -51,7 +51,7 @@ /* Output debug info -- even if debug is not selected. */ #undef lldbg -#define lldbg lib_lowprintf +#define lldbg lowsyslog /**************************************************************************** * Private Data diff --git a/nuttx/arch/z16/src/common/up_assert.c b/nuttx/arch/z16/src/common/up_assert.c index 5832ead45..661d88833 100644 --- a/nuttx/arch/z16/src/common/up_assert.c +++ b/nuttx/arch/z16/src/common/up_assert.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/z16/src/common/up_registerdump.c b/nuttx/arch/z16/src/common/up_registerdump.c index dd1f210f7..178320dd2 100644 --- a/nuttx/arch/z16/src/common/up_registerdump.c +++ b/nuttx/arch/z16/src/common/up_registerdump.c @@ -58,7 +58,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/z16/src/common/up_stackdump.c b/nuttx/arch/z16/src/common/up_stackdump.c index b4930f620..077b0c8f7 100644 --- a/nuttx/arch/z16/src/common/up_stackdump.c +++ b/nuttx/arch/z16/src/common/up_stackdump.c @@ -55,7 +55,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/z16/src/z16f/z16f_sysexec.c b/nuttx/arch/z16/src/z16f/z16f_sysexec.c index 2fbc1e2c9..e824076b0 100644 --- a/nuttx/arch/z16/src/z16f/z16f_sysexec.c +++ b/nuttx/arch/z16/src/z16f/z16f_sysexec.c @@ -53,9 +53,9 @@ ***************************************************************************/ #ifdef CONFIG_ARCH_LOWPUTC -# define SYSDBG lib_lowprintf +# define SYSDBG lowsyslog #else -# define SYSDBG lib_rawprintf +# define SYSDBG syslog #endif /*************************************************************************** diff --git a/nuttx/arch/z80/src/common/up_assert.c b/nuttx/arch/z80/src/common/up_assert.c index ff4e569fb..11a2a4f2a 100644 --- a/nuttx/arch/z80/src/common/up_assert.c +++ b/nuttx/arch/z80/src/common/up_assert.c @@ -62,7 +62,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/z80/src/common/up_doirq.c b/nuttx/arch/z80/src/common/up_doirq.c index 4b57f8f7b..ad318e17f 100644 --- a/nuttx/arch/z80/src/common/up_doirq.c +++ b/nuttx/arch/z80/src/common/up_doirq.c @@ -76,7 +76,7 @@ FAR chipreg_t *up_doirq(uint8_t irq, FAR chipreg_t *regs) #ifdef CONFIG_SUPPRESS_INTERRUPTS - lib_lowprintf("Unexpected IRQ\n"); + lowsyslog("Unexpected IRQ\n"); IRQ_ENTER(regs); PANIC(OSERR_ERREXCEPTION); return NULL; /* Won't get here */ diff --git a/nuttx/arch/z80/src/common/up_stackdump.c b/nuttx/arch/z80/src/common/up_stackdump.c index 817c2d315..f9c515337 100644 --- a/nuttx/arch/z80/src/common/up_stackdump.c +++ b/nuttx/arch/z80/src/common/up_stackdump.c @@ -56,7 +56,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/z80/src/ez80/ez80_registerdump.c b/nuttx/arch/z80/src/ez80/ez80_registerdump.c index a43bd6459..bf53f81f7 100644 --- a/nuttx/arch/z80/src/ez80/ez80_registerdump.c +++ b/nuttx/arch/z80/src/ez80/ez80_registerdump.c @@ -58,7 +58,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/z80/src/z180/z180_registerdump.c b/nuttx/arch/z80/src/z180/z180_registerdump.c index 65ae791db..17a44b059 100644 --- a/nuttx/arch/z80/src/z180/z180_registerdump.c +++ b/nuttx/arch/z80/src/z180/z180_registerdump.c @@ -58,7 +58,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/z80/src/z8/z8_registerdump.c b/nuttx/arch/z80/src/z8/z8_registerdump.c index 36b6cdd37..f1ce13a24 100644 --- a/nuttx/arch/z80/src/z8/z8_registerdump.c +++ b/nuttx/arch/z80/src/z8/z8_registerdump.c @@ -59,7 +59,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/arch/z80/src/z80/z80_registerdump.c b/nuttx/arch/z80/src/z80/z80_registerdump.c index 0d09a243a..7bf21a26f 100644 --- a/nuttx/arch/z80/src/z80/z80_registerdump.c +++ b/nuttx/arch/z80/src/z80/z80_registerdump.c @@ -58,7 +58,7 @@ #ifdef CONFIG_ARCH_STACKDUMP # undef lldbg -# define lldbg lib_lowprintf +# define lldbg lowsyslog #endif /**************************************************************************** diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c index f4b725183..25ee7ba29 100644 --- a/nuttx/binfmt/libelf/libelf_read.c +++ b/nuttx/binfmt/libelf/libelf_read.c @@ -54,7 +54,7 @@ ****************************************************************************/ #undef ELF_DUMP_READDATA /* Define to dump all file data read */ -#define DUMPER lib_rawprintf /* If ELF_DUMP_READDATA is defined, this +#define DUMPER syslog /* If ELF_DUMP_READDATA is defined, this * is the API used to dump data */ /**************************************************************************** diff --git a/nuttx/binfmt/libnxflat/libnxflat_read.c b/nuttx/binfmt/libnxflat/libnxflat_read.c index 8deeb0805..103a81f81 100644 --- a/nuttx/binfmt/libnxflat/libnxflat_read.c +++ b/nuttx/binfmt/libnxflat/libnxflat_read.c @@ -55,7 +55,7 @@ ****************************************************************************/ #undef NXFLAT_DUMP_READDATA /* Define to dump all file data read */ -#define DUMPER lib_rawprintf /* If NXFLAT_DUMP_READDATA is defined, this +#define DUMPER syslog /* If NXFLAT_DUMP_READDATA is defined, this * is the API used to dump data */ /**************************************************************************** diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 1b78567a3..8d9bb381f 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -261,7 +261,7 @@ defconfig -- This is a configuration file similar to the Linux CONFIG_DEBUG - enables built-in debug options CONFIG_DEBUG_VERBOSE - enables verbose debug output - CCONFIG_DEBUG_ENABLE - Support an interface to enable or disable debug output. + CCONFIG_SYSLOG_ENABLE - Support an interface to enable or disable debug output. CONFIG_DEBUG_SYMBOLS - build without optimization and with debug symbols (needed for use with a debugger). CONFIG_DEBUG_SCHED - enable OS debug output (disabled by diff --git a/nuttx/configs/cloudctrl/src/up_nsh.c b/nuttx/configs/cloudctrl/src/up_nsh.c index f389460bb..6baeeeab8 100644 --- a/nuttx/configs/cloudctrl/src/up_nsh.c +++ b/nuttx/configs/cloudctrl/src/up_nsh.c @@ -101,13 +101,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/cloudctrl/src/up_usbmsc.c b/nuttx/configs/cloudctrl/src/up_usbmsc.c index 1e74e6f24..95fc0189a 100644 --- a/nuttx/configs/cloudctrl/src/up_usbmsc.c +++ b/nuttx/configs/cloudctrl/src/up_usbmsc.c @@ -61,7 +61,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -69,7 +69,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/demo9s12ne64/src/up_nsh.c b/nuttx/configs/demo9s12ne64/src/up_nsh.c index 7e53f7f07..c4773c0ac 100644 --- a/nuttx/configs/demo9s12ne64/src/up_nsh.c +++ b/nuttx/configs/demo9s12ne64/src/up_nsh.c @@ -54,13 +54,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/ea3131/src/up_nsh.c b/nuttx/configs/ea3131/src/up_nsh.c index 29ee7ed2c..b763c26f0 100644 --- a/nuttx/configs/ea3131/src/up_nsh.c +++ b/nuttx/configs/ea3131/src/up_nsh.c @@ -100,13 +100,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/ea3131/src/up_usbmsc.c b/nuttx/configs/ea3131/src/up_usbmsc.c index 5f4850ea1..e1869af4d 100644 --- a/nuttx/configs/ea3131/src/up_usbmsc.c +++ b/nuttx/configs/ea3131/src/up_usbmsc.c @@ -91,8 +91,8 @@ int usbmsc_archinitialize(void) pbuffer = (uint8_t *) malloc (BUFFER_SIZE); if (!pbuffer) { - lib_lowprintf ("usbmsc_archinitialize: Failed to allocate ramdisk of size %d\n", - BUFFER_SIZE); + lowsyslog("usbmsc_archinitialize: Failed to allocate ramdisk of size %d\n", + BUFFER_SIZE); return -ENOMEM; } diff --git a/nuttx/configs/ea3152/src/up_nsh.c b/nuttx/configs/ea3152/src/up_nsh.c index 2b523b44a..d4ac3da27 100644 --- a/nuttx/configs/ea3152/src/up_nsh.c +++ b/nuttx/configs/ea3152/src/up_nsh.c @@ -100,13 +100,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/ea3152/src/up_usbmsc.c b/nuttx/configs/ea3152/src/up_usbmsc.c index 2c3356b4e..ee67f0eed 100644 --- a/nuttx/configs/ea3152/src/up_usbmsc.c +++ b/nuttx/configs/ea3152/src/up_usbmsc.c @@ -91,8 +91,8 @@ int usbmsc_archinitialize(void) pbuffer = (uint8_t *) malloc (BUFFER_SIZE); if (!pbuffer) { - lib_lowprintf ("usbmsc_archinitialize: Failed to allocate ramdisk of size %d\n", - BUFFER_SIZE); + lowsyslog("usbmsc_archinitialize: Failed to allocate ramdisk of size %d\n", + BUFFER_SIZE); return -ENOMEM; } diff --git a/nuttx/configs/eagle100/src/up_nsh.c b/nuttx/configs/eagle100/src/up_nsh.c index 65fd30023..b1df8cde6 100644 --- a/nuttx/configs/eagle100/src/up_nsh.c +++ b/nuttx/configs/eagle100/src/up_nsh.c @@ -95,13 +95,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/ekk-lm3s9b96/src/up_nsh.c b/nuttx/configs/ekk-lm3s9b96/src/up_nsh.c index 6f9aac6b1..f54fb726c 100644 --- a/nuttx/configs/ekk-lm3s9b96/src/up_nsh.c +++ b/nuttx/configs/ekk-lm3s9b96/src/up_nsh.c @@ -55,13 +55,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/ez80f910200kitg/ostest/defconfig b/nuttx/configs/ez80f910200kitg/ostest/defconfig index d86177828..1abc3fb58 100644 --- a/nuttx/configs/ez80f910200kitg/ostest/defconfig +++ b/nuttx/configs/ez80f910200kitg/ostest/defconfig @@ -44,7 +44,7 @@ CONFIG_WINDOWS_CYGWIN=y # CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/ez80f910200zco/ostest/defconfig b/nuttx/configs/ez80f910200zco/ostest/defconfig index e414cfcc1..146b56327 100644 --- a/nuttx/configs/ez80f910200zco/ostest/defconfig +++ b/nuttx/configs/ez80f910200zco/ostest/defconfig @@ -44,7 +44,7 @@ CONFIG_WINDOWS_CYGWIN=y # CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/fire-stm32v2/src/up_composite.c b/nuttx/configs/fire-stm32v2/src/up_composite.c index 6ebc06176..15200caa8 100644 --- a/nuttx/configs/fire-stm32v2/src/up_composite.c +++ b/nuttx/configs/fire-stm32v2/src/up_composite.c @@ -60,7 +60,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -68,7 +68,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/fire-stm32v2/src/up_nsh.c b/nuttx/configs/fire-stm32v2/src/up_nsh.c index ba93d714f..fa261f561 100644 --- a/nuttx/configs/fire-stm32v2/src/up_nsh.c +++ b/nuttx/configs/fire-stm32v2/src/up_nsh.c @@ -127,13 +127,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/fire-stm32v2/src/up_usbmsc.c b/nuttx/configs/fire-stm32v2/src/up_usbmsc.c index 8a8269539..f1f6ee69c 100644 --- a/nuttx/configs/fire-stm32v2/src/up_usbmsc.c +++ b/nuttx/configs/fire-stm32v2/src/up_usbmsc.c @@ -60,7 +60,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -68,7 +68,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/hymini-stm32v/src/up_nsh.c b/nuttx/configs/hymini-stm32v/src/up_nsh.c index ae1ea03a6..5b823012d 100644 --- a/nuttx/configs/hymini-stm32v/src/up_nsh.c +++ b/nuttx/configs/hymini-stm32v/src/up_nsh.c @@ -110,13 +110,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/hymini-stm32v/src/up_usbmsc.c b/nuttx/configs/hymini-stm32v/src/up_usbmsc.c index 1ce55adcc..da8f02533 100644 --- a/nuttx/configs/hymini-stm32v/src/up_usbmsc.c +++ b/nuttx/configs/hymini-stm32v/src/up_usbmsc.c @@ -78,7 +78,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -86,7 +86,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/kwikstik-k40/src/up_nsh.c b/nuttx/configs/kwikstik-k40/src/up_nsh.c index 884ff3c44..1e52c931e 100644 --- a/nuttx/configs/kwikstik-k40/src/up_nsh.c +++ b/nuttx/configs/kwikstik-k40/src/up_nsh.c @@ -109,13 +109,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/kwikstik-k40/src/up_usbmsc.c b/nuttx/configs/kwikstik-k40/src/up_usbmsc.c index 8051ea1ba..ea97cb99f 100644 --- a/nuttx/configs/kwikstik-k40/src/up_usbmsc.c +++ b/nuttx/configs/kwikstik-k40/src/up_usbmsc.c @@ -74,7 +74,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -82,7 +82,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/lincoln60/src/up_nsh.c b/nuttx/configs/lincoln60/src/up_nsh.c index 2c829837a..a4a679415 100644 --- a/nuttx/configs/lincoln60/src/up_nsh.c +++ b/nuttx/configs/lincoln60/src/up_nsh.c @@ -56,13 +56,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/lm3s6432-s2e/src/up_nsh.c b/nuttx/configs/lm3s6432-s2e/src/up_nsh.c index 46726e753..75107be22 100644 --- a/nuttx/configs/lm3s6432-s2e/src/up_nsh.c +++ b/nuttx/configs/lm3s6432-s2e/src/up_nsh.c @@ -57,13 +57,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/lm3s6965-ek/src/up_nsh.c b/nuttx/configs/lm3s6965-ek/src/up_nsh.c index 409b351f0..24b8b0206 100644 --- a/nuttx/configs/lm3s6965-ek/src/up_nsh.c +++ b/nuttx/configs/lm3s6965-ek/src/up_nsh.c @@ -95,13 +95,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/lm3s8962-ek/src/up_nsh.c b/nuttx/configs/lm3s8962-ek/src/up_nsh.c index 693862184..f12c48988 100644 --- a/nuttx/configs/lm3s8962-ek/src/up_nsh.c +++ b/nuttx/configs/lm3s8962-ek/src/up_nsh.c @@ -95,13 +95,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_nsh.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_nsh.c index b9c39ed16..6165cd9e9 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/src/up_nsh.c +++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_nsh.c @@ -103,13 +103,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_usbmsc.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_usbmsc.c index c43028f1e..937c7857a 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/src/up_usbmsc.c +++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_usbmsc.c @@ -74,7 +74,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -82,7 +82,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/mbed/src/up_nsh.c b/nuttx/configs/mbed/src/up_nsh.c index 3a23ca7a5..883a0da15 100644 --- a/nuttx/configs/mbed/src/up_nsh.c +++ b/nuttx/configs/mbed/src/up_nsh.c @@ -72,13 +72,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/mcu123-lpc214x/src/up_composite.c b/nuttx/configs/mcu123-lpc214x/src/up_composite.c index 3540cdb8a..8feacc971 100644 --- a/nuttx/configs/mcu123-lpc214x/src/up_composite.c +++ b/nuttx/configs/mcu123-lpc214x/src/up_composite.c @@ -75,7 +75,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -83,7 +83,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/mcu123-lpc214x/src/up_nsh.c b/nuttx/configs/mcu123-lpc214x/src/up_nsh.c index 14b5d7d97..c4a56784f 100644 --- a/nuttx/configs/mcu123-lpc214x/src/up_nsh.c +++ b/nuttx/configs/mcu123-lpc214x/src/up_nsh.c @@ -95,13 +95,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/mcu123-lpc214x/src/up_usbmsc.c b/nuttx/configs/mcu123-lpc214x/src/up_usbmsc.c index 79d9344a4..f003d4c3c 100644 --- a/nuttx/configs/mcu123-lpc214x/src/up_usbmsc.c +++ b/nuttx/configs/mcu123-lpc214x/src/up_usbmsc.c @@ -74,7 +74,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -82,7 +82,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/ne64badge/src/up_nsh.c b/nuttx/configs/ne64badge/src/up_nsh.c index 17a52819b..10e0e74d5 100644 --- a/nuttx/configs/ne64badge/src/up_nsh.c +++ b/nuttx/configs/ne64badge/src/up_nsh.c @@ -54,13 +54,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/nucleus2g/src/up_nsh.c b/nuttx/configs/nucleus2g/src/up_nsh.c index 9986c8282..4453d73a1 100644 --- a/nuttx/configs/nucleus2g/src/up_nsh.c +++ b/nuttx/configs/nucleus2g/src/up_nsh.c @@ -97,13 +97,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/nucleus2g/src/up_usbmsc.c b/nuttx/configs/nucleus2g/src/up_usbmsc.c index 8c71a5ce7..f4a533cb6 100644 --- a/nuttx/configs/nucleus2g/src/up_usbmsc.c +++ b/nuttx/configs/nucleus2g/src/up_usbmsc.c @@ -74,7 +74,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -82,7 +82,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c index 99e9c4d9c..f201c8a1b 100644 --- a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c +++ b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c @@ -124,13 +124,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c b/nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c index ce7c75771..5f97aff81 100644 --- a/nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c +++ b/nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c @@ -77,7 +77,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -85,7 +85,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/olimex-lpc2378/src/up_nsh.c b/nuttx/configs/olimex-lpc2378/src/up_nsh.c index 6279a7668..f5ec1fed8 100644 --- a/nuttx/configs/olimex-lpc2378/src/up_nsh.c +++ b/nuttx/configs/olimex-lpc2378/src/up_nsh.c @@ -84,13 +84,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/olimex-strp711/src/up_nsh.c b/nuttx/configs/olimex-strp711/src/up_nsh.c index 21c3efb83..7499a8d8f 100644 --- a/nuttx/configs/olimex-strp711/src/up_nsh.c +++ b/nuttx/configs/olimex-strp711/src/up_nsh.c @@ -99,13 +99,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/pic32-starterkit/src/up_nsh.c b/nuttx/configs/pic32-starterkit/src/up_nsh.c index 0f0f0dffe..f0e745112 100644 --- a/nuttx/configs/pic32-starterkit/src/up_nsh.c +++ b/nuttx/configs/pic32-starterkit/src/up_nsh.c @@ -154,13 +154,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/pic32-starterkit/src/up_usbmsc.c b/nuttx/configs/pic32-starterkit/src/up_usbmsc.c index c645c0fe5..51e450c56 100644 --- a/nuttx/configs/pic32-starterkit/src/up_usbmsc.c +++ b/nuttx/configs/pic32-starterkit/src/up_usbmsc.c @@ -50,7 +50,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -58,7 +58,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/pic32mx7mmb/src/up_nsh.c b/nuttx/configs/pic32mx7mmb/src/up_nsh.c index d063450d3..a1bfbeaa2 100644 --- a/nuttx/configs/pic32mx7mmb/src/up_nsh.c +++ b/nuttx/configs/pic32mx7mmb/src/up_nsh.c @@ -153,13 +153,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/pic32mx7mmb/src/up_usbmsc.c b/nuttx/configs/pic32mx7mmb/src/up_usbmsc.c index fbebaa3d1..d1f473d4f 100644 --- a/nuttx/configs/pic32mx7mmb/src/up_usbmsc.c +++ b/nuttx/configs/pic32mx7mmb/src/up_usbmsc.c @@ -50,7 +50,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -58,7 +58,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/rgmp/include/README.txt b/nuttx/configs/rgmp/include/README.txt index 006f13e7c..78da4eb92 100644 --- a/nuttx/configs/rgmp/include/README.txt +++ b/nuttx/configs/rgmp/include/README.txt @@ -1 +1 @@ -This directory is reserved for RGMP header files +This directory is reserved for RGMP header files diff --git a/nuttx/configs/rgmp/src/README.txt b/nuttx/configs/rgmp/src/README.txt index d7d216e24..3d0f237c0 100644 --- a/nuttx/configs/rgmp/src/README.txt +++ b/nuttx/configs/rgmp/src/README.txt @@ -1 +1 @@ -This directory is reserved for RGMP source files +This directory is reserved for RGMP source files diff --git a/nuttx/configs/sam3u-ek/src/up_nsh.c b/nuttx/configs/sam3u-ek/src/up_nsh.c index e8c0df87b..7b3174a74 100644 --- a/nuttx/configs/sam3u-ek/src/up_nsh.c +++ b/nuttx/configs/sam3u-ek/src/up_nsh.c @@ -100,13 +100,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_rawprintf(__VA_ARGS__) +# define message(...) syslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_rawprintf +# define message syslog # else # define message printf # endif diff --git a/nuttx/configs/sam3u-ek/src/up_usbmsc.c b/nuttx/configs/sam3u-ek/src/up_usbmsc.c index 7e04ee04a..dfe2e2c49 100644 --- a/nuttx/configs/sam3u-ek/src/up_usbmsc.c +++ b/nuttx/configs/sam3u-ek/src/up_usbmsc.c @@ -76,7 +76,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -84,7 +84,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/shenzhou/src/up_composite.c b/nuttx/configs/shenzhou/src/up_composite.c index 81c33dcc8..fb1640908 100644 --- a/nuttx/configs/shenzhou/src/up_composite.c +++ b/nuttx/configs/shenzhou/src/up_composite.c @@ -60,7 +60,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -68,7 +68,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/shenzhou/src/up_ili93xx.c b/nuttx/configs/shenzhou/src/up_ili93xx.c index a89e20d02..1a099f820 100644 --- a/nuttx/configs/shenzhou/src/up_ili93xx.c +++ b/nuttx/configs/shenzhou/src/up_ili93xx.c @@ -833,14 +833,14 @@ static void stm32_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixels { int i, j; - lib_rawprintf("\n%s:\n", msg); + syslog("\n%s:\n", msg); for (i = 0; i < npixels; i += 16) { up_putc(' '); - lib_rawprintf(" "); + syslog(" "); for (j = 0; j < 16; j++) { - lib_rawprintf(" %04x", *run++); + syslog(" %04x", *run++); } up_putc('\n'); } diff --git a/nuttx/configs/shenzhou/src/up_nsh.c b/nuttx/configs/shenzhou/src/up_nsh.c index 685281f5d..d68a734e0 100644 --- a/nuttx/configs/shenzhou/src/up_nsh.c +++ b/nuttx/configs/shenzhou/src/up_nsh.c @@ -149,13 +149,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/shenzhou/src/up_usbmsc.c b/nuttx/configs/shenzhou/src/up_usbmsc.c index 8566aedfd..eaecfb496 100644 --- a/nuttx/configs/shenzhou/src/up_usbmsc.c +++ b/nuttx/configs/shenzhou/src/up_usbmsc.c @@ -60,7 +60,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -68,7 +68,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/sim/cxxtest/defconfig b/nuttx/configs/sim/cxxtest/defconfig index 6ac45d44d..b12eda172 100644 --- a/nuttx/configs/sim/cxxtest/defconfig +++ b/nuttx/configs/sim/cxxtest/defconfig @@ -36,7 +36,7 @@ CONFIG_ARCH_FLOAT_H=y # CONFIG_DEBUG=y CONFIG_DEBUG_VERBOSE=y -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/sim/ostest/defconfig b/nuttx/configs/sim/ostest/defconfig index 65f5330fc..07a0f71b4 100644 --- a/nuttx/configs/sim/ostest/defconfig +++ b/nuttx/configs/sim/ostest/defconfig @@ -40,7 +40,7 @@ CONFIG_HOST_LINUX=y # CONFIG_DEBUG=y CONFIG_DEBUG_VERBOSE=y -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/stm3210e-eval/src/up_composite.c b/nuttx/configs/stm3210e-eval/src/up_composite.c index e80e0fcb4..de5759c78 100644 --- a/nuttx/configs/stm3210e-eval/src/up_composite.c +++ b/nuttx/configs/stm3210e-eval/src/up_composite.c @@ -79,7 +79,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -87,7 +87,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/stm3210e-eval/src/up_lcd.c b/nuttx/configs/stm3210e-eval/src/up_lcd.c index 8b832aafb..81cc3f20a 100644 --- a/nuttx/configs/stm3210e-eval/src/up_lcd.c +++ b/nuttx/configs/stm3210e-eval/src/up_lcd.c @@ -704,14 +704,14 @@ static void stm3210e_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npix { int i, j; - lib_rawprintf("\n%s:\n", msg); + syslog("\n%s:\n", msg); for (i = 0; i < npixels; i += 16) { up_putc(' '); - lib_rawprintf(" "); + syslog(" "); for (j = 0; j < 16; j++) { - lib_rawprintf(" %04x", *run++); + syslog(" %04x", *run++); } up_putc('\n'); } diff --git a/nuttx/configs/stm3210e-eval/src/up_nsh.c b/nuttx/configs/stm3210e-eval/src/up_nsh.c index 3e7c2013c..544a0e75e 100644 --- a/nuttx/configs/stm3210e-eval/src/up_nsh.c +++ b/nuttx/configs/stm3210e-eval/src/up_nsh.c @@ -108,13 +108,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/stm3210e-eval/src/up_pmbuttons.c b/nuttx/configs/stm3210e-eval/src/up_pmbuttons.c index c0f16ee8c..cc6f3cae0 100644 --- a/nuttx/configs/stm3210e-eval/src/up_pmbuttons.c +++ b/nuttx/configs/stm3210e-eval/src/up_pmbuttons.c @@ -308,9 +308,9 @@ void up_pmbuttons(void) if (oldhandler != NULL) { - lib_lowprintf("WARNING: oldhandler:%p is not NULL! " - "Button events may be lost or aliased!\n", - oldhandler); + lowsyslog("WARNING: oldhandler:%p is not NULL! " + "Button events may be lost or aliased!\n", + oldhandler); } } #endif diff --git a/nuttx/configs/stm3210e-eval/src/up_usbmsc.c b/nuttx/configs/stm3210e-eval/src/up_usbmsc.c index dce463abc..d1727174e 100644 --- a/nuttx/configs/stm3210e-eval/src/up_usbmsc.c +++ b/nuttx/configs/stm3210e-eval/src/up_usbmsc.c @@ -78,7 +78,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -86,7 +86,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/stm3220g-eval/src/up_lcd.c b/nuttx/configs/stm3220g-eval/src/up_lcd.c index a1fcceef7..4a1ce0953 100644 --- a/nuttx/configs/stm3220g-eval/src/up_lcd.c +++ b/nuttx/configs/stm3220g-eval/src/up_lcd.c @@ -550,14 +550,14 @@ static void stm3220g_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npix { int i, j; - lib_rawprintf("\n%s:\n", msg); + syslog("\n%s:\n", msg); for (i = 0; i < npixels; i += 16) { up_putc(' '); - lib_rawprintf(" "); + syslog(" "); for (j = 0; j < 16; j++) { - lib_rawprintf(" %04x", *run++); + syslog(" %04x", *run++); } up_putc('\n'); } diff --git a/nuttx/configs/stm3220g-eval/src/up_nsh.c b/nuttx/configs/stm3220g-eval/src/up_nsh.c index e1359de96..068deb1a6 100644 --- a/nuttx/configs/stm3220g-eval/src/up_nsh.c +++ b/nuttx/configs/stm3220g-eval/src/up_nsh.c @@ -122,13 +122,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/stm3240g-eval/discover/defconfig b/nuttx/configs/stm3240g-eval/discover/defconfig index e11d39ce1..37b74972f 100644 --- a/nuttx/configs/stm3240g-eval/discover/defconfig +++ b/nuttx/configs/stm3240g-eval/discover/defconfig @@ -35,7 +35,7 @@ CONFIG_RAW_BINARY=y # CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/stm3240g-eval/src/up_lcd.c b/nuttx/configs/stm3240g-eval/src/up_lcd.c index 45e4a2b57..74088dc5e 100644 --- a/nuttx/configs/stm3240g-eval/src/up_lcd.c +++ b/nuttx/configs/stm3240g-eval/src/up_lcd.c @@ -550,14 +550,14 @@ static void stm3240g_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npix { int i, j; - lib_rawprintf("\n%s:\n", msg); + syslog("\n%s:\n", msg); for (i = 0; i < npixels; i += 16) { up_putc(' '); - lib_rawprintf(" "); + syslog(" "); for (j = 0; j < 16; j++) { - lib_rawprintf(" %04x", *run++); + syslog(" %04x", *run++); } up_putc('\n'); } diff --git a/nuttx/configs/stm3240g-eval/src/up_nsh.c b/nuttx/configs/stm3240g-eval/src/up_nsh.c index c106e9918..596f902db 100644 --- a/nuttx/configs/stm3240g-eval/src/up_nsh.c +++ b/nuttx/configs/stm3240g-eval/src/up_nsh.c @@ -128,13 +128,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/stm3240g-eval/xmlrpc/defconfig b/nuttx/configs/stm3240g-eval/xmlrpc/defconfig index 4f621d453..daa1efb8a 100644 --- a/nuttx/configs/stm3240g-eval/xmlrpc/defconfig +++ b/nuttx/configs/stm3240g-eval/xmlrpc/defconfig @@ -35,7 +35,7 @@ CONFIG_RAW_BINARY=y # CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/stm32f4discovery/src/up_nsh.c b/nuttx/configs/stm32f4discovery/src/up_nsh.c index 2a933569f..fd3fe5cd9 100644 --- a/nuttx/configs/stm32f4discovery/src/up_nsh.c +++ b/nuttx/configs/stm32f4discovery/src/up_nsh.c @@ -89,13 +89,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/stm32f4discovery/src/up_pmbuttons.c b/nuttx/configs/stm32f4discovery/src/up_pmbuttons.c index aa72e3da1..4bc241fce 100644 --- a/nuttx/configs/stm32f4discovery/src/up_pmbuttons.c +++ b/nuttx/configs/stm32f4discovery/src/up_pmbuttons.c @@ -139,7 +139,7 @@ void up_pmbuttons(void) if (oldhandler != NULL) { - lib_lowprintf("WARNING: oldhandler:%p is not NULL! " + lowsyslog("WARNING: oldhandler:%p is not NULL! " "Button events may be lost or aliased!\n", oldhandler); } diff --git a/nuttx/configs/sure-pic32mx/src/up_nsh.c b/nuttx/configs/sure-pic32mx/src/up_nsh.c index 4b68350ed..94ae10d21 100644 --- a/nuttx/configs/sure-pic32mx/src/up_nsh.c +++ b/nuttx/configs/sure-pic32mx/src/up_nsh.c @@ -124,13 +124,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/teensy/src/up_usbmsc.c b/nuttx/configs/teensy/src/up_usbmsc.c index fcf7fe2f5..0b944eda3 100644 --- a/nuttx/configs/teensy/src/up_usbmsc.c +++ b/nuttx/configs/teensy/src/up_usbmsc.c @@ -78,7 +78,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -86,7 +86,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/twr-k60n512/src/up_nsh.c b/nuttx/configs/twr-k60n512/src/up_nsh.c index 3bb4e8527..8069e3f96 100644 --- a/nuttx/configs/twr-k60n512/src/up_nsh.c +++ b/nuttx/configs/twr-k60n512/src/up_nsh.c @@ -109,13 +109,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/twr-k60n512/src/up_usbmsc.c b/nuttx/configs/twr-k60n512/src/up_usbmsc.c index 1a8f7a70d..c893551ca 100644 --- a/nuttx/configs/twr-k60n512/src/up_usbmsc.c +++ b/nuttx/configs/twr-k60n512/src/up_usbmsc.c @@ -74,7 +74,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -82,7 +82,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/ubw32/src/up_nsh.c b/nuttx/configs/ubw32/src/up_nsh.c index 5e5895b63..7c6452004 100644 --- a/nuttx/configs/ubw32/src/up_nsh.c +++ b/nuttx/configs/ubw32/src/up_nsh.c @@ -54,13 +54,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/vsn/src/usbmsc.c b/nuttx/configs/vsn/src/usbmsc.c index c0eebf6bf..198e27dea 100644 --- a/nuttx/configs/vsn/src/usbmsc.c +++ b/nuttx/configs/vsn/src/usbmsc.c @@ -79,7 +79,7 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # define msgflush() # else # define message(...) printf(__VA_ARGS__) @@ -87,7 +87,7 @@ # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # define msgflush() # else # define message printf diff --git a/nuttx/configs/vsn/src/vsn.h b/nuttx/configs/vsn/src/vsn.h index eb999f246..f8414f36c 100644 --- a/nuttx/configs/vsn/src/vsn.h +++ b/nuttx/configs/vsn/src/vsn.h @@ -175,13 +175,13 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) +# define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else # ifdef CONFIG_DEBUG -# define message lib_lowprintf +# define message lowsyslog # else # define message printf # endif diff --git a/nuttx/configs/z16f2800100zcog/ostest/defconfig b/nuttx/configs/z16f2800100zcog/ostest/defconfig index 64828738f..50c3a96c6 100644 --- a/nuttx/configs/z16f2800100zcog/ostest/defconfig +++ b/nuttx/configs/z16f2800100zcog/ostest/defconfig @@ -44,7 +44,7 @@ CONFIG_WINDOWS_CYGWIN=y # CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/z16f2800100zcog/pashello/README.txt b/nuttx/configs/z16f2800100zcog/pashello/README.txt index bc9828184..97d326097 100644 --- a/nuttx/configs/z16f2800100zcog/pashello/README.txt +++ b/nuttx/configs/z16f2800100zcog/pashello/README.txt @@ -1,12 +1,12 @@ -README.txt -^^^^^^^^^^ - -pashello.zfpproj is a simple ZDS-II project that will allow you - to use the ZDS-II debugger. Before using, copy the following - files from the toplevel directory: - - nuttx.hex, nuttx.map, nuttx.lod - - to this directory as: - - pashello.hex, pashello.map, pashello.lod +README.txt +^^^^^^^^^^ + +pashello.zfpproj is a simple ZDS-II project that will allow you + to use the ZDS-II debugger. Before using, copy the following + files from the toplevel directory: + + nuttx.hex, nuttx.map, nuttx.lod + + to this directory as: + + pashello.hex, pashello.map, pashello.lod diff --git a/nuttx/configs/z16f2800100zcog/pashello/defconfig b/nuttx/configs/z16f2800100zcog/pashello/defconfig index ba99283d3..96bff8dee 100644 --- a/nuttx/configs/z16f2800100zcog/pashello/defconfig +++ b/nuttx/configs/z16f2800100zcog/pashello/defconfig @@ -44,7 +44,7 @@ CONFIG_WINDOWS_CYGWIN=y # CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/z8encore000zco/ostest/defconfig b/nuttx/configs/z8encore000zco/ostest/defconfig index 7bd512727..605bec669 100644 --- a/nuttx/configs/z8encore000zco/ostest/defconfig +++ b/nuttx/configs/z8encore000zco/ostest/defconfig @@ -44,7 +44,7 @@ CONFIG_WINDOWS_CYGWIN=y # CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/configs/z8f64200100kit/ostest/defconfig b/nuttx/configs/z8f64200100kit/ostest/defconfig index e98e41561..aabfc6ee4 100644 --- a/nuttx/configs/z8f64200100kit/ostest/defconfig +++ b/nuttx/configs/z8f64200100kit/ostest/defconfig @@ -44,7 +44,7 @@ CONFIG_WINDOWS_CYGWIN=y # CONFIG_DEBUG=y # CONFIG_DEBUG_VERBOSE is not set -# CONFIG_DEBUG_ENABLE is not set +# CONFIG_SYSLOG_ENABLE is not set # # Subsystem Debug Options diff --git a/nuttx/drivers/lcd/mio283qt2.c b/nuttx/drivers/lcd/mio283qt2.c index 1758e230c..4c8835eef 100644 --- a/nuttx/drivers/lcd/mio283qt2.c +++ b/nuttx/drivers/lcd/mio283qt2.c @@ -495,14 +495,14 @@ static void mio283qt2_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npi { int i, j; - lib_rawprintf("\n%s:\n", msg); + syslog("\n%s:\n", msg); for (i = 0; i < npixels; i += 16) { up_putc(' '); - lib_rawprintf(" "); + syslog(" "); for (j = 0; j < 16; j++) { - lib_rawprintf(" %04x", *run++); + syslog(" %04x", *run++); } up_putc('\n'); } diff --git a/nuttx/drivers/lcd/ssd1289.c b/nuttx/drivers/lcd/ssd1289.c index e42b5bded..d78688be5 100644 --- a/nuttx/drivers/lcd/ssd1289.c +++ b/nuttx/drivers/lcd/ssd1289.c @@ -497,14 +497,14 @@ static void ssd1289_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixe { int i, j; - lib_rawprintf("\n%s:\n", msg); + syslog("\n%s:\n", msg); for (i = 0; i < npixels; i += 16) { up_putc(' '); - lib_rawprintf(" "); + syslog(" "); for (j = 0; j < 16; j++) { - lib_rawprintf(" %04x", *run++); + syslog(" %04x", *run++); } up_putc('\n'); } diff --git a/nuttx/drivers/mmcsd/mmcsd_debug.c b/nuttx/drivers/mmcsd/mmcsd_debug.c index 0bd7f896e..8cb5b2a2a 100644 --- a/nuttx/drivers/mmcsd/mmcsd_debug.c +++ b/nuttx/drivers/mmcsd/mmcsd_debug.c @@ -56,9 +56,9 @@ /* This needs to match the logic in include/debug.h */ #ifdef CONFIG_CPP_HAVE_VARARGS -# define message(format, arg...) lib_rawprintf(format, ##arg) +# define message(format, arg...) syslog(format, ##arg) #else -# define message lib_rawprintf +# define message syslog #endif /**************************************************************************** diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c index 2346ee2d6..203259aeb 100644 --- a/nuttx/drivers/net/enc28j60.c +++ b/nuttx/drivers/net/enc28j60.c @@ -179,10 +179,10 @@ /* Debug ********************************************************************/ #ifdef CONFIG_ENC28J60_REGDEBUG -# define enc_wrdump(a,v) lib_lowprintf("ENC28J60: %02x<-%02x\n", a, v); -# define enc_rddump(a,v) lib_lowprintf("ENC28J60: %02x->%02x\n", a, v); -# define enc_cmddump(c) lib_lowprintf("ENC28J60: CMD: %02x\n", c); -# define enc_bmdump(c,b,s) lib_lowprintf("ENC28J60: CMD: %02x buffer: %p length: %d\n", c,b,s); +# define enc_wrdump(a,v) lowsyslog("ENC28J60: %02x<-%02x\n", a, v); +# define enc_rddump(a,v) lowsyslog("ENC28J60: %02x->%02x\n", a, v); +# define enc_cmddump(c) lowsyslog("ENC28J60: CMD: %02x\n", c); +# define enc_bmdump(c,b,s) lowsyslog("ENC28J60: CMD: %02x buffer: %p length: %d\n", c,b,s); #else # define enc_wrdump(a,v) # define enc_rddump(a,v) @@ -773,56 +773,56 @@ static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg, #if 0 /* Sometimes useful */ static void enc_rxdump(FAR struct enc_driver_s *priv) { - lib_lowprintf("Rx Registers:\n"); - lib_lowprintf(" EIE: %02x EIR: %02x\n", - enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR)); - lib_lowprintf(" ESTAT: %02x ECON1: %02x ECON2: %02x\n", - enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1), - enc_rdgreg(priv, ENC_ECON2)); - lib_lowprintf(" ERXST: %02x %02x\n", - enc_rdbreg(priv, ENC_ERXSTH), enc_rdbreg(priv, ENC_ERXSTL)); - lib_lowprintf(" ERXND: %02x %02x\n", - enc_rdbreg(priv, ENC_ERXNDH), enc_rdbreg(priv, ENC_ERXNDL)); - lib_lowprintf(" ERXRDPT: %02x %02x\n", - enc_rdbreg(priv, ENC_ERXRDPTH), enc_rdbreg(priv, ENC_ERXRDPTL)); - lib_lowprintf(" ERXFCON: %02x EPKTCNT: %02x\n", - enc_rdbreg(priv, ENC_ERXFCON), enc_rdbreg(priv, ENC_EPKTCNT)); - lib_lowprintf(" MACON1: %02x MACON3: %02x\n", - enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3)); - lib_lowprintf(" MAMXFL: %02x %02x\n", - enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL)); - lib_lowprintf(" MAADR: %02x:%02x:%02x:%02x:%02x:%02x\n", - enc_rdbreg(priv, ENC_MAADR1), enc_rdbreg(priv, ENC_MAADR2), - enc_rdbreg(priv, ENC_MAADR3), enc_rdbreg(priv, ENC_MAADR4), - enc_rdbreg(priv, ENC_MAADR5), enc_rdbreg(priv, ENC_MAADR6)); + lowsyslog("Rx Registers:\n"); + lowsyslog(" EIE: %02x EIR: %02x\n", + enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR)); + lowsyslog(" ESTAT: %02x ECON1: %02x ECON2: %02x\n", + enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1), + enc_rdgreg(priv, ENC_ECON2)); + lowsyslog(" ERXST: %02x %02x\n", + enc_rdbreg(priv, ENC_ERXSTH), enc_rdbreg(priv, ENC_ERXSTL)); + lowsyslog(" ERXND: %02x %02x\n", + enc_rdbreg(priv, ENC_ERXNDH), enc_rdbreg(priv, ENC_ERXNDL)); + lowsyslog(" ERXRDPT: %02x %02x\n", + enc_rdbreg(priv, ENC_ERXRDPTH), enc_rdbreg(priv, ENC_ERXRDPTL)); + lowsyslog(" ERXFCON: %02x EPKTCNT: %02x\n", + enc_rdbreg(priv, ENC_ERXFCON), enc_rdbreg(priv, ENC_EPKTCNT)); + lowsyslog(" MACON1: %02x MACON3: %02x\n", + enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3)); + lowsyslog(" MAMXFL: %02x %02x\n", + enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL)); + lowsyslog(" MAADR: %02x:%02x:%02x:%02x:%02x:%02x\n", + enc_rdbreg(priv, ENC_MAADR1), enc_rdbreg(priv, ENC_MAADR2), + enc_rdbreg(priv, ENC_MAADR3), enc_rdbreg(priv, ENC_MAADR4), + enc_rdbreg(priv, ENC_MAADR5), enc_rdbreg(priv, ENC_MAADR6)); } #endif #if 0 /* Sometimes useful */ static void enc_txdump(FAR struct enc_driver_s *priv) { - lib_lowprintf("Tx Registers:\n"); - lib_lowprintf(" EIE: %02x EIR: %02x ESTAT: %02x\n", - enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR),); - lib_lowprintf(" ESTAT: %02x ECON1: %02x\n", - enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1)); - lib_lowprintf(" ETXST: %02x %02x\n", - enc_rdbreg(priv, ENC_ETXSTH), enc_rdbreg(priv, ENC_ETXSTL)); - lib_lowprintf(" ETXND: %02x %02x\n", - enc_rdbreg(priv, ENC_ETXNDH), enc_rdbreg(priv, ENC_ETXNDL)); - lib_lowprintf(" MACON1: %02x MACON3: %02x MACON4: %02x\n", - enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3), - enc_rdbreg(priv, ENC_MACON4)); - lib_lowprintf(" MACON1: %02x MACON3: %02x MACON4: %02x\n", - enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3), - enc_rdbreg(priv, ENC_MACON4)); - lib_lowprintf(" MABBIPG: %02x MAIPG %02x %02x\n", - enc_rdbreg(priv, ENC_MABBIPG), enc_rdbreg(priv, ENC_MAIPGH), - enc_rdbreg(priv, ENC_MAIPGL)); - lib_lowprintf(" MACLCON1: %02x MACLCON2: %02x\n", - enc_rdbreg(priv, ENC_MACLCON1), enc_rdbreg(priv, ENC_MACLCON2)); - lib_lowprintf(" MAMXFL: %02x %02x\n", - enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL)); + lowsyslog("Tx Registers:\n"); + lowsyslog(" EIE: %02x EIR: %02x ESTAT: %02x\n", + enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR),); + lowsyslog(" ESTAT: %02x ECON1: %02x\n", + enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1)); + lowsyslog(" ETXST: %02x %02x\n", + enc_rdbreg(priv, ENC_ETXSTH), enc_rdbreg(priv, ENC_ETXSTL)); + lowsyslog(" ETXND: %02x %02x\n", + enc_rdbreg(priv, ENC_ETXNDH), enc_rdbreg(priv, ENC_ETXNDL)); + lowsyslog(" MACON1: %02x MACON3: %02x MACON4: %02x\n", + enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3), + enc_rdbreg(priv, ENC_MACON4)); + lowsyslog(" MACON1: %02x MACON3: %02x MACON4: %02x\n", + enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3), + enc_rdbreg(priv, ENC_MACON4)); + lowsyslog(" MABBIPG: %02x MAIPG %02x %02x\n", + enc_rdbreg(priv, ENC_MABBIPG), enc_rdbreg(priv, ENC_MAIPGH), + enc_rdbreg(priv, ENC_MAIPGL)); + lowsyslog(" MACLCON1: %02x MACLCON2: %02x\n", + enc_rdbreg(priv, ENC_MACLCON1), enc_rdbreg(priv, ENC_MACLCON2)); + lowsyslog(" MAMXFL: %02x %02x\n", + enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL)); } #endif diff --git a/nuttx/drivers/syslog/ramlog.c b/nuttx/drivers/syslog/ramlog.c index b3a2ad0f5..08bbbfb59 100644 --- a/nuttx/drivers/syslog/ramlog.c +++ b/nuttx/drivers/syslog/ramlog.c @@ -726,10 +726,10 @@ int ramlog_sysloginit(void) * * Description: * This is the low-level system logging interface. The debugging/syslogging - * interfaces are lib_rawprintf() and lib_lowprinf(). The difference is - * the lib_rawprintf() writes to fd=1 (stdout) and lib_lowprintf() uses + * interfaces are syslog() and lowsyslog(). The difference is that + * the syslog() internface writes to fd=1 (stdout) whereas lowsyslog() uses * a lower level interface that works from interrupt handlers. This - * function is a a low-level interface used to implement lib_lowprintf() + * function is a a low-level interface used to implement lowsyslog() * when CONFIG_RAMLOG_SYSLOG=y and CONFIG_SYSLOG=y * ****************************************************************************/ diff --git a/nuttx/drivers/usbdev/usbdev_trace.c b/nuttx/drivers/usbdev/usbdev_trace.c index c8cc09292..c332c1358 100644 --- a/nuttx/drivers/usbdev/usbdev_trace.c +++ b/nuttx/drivers/usbdev/usbdev_trace.c @@ -168,9 +168,9 @@ void usbtrace(uint16_t event, uint16_t value) } } #else - /* Just print the data using lib_lowprintf */ + /* Just print the data using lowsyslog */ - usbtrace_trprintf((trprintf_t)lib_lowprintf, event, value); + usbtrace_trprintf((trprintf_t)lowsyslog, event, value); #endif } irqrestore(flags); diff --git a/nuttx/drivers/usbdev/usbmsc.h b/nuttx/drivers/usbdev/usbmsc.h index 883a49951..da35ae923 100644 --- a/nuttx/drivers/usbdev/usbmsc.h +++ b/nuttx/drivers/usbdev/usbmsc.h @@ -199,9 +199,9 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_DEBUG # ifdef CONFIG_ARCH_LOWPUTC -# define dbgprintf(format, arg...) lib_lowprintf(format, ##arg) +# define dbgprintf(format, arg...) lowsyslog(format, ##arg) # else -# define dbgprintf(format, arg...) lib_rawprintf(format, ##arg) +# define dbgprintf(format, arg...) syslog(format, ##arg) # endif # else # define dbgprintf(x...) @@ -209,9 +209,9 @@ #else # ifdef CONFIG_DEBUG # ifdef CONFIG_ARCH_LOWPUTC -# define dbgprintf lib_lowprintf +# define dbgprintf lowsyslog # else -# define dbgprintf lib_rawprintf +# define dbgprintf syslog # endif # else # define dbgprintf (void) diff --git a/nuttx/fs/fs_syslog.c b/nuttx/fs/fs_syslog.c index ab6cec51e..779263a3c 100644 --- a/nuttx/fs/fs_syslog.c +++ b/nuttx/fs/fs_syslog.c @@ -357,10 +357,10 @@ int syslog_initialize(void) * * Description: * This is the low-level system logging interface. The debugging/syslogging - * interfaces are lib_rawprintf() and lib_lowprinf(). The difference is - * the lib_rawprintf() writes to fd=1 (stdout) and lib_lowprintf() uses + * interfaces are syslog() and lowsyslog(). The difference is is that + * the syslog() function writes to fd=1 (stdout) whereas lowsyslog() uses * a lower level interface that works from interrupt handlers. This - * function is a a low-level interface used to implement lib_lowprintf(). + * function is a a low-level interface used to implement lowsyslog(). * ****************************************************************************/ diff --git a/nuttx/fs/nxffs/nxffs_dump.c b/nuttx/fs/nxffs/nxffs_dump.c index 6a89aaf1d..9caac4c4b 100644 --- a/nuttx/fs/nxffs/nxffs_dump.c +++ b/nuttx/fs/nxffs/nxffs_dump.c @@ -60,7 +60,7 @@ */ #undef fdbg -#define fdbg lib_rawprintf +#define fdbg syslog /**************************************************************************** * Private Types diff --git a/nuttx/include/debug.h b/nuttx/include/debug.h index aa5efd432..70ae2ee18 100644 --- a/nuttx/include/debug.h +++ b/nuttx/include/debug.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/debug.h * - * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -43,7 +43,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions @@ -104,22 +104,22 @@ #ifdef CONFIG_DEBUG # define dbg(format, arg...) \ - lib_rawprintf(EXTRA_FMT format EXTRA_ARG, ##arg) + syslog(EXTRA_FMT format EXTRA_ARG, ##arg) # ifdef CONFIG_ARCH_LOWPUTC # define lldbg(format, arg...) \ - lib_lowprintf(EXTRA_FMT format EXTRA_ARG, ##arg) + lowsyslog(EXTRA_FMT format EXTRA_ARG, ##arg) # else # define lldbg(x...) # endif # ifdef CONFIG_DEBUG_VERBOSE # define vdbg(format, arg...) \ - lib_rawprintf(EXTRA_FMT format EXTRA_ARG, ##arg) + syslog(EXTRA_FMT format EXTRA_ARG, ##arg) # ifdef CONFIG_ARCH_LOWPUTC # define llvdbg(format, arg...) \ - lib_lowprintf(EXTRA_FMT format EXTRA_ARG, ##arg) + lowsyslog(EXTRA_FMT format EXTRA_ARG, ##arg) # else # define llvdbg(x...) # endif @@ -576,29 +576,16 @@ extern "C" { #endif -/* These low-level debug APIs are provided by the NuttX library. If the - * cross-compiler's pre-processor supports a variable number of macro - * arguments, then the macros below will map all debug statements to one - * or the other of the following. - */ - -int lib_rawprintf(FAR const char *format, ...); - -#ifdef CONFIG_ARCH_LOWPUTC -int lib_lowprintf(FAR const char *format, ...); -#endif - /* Dump a buffer of data */ void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen); -/* Enable or disable debug output */ - -#ifdef CONFIG_DEBUG_ENABLE -void dbg_enable(bool enable); -#endif - -/* If the cross-compiler's pre-processor does not support variable length +/* The system logging interfaces are pnormally accessed via the macros + * provided above. If the cross-compiler's C pre-processor supports a + * variable number of macro arguments, then those macros below will map all + * debug statements to the logging interfaces declared in syslog.h. + * + * If the cross-compiler's pre-processor does not support variable length * arguments, then these additional APIs will be built. */ diff --git a/nuttx/include/nuttx/syslog.h b/nuttx/include/nuttx/syslog.h index 3c340d23a..bb3c8f493 100644 --- a/nuttx/include/nuttx/syslog.h +++ b/nuttx/include/nuttx/syslog.h @@ -116,10 +116,10 @@ EXTERN int syslog_initialize(void); * * Description: * This is the low-level system logging interface. The debugging/syslogging - * interfaces are lib_rawprintf() and lib_lowprinf(). The difference is - * the lib_rawprintf() writes to fd=1 (stdout) and lib_lowprintf() uses + * interfaces are syslog() and lowsyslog(). The difference is that + * the syslog() internface writes to fd=1 (stdout) whereas lowsyslog() uses * a lower level interface that works from interrupt handlers. This - * function is a a low-level interface used to implement lib_lowprintf(). + * function is a a low-level interface used to implement lowsyslog(). * ****************************************************************************/ diff --git a/nuttx/include/syslog.h b/nuttx/include/syslog.h new file mode 100644 index 000000000..cfb2db97b --- /dev/null +++ b/nuttx/include/syslog.h @@ -0,0 +1,94 @@ +/**************************************************************************** + * include/syslog.h + * + * Copyright (C) 2013 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 NuttX 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. + * + ****************************************************************************/ + +#ifndef __INCLUDE_SYSLOG_H +#define __INCLUDE_SYSLOG_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#if defined(__cplusplus) +extern "C" +{ +#endif + +/* These low-level debug APIs are provided by the NuttX library. These are + * normally accessed via the macros in debug.h. If the cross-compiler's + * C pre-processor supports a variable number of macro arguments, then those + * macros below will map all debug statements to one or the other of the + * following. + */ + +int syslog(FAR const char *format, ...); +int vsyslog(const char *src, va_list ap); + +#ifdef CONFIG_ARCH_LOWPUTC +int lowsyslog(FAR const char *format, ...); +int lowvsyslog(const char *src, va_list ap); +#endif + +/* Enable or disable syslog output */ + +#ifdef CONFIG_SYSLOG_ENABLE +void syslog_enable(bool enable); +#endif + +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_SYSLOG_H */ diff --git a/nuttx/libc/lib.csv b/nuttx/libc/lib.csv index 171f64e9b..29cdf39a6 100644 --- a/nuttx/libc/lib.csv +++ b/nuttx/libc/lib.csv @@ -16,7 +16,6 @@ "crc32","crc32.h","","uint32_t","FAR const uint8_t *","size_t" "crc32part","crc32.h","","uint32_t","FAR const uint8_t *","size_t","uint32_t" "dbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG)","int","const char *","..." -"dbg_enable","debug.h","defined(CONFIG_DEBUG_ENABLE)","void","bool" "dirname","libgen.h","","FAR char","FAR char *" "dq_addafter","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *" "dq_addbefore","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *" @@ -59,11 +58,10 @@ "inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *" "labs","stdlib.h","","long int","long int" "lib_dumpbuffer","debug.h","","void","FAR const char *","FAR const uint8_t *","unsigned int" -"lib_lowprintf","debug.h","","int","FAR const char *","..." -"lib_rawprintf","debug.h","","int","FAR const char *","..." "llabs","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long int","long long int" "lldbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..." "llvdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..." +"lowsyslog","syslog.h","","int","FAR const char *","..." "match","","","int","const char *","const char *" "memccpy","string.h","","FAR void","FAR void *","FAR const void *","int c","size_t" "memchr","string.h","","FAR void","FAR const void *","int c","size_t" @@ -154,6 +152,8 @@ "strtoll","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long","const char *nptr","char **endptr","int base" "strtoul","stdlib.h","","unsigned long","const char *","char **","int" "strtoull","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","unsigned long long","const char *","char **","int" +"syslog","syslog.h","","int","FAR const char *","..." +"syslog_enable","syslog.h","defined(CONFIG_SYSLOG_ENABLE)","void","bool" "tcflush","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int" "tcgetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","FAR struct termios *" "tcsetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int","FAR const struct termios *" diff --git a/nuttx/libc/lib_internal.h b/nuttx/libc/lib_internal.h index c09c751d4..17adff417 100644 --- a/nuttx/libc/lib_internal.h +++ b/nuttx/libc/lib_internal.h @@ -106,8 +106,8 @@ /* Debug output is initially disabled */ -#ifdef CONFIG_DEBUG_ENABLE -extern bool g_dbgenable; +#ifdef CONFIG_SYSLOG_ENABLE +extern bool g_syslogenable; #endif /**************************************************************************** @@ -137,14 +137,6 @@ int lib_sprintf(FAR struct lib_outstream_s *obj, int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list ap); -/* Defined lib_rawprintf.c */ - -int lib_rawvprintf(const char *src, va_list ap); - -/* Defined lib_lowprintf.c */ - -int lib_lowvprintf(const char *src, va_list ap); - /* Defined in lib_dtoa.c */ #ifdef CONFIG_LIBC_FLOATINGPOINT diff --git a/nuttx/libc/misc/lib_dbg.c b/nuttx/libc/misc/lib_dbg.c index 5605ff828..921a4e24d 100644 --- a/nuttx/libc/misc/lib_dbg.c +++ b/nuttx/libc/misc/lib_dbg.c @@ -50,8 +50,8 @@ /* Debug output is initially disabled */ -#ifdef CONFIG_DEBUG_ENABLE -bool g_dbgenable; +#ifdef CONFIG_SYSLOG_ENABLE +bool g_syslogenable; #endif /**************************************************************************** @@ -59,17 +59,17 @@ bool g_dbgenable; ****************************************************************************/ /**************************************************************************** - * Name: dbg_enable + * Name: syslog_enable * * Description: * Enable or disable debug output. * ****************************************************************************/ -#ifdef CONFIG_DEBUG_ENABLE -void dbg_enable(bool enable) +#ifdef CONFIG_SYSLOG_ENABLE +void syslog_enable(bool enable) { - g_dbgenable = enable; + g_syslogenable = enable; } #endif @@ -89,13 +89,13 @@ int dbg(const char *format, ...) va_list ap; int ret; -#ifdef CONFIG_DEBUG_ENABLE +#ifdef CONFIG_SYSLOG_ENABLE ret = 0; - if (g_dbgenable) + if (g_syslogenable) #endif { va_start(ap, format); - ret = lib_rawvprintf(format, ap); + ret = vsyslog(format, ap); va_end(ap); } @@ -108,13 +108,13 @@ int lldbg(const char *format, ...) va_list ap; int ret; -#ifdef CONFIG_DEBUG_ENABLE +#ifdef CONFIG_SYSLOG_ENABLE ret = 0; - if (g_dbgenable) + if (g_syslogenable) #endif { va_start(ap, format); - ret = lib_lowvprintf(format, ap); + ret = lowvsyslog(format, ap); va_end(ap); } @@ -128,13 +128,13 @@ int vdbg(const char *format, ...) va_list ap; int ret; -#ifdef CONFIG_DEBUG_ENABLE +#ifdef CONFIG_SYSLOG_ENABLE ret = 0; - if (g_dbgenable) + if (g_syslogenable) #endif { va_start(ap, format); - ret = lib_rawvprintf(format, ap); + ret = vsyslog(format, ap); va_end(ap); } @@ -147,13 +147,13 @@ int llvdbg(const char *format, ...) va_list ap; int ret; -#ifdef CONFIG_DEBUG_ENABLE +#ifdef CONFIG_SYSLOG_ENABLE ret = 0; - if (g_dbgenable) + if (g_syslogenable) #endif { va_start(ap, format); - ret = lib_lowvprintf(format, ap); + ret = lowvsyslog(format, ap); va_end(ap); } diff --git a/nuttx/libc/misc/lib_dumpbuffer.c b/nuttx/libc/misc/lib_dumpbuffer.c index 52158b220..5194560fd 100644 --- a/nuttx/libc/misc/lib_dumpbuffer.c +++ b/nuttx/libc/misc/lib_dumpbuffer.c @@ -51,15 +51,15 @@ #ifdef CONFIG_CPP_HAVE_VARARGS # ifdef CONFIG_ARCH_LOWPUTC -# define message(format, arg...) lib_lowprintf(format, ##arg) +# define message(format, arg...) lowsyslog(format, ##arg) # else -# define message(format, arg...) lib_rawprintf(format, ##arg) +# define message(format, arg...) syslog(format, ##arg) # endif #else # ifdef CONFIG_ARCH_LOWPUTC -# define message lib_lowprintf +# define message lowsyslog # else -# define message lib_rawprintf +# define message syslog # endif #endif diff --git a/nuttx/libc/stdio/Make.defs b/nuttx/libc/stdio/Make.defs index e18ab0220..ffc9b1a75 100644 --- a/nuttx/libc/stdio/Make.defs +++ b/nuttx/libc/stdio/Make.defs @@ -37,7 +37,7 @@ # This first group of C files do not depend on having file descriptors or # C streams. -CSRCS += lib_fileno.c lib_printf.c lib_rawprintf.c lib_lowprintf.c \ +CSRCS += lib_fileno.c lib_printf.c lib_syslog.c lib_lowsyslog.c\ lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \ lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \ lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \ diff --git a/nuttx/libc/stdio/lib_lowprintf.c b/nuttx/libc/stdio/lib_lowprintf.c deleted file mode 100644 index 667fad7be..000000000 --- a/nuttx/libc/stdio/lib_lowprintf.c +++ /dev/null @@ -1,130 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_lowprintf.c - * - * Copyright (C) 2007-2009, 2011-2012 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 NuttX 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 "lib_internal.h" - -/* This interface can only be used from within the kernel */ - -#if !defined(CONFIG_NUTTX_KERNEL) || defined(__KERNEL__) - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_lowvprintf - ****************************************************************************/ - -#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_SYSLOG) - -int lib_lowvprintf(const char *fmt, va_list ap) -{ - struct lib_outstream_s stream; - - /* Wrap the stdout in a stream object and let lib_vsprintf do the work. */ - -#ifdef CONFIG_SYSLOG - lib_syslogstream((FAR struct lib_outstream_s *)&stream); -#else - lib_lowoutstream((FAR struct lib_outstream_s *)&stream); -#endif - return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); -} - -/**************************************************************************** - * Name: lib_lowprintf - ****************************************************************************/ - -int lib_lowprintf(const char *fmt, ...) -{ - va_list ap; - int ret; - -#ifdef CONFIG_DEBUG_ENABLE - ret = 0; - if (g_dbgenable) -#endif - { - va_start(ap, fmt); - ret = lib_lowvprintf(fmt, ap); - va_end(ap); - } - - return ret; -} - -#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_SYSLOG */ -#endif /* __KERNEL__ */ diff --git a/nuttx/libc/stdio/lib_lowsyslog.c b/nuttx/libc/stdio/lib_lowsyslog.c new file mode 100644 index 000000000..bfe6a2cce --- /dev/null +++ b/nuttx/libc/stdio/lib_lowsyslog.c @@ -0,0 +1,130 @@ +/**************************************************************************** + * libc/stdio/lib_lowsyslog.c + * + * Copyright (C) 2007-2009, 2011-2012 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 NuttX 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 "lib_internal.h" + +/* This interface can only be used from within the kernel */ + +#if !defined(CONFIG_NUTTX_KERNEL) || defined(__KERNEL__) + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lowvsyslog + ****************************************************************************/ + +#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_SYSLOG) + +int lowvsyslog(const char *fmt, va_list ap) +{ + struct lib_outstream_s stream; + + /* Wrap the stdout in a stream object and let lib_vsprintf do the work. */ + +#ifdef CONFIG_SYSLOG + lib_syslogstream((FAR struct lib_outstream_s *)&stream); +#else + lib_lowoutstream((FAR struct lib_outstream_s *)&stream); +#endif + return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); +} + +/**************************************************************************** + * Name: lowsyslog + ****************************************************************************/ + +int lowsyslog(const char *fmt, ...) +{ + va_list ap; + int ret; + +#ifdef CONFIG_SYSLOG_ENABLE + ret = 0; + if (g_syslogenable) +#endif + { + va_start(ap, fmt); + ret = lowvsyslog(fmt, ap); + va_end(ap); + } + + return ret; +} + +#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_SYSLOG */ +#endif /* __KERNEL__ */ diff --git a/nuttx/libc/stdio/lib_printf.c b/nuttx/libc/stdio/lib_printf.c index 0e90c7ca5..b035aa14f 100644 --- a/nuttx/libc/stdio/lib_printf.c +++ b/nuttx/libc/stdio/lib_printf.c @@ -93,9 +93,9 @@ int printf(const char *fmt, ...) #if CONFIG_NFILE_STREAMS > 0 ret = vfprintf(stdout, fmt, ap); #elif CONFIG_NFILE_DESCRIPTORS > 0 - ret = lib_rawvprintf(fmt, ap); + ret = vsyslog(fmt, ap); #elif defined(CONFIG_ARCH_LOWPUTC) - ret = lib_lowvprintf(fmt, ap); + ret = lowvsyslog(fmt, ap); #else # ifdef CONFIG_CPP_HAVE_WARNING # warning "printf has no data sink" diff --git a/nuttx/libc/stdio/lib_rawprintf.c b/nuttx/libc/stdio/lib_rawprintf.c deleted file mode 100644 index d8deba12d..000000000 --- a/nuttx/libc/stdio/lib_rawprintf.c +++ /dev/null @@ -1,154 +0,0 @@ -/**************************************************************************** - * libc/stdio/lib_rawprintf.c - * - * Copyright (C) 2007-2009, 2011-2012 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 NuttX 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 "lib_internal.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Some output destinations are only available from within the kernel */ - -#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__) -# undef CONFIG_SYSLOG -# undef CONFIG_ARCH_LOWPUTC -#endif - -/**************************************************************************** - * Private Type Declarations - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Global Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Global Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Constant Data - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lib_rawvprintf - ****************************************************************************/ - -int lib_rawvprintf(const char *fmt, va_list ap) -{ -#if defined(CONFIG_SYSLOG) - - struct lib_outstream_s stream; - - /* Wrap the low-level output in a stream object and let lib_vsprintf - * do the work. - */ - - lib_syslogstream((FAR struct lib_outstream_s *)&stream); - return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); - -#elif CONFIG_NFILE_DESCRIPTORS > 0 - - struct lib_rawoutstream_s rawoutstream; - - /* Wrap the stdout in a stream object and let lib_vsprintf - * do the work. - */ - - lib_rawoutstream(&rawoutstream, 1); - return lib_vsprintf(&rawoutstream.public, fmt, ap); - -#elif defined(CONFIG_ARCH_LOWPUTC) - - struct lib_outstream_s stream; - - /* Wrap the low-level output in a stream object and let lib_vsprintf - * do the work. - */ - - lib_lowoutstream((FAR struct lib_outstream_s *)&stream); - return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); - -#else - return 0; -#endif -} - -/**************************************************************************** - * Name: lib_rawprintf - ****************************************************************************/ - -int lib_rawprintf(const char *fmt, ...) -{ - va_list ap; - int ret; - -#ifdef CONFIG_DEBUG_ENABLE - ret = 0; - if (g_dbgenable) -#endif - { - va_start(ap, fmt); - ret = lib_rawvprintf(fmt, ap); - va_end(ap); - } - - return ret; -} diff --git a/nuttx/libc/stdio/lib_syslog.c b/nuttx/libc/stdio/lib_syslog.c new file mode 100644 index 000000000..bbf7860d2 --- /dev/null +++ b/nuttx/libc/stdio/lib_syslog.c @@ -0,0 +1,154 @@ +/**************************************************************************** + * libc/stdio/lib_syslog.c + * + * Copyright (C) 2007-2009, 2011-2013 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 NuttX 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 "lib_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Some output destinations are only available from within the kernel */ + +#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__) +# undef CONFIG_SYSLOG +# undef CONFIG_ARCH_LOWPUTC +#endif + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Constant Data + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: vsyslog + ****************************************************************************/ + +int vsyslog(const char *fmt, va_list ap) +{ +#if defined(CONFIG_SYSLOG) + + struct lib_outstream_s stream; + + /* Wrap the low-level output in a stream object and let lib_vsprintf + * do the work. + */ + + lib_syslogstream((FAR struct lib_outstream_s *)&stream); + return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); + +#elif CONFIG_NFILE_DESCRIPTORS > 0 + + struct lib_rawoutstream_s rawoutstream; + + /* Wrap the stdout in a stream object and let lib_vsprintf + * do the work. + */ + + lib_rawoutstream(&rawoutstream, 1); + return lib_vsprintf(&rawoutstream.public, fmt, ap); + +#elif defined(CONFIG_ARCH_LOWPUTC) + + struct lib_outstream_s stream; + + /* Wrap the low-level output in a stream object and let lib_vsprintf + * do the work. + */ + + lib_lowoutstream((FAR struct lib_outstream_s *)&stream); + return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, ap); + +#else + return 0; +#endif +} + +/**************************************************************************** + * Name: syslog + ****************************************************************************/ + +int syslog(const char *fmt, ...) +{ + va_list ap; + int ret; + +#ifdef CONFIG_SYSLOG_ENABLE + ret = 0; + if (g_syslogenable) +#endif + { + va_start(ap, fmt); + ret = vsyslog(fmt, ap); + va_end(ap); + } + + return ret; +} -- cgit v1.2.3 From 2ee8d521599a3b15275bffc9a27730f083898290 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 30 Jan 2013 13:24:45 +0000 Subject: LPC1788 updated from Rommel Marcelo git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5583 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h | 217 +++++++++++++++++++++++- nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c | 168 +++++++++++++++++- nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h | 38 +++-- 3 files changed, 389 insertions(+), 34 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h index b8c9ee480..a3c247caf 100755 --- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h +++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h @@ -52,13 +52,7 @@ /* Register offsets *****************************************************************/ -#define LPC17_IOCON_P0_OFFSET (LPC17_IOCON_BASE+0x0000) -#define LPC17_IOCON_P1_OFFSET (LPC17_IOCON_BASE+0x0080) -#define LPC17_IOCON_P2_OFFSET (LPC17_IOCON_BASE+0x0100) -#define LPC17_IOCON_P3_OFFSET (LPC17_IOCON_BASE+0x0180) -#define LPC17_IOCON_P4_OFFSET (LPC17_IOCON_BASE+0x0200) -#define LPC17_IOCON_P5_OFFSET (LPC17_IOCON_BASE+0x0280) - +#define LPC17_IOCON_PP_OFFSET(p) ((p) << 2) #define LPC17_IOCON_PP0_OFFSET (0x0000) /* IOCON Port(n) register 0 */ #define LPC17_IOCON_PP1_OFFSET (0x0004) /* IOCON Port(n) register 1 */ #define LPC17_IOCON_PP2_OFFSET (0x0008) /* IOCON Port(n) register 2 */ @@ -94,10 +88,215 @@ /* Register addresses ***************************************************************/ -//~ #define LPC17_IOCON_PP1(portoffset) (portoffset+LPC17_IOCON_P0_OFFSET) +#define LPC17_IOCON_P_BASE(b) (LPC17_IOCON_BASE + ((b) << 7)) +#define LPC17_IOCON_P0_BASE (LPC17_IOCON_BASE + 0x0000) +#define LPC17_IOCON_P1_BASE (LPC17_IOCON_BASE + 0x0080) +#define LPC17_IOCON_P2_BASE (LPC17_IOCON_BASE + 0x0100) +#define LPC17_IOCON_P3_BASE (LPC17_IOCON_BASE + 0x0180) +#define LPC17_IOCON_P4_BASE (LPC17_IOCON_BASE + 0x0200) +#define LPC17_IOCON_P4_BASE (LPC17_IOCON_BASE + 0x0280) + +#define LPC17_IOCON_P(b,p) (LPC17_IOCON_P_BASE(b) + LPC17_IOCON_PP_OFFSET(p)) + +#define LPC17_IOCON_P0_0 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP0_OFFSET) +#define LPC17_IOCON_P0_1 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP1_OFFSET) +#define LPC17_IOCON_P0_2 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP2_OFFSET) +#define LPC17_IOCON_P0_3 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP3_OFFSET) +#define LPC17_IOCON_P0_4 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP4_OFFSET) +#define LPC17_IOCON_P0_5 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP5_OFFSET) +#define LPC17_IOCON_P0_6 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP6_OFFSET) +#define LPC17_IOCON_P0_7 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP7_OFFSET) +#define LPC17_IOCON_P0_8 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP8_OFFSET) +#define LPC17_IOCON_P0_9 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP9_OFFSET) +#define LPC17_IOCON_P0_10 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP10_OFFSET) +#define LPC17_IOCON_P0_11 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP11_OFFSET) +#define LPC17_IOCON_P0_12 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP12_OFFSET) +#define LPC17_IOCON_P0_13 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP13_OFFSET) +#define LPC17_IOCON_P0_14 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP14_OFFSET) +#define LPC17_IOCON_P0_15 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP15_OFFSET) +#define LPC17_IOCON_P0_16 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP16_OFFSET) +#define LPC17_IOCON_P0_17 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP17_OFFSET) +#define LPC17_IOCON_P0_18 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP18_OFFSET) +#define LPC17_IOCON_P0_19 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP19_OFFSET) +#define LPC17_IOCON_P0_20 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP20_OFFSET) +#define LPC17_IOCON_P0_21 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP21_OFFSET) +#define LPC17_IOCON_P0_22 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP22_OFFSET) +#define LPC17_IOCON_P0_23 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP23_OFFSET) +#define LPC17_IOCON_P0_24 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP24_OFFSET) +#define LPC17_IOCON_P0_25 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP25_OFFSET) +#define LPC17_IOCON_P0_26 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP26_OFFSET) +#define LPC17_IOCON_P0_27 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP27_OFFSET) +#define LPC17_IOCON_P0_28 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP28_OFFSET) +#define LPC17_IOCON_P0_29 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP29_OFFSET) +#define LPC17_IOCON_P0_30 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP30_OFFSET) +#define LPC17_IOCON_P0_31 (LPC17_IOCON_P0_BASE + LPC17_IOCON_PP31_OFFSET) + +#define LPC17_IOCON_P1_0 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP0_OFFSET) +#define LPC17_IOCON_P1_1 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP1_OFFSET) +#define LPC17_IOCON_P1_2 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP2_OFFSET) +#define LPC17_IOCON_P1_3 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP3_OFFSET) +#define LPC17_IOCON_P1_4 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP4_OFFSET) +#define LPC17_IOCON_P1_5 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP5_OFFSET) +#define LPC17_IOCON_P1_6 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP6_OFFSET) +#define LPC17_IOCON_P1_7 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP7_OFFSET) +#define LPC17_IOCON_P1_8 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP8_OFFSET) +#define LPC17_IOCON_P1_9 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP9_OFFSET) +#define LPC17_IOCON_P1_10 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP10_OFFSET) +#define LPC17_IOCON_P1_11 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP11_OFFSET) +#define LPC17_IOCON_P1_12 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP12_OFFSET) +#define LPC17_IOCON_P1_13 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP13_OFFSET) +#define LPC17_IOCON_P1_14 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP14_OFFSET) +#define LPC17_IOCON_P1_15 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP15_OFFSET) +#define LPC17_IOCON_P1_16 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP16_OFFSET) +#define LPC17_IOCON_P1_17 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP17_OFFSET) +#define LPC17_IOCON_P1_18 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP18_OFFSET) +#define LPC17_IOCON_P1_19 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP19_OFFSET) +#define LPC17_IOCON_P1_20 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP20_OFFSET) +#define LPC17_IOCON_P1_21 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP21_OFFSET) +#define LPC17_IOCON_P1_22 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP22_OFFSET) +#define LPC17_IOCON_P1_23 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP23_OFFSET) +#define LPC17_IOCON_P1_24 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP24_OFFSET) +#define LPC17_IOCON_P1_25 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP25_OFFSET) +#define LPC17_IOCON_P1_26 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP26_OFFSET) +#define LPC17_IOCON_P1_27 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP27_OFFSET) +#define LPC17_IOCON_P1_28 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP28_OFFSET) +#define LPC17_IOCON_P1_29 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP29_OFFSET) +#define LPC17_IOCON_P1_30 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP30_OFFSET) +#define LPC17_IOCON_P1_31 (LPC17_IOCON_P1_BASE + LPC17_IOCON_PP31_OFFSET) + +#define LPC17_IOCON_P2_0 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP0_OFFSET) +#define LPC17_IOCON_P2_1 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP1_OFFSET) +#define LPC17_IOCON_P2_2 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP2_OFFSET) +#define LPC17_IOCON_P2_3 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP3_OFFSET) +#define LPC17_IOCON_P2_4 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP4_OFFSET) +#define LPC17_IOCON_P2_5 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP5_OFFSET) +#define LPC17_IOCON_P2_6 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP6_OFFSET) +#define LPC17_IOCON_P2_7 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP7_OFFSET) +#define LPC17_IOCON_P2_8 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP8_OFFSET) +#define LPC17_IOCON_P2_9 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP9_OFFSET) +#define LPC17_IOCON_P2_10 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP10_OFFSET) +#define LPC17_IOCON_P2_11 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP11_OFFSET) +#define LPC17_IOCON_P2_12 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP12_OFFSET) +#define LPC17_IOCON_P2_13 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP13_OFFSET) +#define LPC17_IOCON_P2_14 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP14_OFFSET) +#define LPC17_IOCON_P2_15 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP15_OFFSET) +#define LPC17_IOCON_P2_16 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP16_OFFSET) +#define LPC17_IOCON_P2_17 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP17_OFFSET) +#define LPC17_IOCON_P2_18 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP18_OFFSET) +#define LPC17_IOCON_P2_19 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP19_OFFSET) +#define LPC17_IOCON_P2_20 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP20_OFFSET) +#define LPC17_IOCON_P2_21 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP21_OFFSET) +#define LPC17_IOCON_P2_22 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP22_OFFSET) +#define LPC17_IOCON_P2_23 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP23_OFFSET) +#define LPC17_IOCON_P2_24 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP24_OFFSET) +#define LPC17_IOCON_P2_25 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP25_OFFSET) +#define LPC17_IOCON_P2_26 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP26_OFFSET) +#define LPC17_IOCON_P2_27 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP27_OFFSET) +#define LPC17_IOCON_P2_28 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP28_OFFSET) +#define LPC17_IOCON_P2_29 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP29_OFFSET) +#define LPC17_IOCON_P2_30 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP30_OFFSET) +#define LPC17_IOCON_P2_31 (LPC17_IOCON_P2_BASE + LPC17_IOCON_PP31_OFFSET) + +#define LPC17_IOCON_P3_0 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP0_OFFSET) +#define LPC17_IOCON_P3_1 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP1_OFFSET) +#define LPC17_IOCON_P3_2 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP2_OFFSET) +#define LPC17_IOCON_P3_3 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP3_OFFSET) +#define LPC17_IOCON_P3_4 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP4_OFFSET) +#define LPC17_IOCON_P3_5 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP5_OFFSET) +#define LPC17_IOCON_P3_6 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP6_OFFSET) +#define LPC17_IOCON_P3_7 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP7_OFFSET) +#define LPC17_IOCON_P3_8 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP8_OFFSET) +#define LPC17_IOCON_P3_9 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP9_OFFSET) +#define LPC17_IOCON_P3_10 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP10_OFFSET) +#define LPC17_IOCON_P3_11 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP11_OFFSET) +#define LPC17_IOCON_P3_12 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP12_OFFSET) +#define LPC17_IOCON_P3_13 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP13_OFFSET) +#define LPC17_IOCON_P3_14 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP14_OFFSET) +#define LPC17_IOCON_P3_15 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP15_OFFSET) +#define LPC17_IOCON_P3_16 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP16_OFFSET) +#define LPC17_IOCON_P3_17 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP17_OFFSET) +#define LPC17_IOCON_P3_18 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP18_OFFSET) +#define LPC17_IOCON_P3_19 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP19_OFFSET) +#define LPC17_IOCON_P3_20 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP20_OFFSET) +#define LPC17_IOCON_P3_21 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP21_OFFSET) +#define LPC17_IOCON_P3_22 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP22_OFFSET) +#define LPC17_IOCON_P3_23 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP23_OFFSET) +#define LPC17_IOCON_P3_24 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP24_OFFSET) +#define LPC17_IOCON_P3_25 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP25_OFFSET) +#define LPC17_IOCON_P3_26 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP26_OFFSET) +#define LPC17_IOCON_P3_27 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP27_OFFSET) +#define LPC17_IOCON_P3_28 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP28_OFFSET) +#define LPC17_IOCON_P3_29 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP29_OFFSET) +#define LPC17_IOCON_P3_30 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP30_OFFSET) +#define LPC17_IOCON_P3_31 (LPC17_IOCON_P3_BASE + LPC17_IOCON_PP31_OFFSET) + +#define LPC17_IOCON_P4_0 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP0_OFFSET) +#define LPC17_IOCON_P4_1 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP1_OFFSET) +#define LPC17_IOCON_P4_2 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP2_OFFSET) +#define LPC17_IOCON_P4_3 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP3_OFFSET) +#define LPC17_IOCON_P4_4 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP4_OFFSET) +#define LPC17_IOCON_P4_5 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP5_OFFSET) +#define LPC17_IOCON_P4_6 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP6_OFFSET) +#define LPC17_IOCON_P4_7 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP7_OFFSET) +#define LPC17_IOCON_P4_8 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP8_OFFSET) +#define LPC17_IOCON_P4_9 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP9_OFFSET) +#define LPC17_IOCON_P4_10 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP10_OFFSET) +#define LPC17_IOCON_P4_11 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP11_OFFSET) +#define LPC17_IOCON_P4_12 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP12_OFFSET) +#define LPC17_IOCON_P4_13 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP13_OFFSET) +#define LPC17_IOCON_P4_14 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP14_OFFSET) +#define LPC17_IOCON_P4_15 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP15_OFFSET) +#define LPC17_IOCON_P4_16 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP16_OFFSET) +#define LPC17_IOCON_P4_17 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP17_OFFSET) +#define LPC17_IOCON_P4_18 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP18_OFFSET) +#define LPC17_IOCON_P4_19 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP19_OFFSET) +#define LPC17_IOCON_P4_20 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP20_OFFSET) +#define LPC17_IOCON_P4_21 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP21_OFFSET) +#define LPC17_IOCON_P4_22 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP22_OFFSET) +#define LPC17_IOCON_P4_23 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP23_OFFSET) +#define LPC17_IOCON_P4_24 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP24_OFFSET) +#define LPC17_IOCON_P4_25 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP25_OFFSET) +#define LPC17_IOCON_P4_26 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP26_OFFSET) +#define LPC17_IOCON_P4_27 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP27_OFFSET) +#define LPC17_IOCON_P4_28 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP28_OFFSET) +#define LPC17_IOCON_P4_29 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP29_OFFSET) +#define LPC17_IOCON_P4_30 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP30_OFFSET) +#define LPC17_IOCON_P4_31 (LPC17_IOCON_P4_BASE + LPC17_IOCON_PP31_OFFSET) + +#define LPC17_IOCON_P5_0 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP0_OFFSET) +#define LPC17_IOCON_P5_1 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP1_OFFSET) +#define LPC17_IOCON_P5_2 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP2_OFFSET) +#define LPC17_IOCON_P5_3 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP3_OFFSET) +#define LPC17_IOCON_P5_4 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP4_OFFSET) +#define LPC17_IOCON_P5_5 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP5_OFFSET) +#define LPC17_IOCON_P5_6 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP6_OFFSET) +#define LPC17_IOCON_P5_7 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP7_OFFSET) +#define LPC17_IOCON_P5_8 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP8_OFFSET) +#define LPC17_IOCON_P5_9 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP9_OFFSET) +#define LPC17_IOCON_P5_10 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP10_OFFSET) +#define LPC17_IOCON_P5_11 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP11_OFFSET) +#define LPC17_IOCON_P5_12 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP12_OFFSET) +#define LPC17_IOCON_P5_13 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP13_OFFSET) +#define LPC17_IOCON_P5_14 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP14_OFFSET) +#define LPC17_IOCON_P5_15 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP15_OFFSET) +#define LPC17_IOCON_P5_16 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP16_OFFSET) +#define LPC17_IOCON_P5_17 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP17_OFFSET) +#define LPC17_IOCON_P5_18 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP18_OFFSET) +#define LPC17_IOCON_P5_19 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP19_OFFSET) +#define LPC17_IOCON_P5_20 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP20_OFFSET) +#define LPC17_IOCON_P5_21 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP21_OFFSET) +#define LPC17_IOCON_P5_22 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP22_OFFSET) +#define LPC17_IOCON_P5_23 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP23_OFFSET) +#define LPC17_IOCON_P5_24 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP24_OFFSET) +#define LPC17_IOCON_P5_25 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP25_OFFSET) +#define LPC17_IOCON_P5_26 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP26_OFFSET) +#define LPC17_IOCON_P5_27 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP27_OFFSET) +#define LPC17_IOCON_P5_28 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP28_OFFSET) +#define LPC17_IOCON_P5_29 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP29_OFFSET) +#define LPC17_IOCON_P5_30 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP30_OFFSET) +#define LPC17_IOCON_P5_31 (LPC17_IOCON_P5_BASE + LPC17_IOCON_PP31_OFFSET) /* Register bit definitions *********************************************************/ -/* Pin Function Select register 0 (PINSEL0: 0x4002c000) */ /* IOCON pin function select */ #define IOCON_FUNC_GPIO (0) diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c index 73939a389..ece6adc5f 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c @@ -93,37 +93,101 @@ const uint32_t g_fiobase[GPIO_NPORTS] = LPC17_FIO2_BASE, LPC17_FIO3_BASE, LPC17_FIO4_BASE +#if GPIO_NPORTS > 5 + , LPC17_FIO5_BASE +#endif +}; + +#ifdef LPC178X +/* IOCON register base addresses */ + +const uint32_t g_ioconport[GPIO_NPORTS] = +{ + LPC17_IOCON_P0, + LPC17_IOCON_P1, + LPC17_IOCON_P2, + LPC17_IOCON_P3, + LPC17_IOCON_P4, + LPC17_IOCON_P5 +} + +/* Register offsets */ + +const uint32_t g_ioconpin[32] = +{ + LPC17_IOCON_PP0_OFFSET, + LPC17_IOCON_PP1_OFFSET, + LPC17_IOCON_PP2_OFFSET, + LPC17_IOCON_PP3_OFFSET, + LPC17_IOCON_PP4_OFFSET, + LPC17_IOCON_PP5_OFFSET, + LPC17_IOCON_PP6_OFFSET, + LPC17_IOCON_PP7_OFFSET, + LPC17_IOCON_PP8_OFFSET, + LPC17_IOCON_PP9_OFFSET, + LPC17_IOCON_PP10_OFFSET, + LPC17_IOCON_PP11_OFFSET, + LPC17_IOCON_PP12_OFFSET, + LPC17_IOCON_PP13_OFFSET, + LPC17_IOCON_PP14_OFFSET, + LPC17_IOCON_PP15_OFFSET, + LPC17_IOCON_PP16_OFFSET, + LPC17_IOCON_PP17_OFFSET, + LPC17_IOCON_PP18_OFFSET, + LPC17_IOCON_PP19_OFFSET, + LPC17_IOCON_PP20_OFFSET, + LPC17_IOCON_PP21_OFFSET, + LPC17_IOCON_PP22_OFFSET, + LPC17_IOCON_PP23_OFFSET, + LPC17_IOCON_PP24_OFFSET, + LPC17_IOCON_PP25_OFFSET, + LPC17_IOCON_PP26_OFFSET, + LPC17_IOCON_PP27_OFFSET, + LPC17_IOCON_PP28_OFFSET, + LPC17_IOCON_PP29_OFFSET, + LPC17_IOCON_PP30_OFFSET, + LPC17_IOCON_PP31_OFFSET }; +#endif /* Port 0 and Port 2 can provide a single interrupt for any combination of - * port pins + * port pins */ -const uint32_t g_intbase[GPIO_NPORTS] = +const uint32_t g_intbase[GPIO_NPORTS] = { LPC17_GPIOINT0_BASE, 0, LPC17_GPIOINT2_BASE, 0, 0 +#if GPIO_NPORTS > 5 + , 0 +#endif }; -const uint32_t g_lopinsel[GPIO_NPORTS] = +const uint32_t g_lopinsel[GPIO_NPORTS] = { LPC17_PINCONN_PINSEL0, LPC17_PINCONN_PINSEL2, LPC17_PINCONN_PINSEL4, 0, 0 +#if GPIO_NPORTS > 5 + , 0 +#endif }; -const uint32_t g_hipinsel[GPIO_NPORTS] = +const uint32_t g_hipinsel[GPIO_NPORTS] = { LPC17_PINCONN_PINSEL1, LPC17_PINCONN_PINSEL3, 0, LPC17_PINCONN_PINSEL7, LPC17_PINCONN_PINSEL9 +#if GPIO_NPORTS > 5 + , 0 +#endif }; const uint32_t g_lopinmode[GPIO_NPORTS] = @@ -133,6 +197,9 @@ const uint32_t g_lopinmode[GPIO_NPORTS] = LPC17_PINCONN_PINMODE4, 0, 0 +#if GPIO_NPORTS > 5 + , 0 +#endif }; const uint32_t g_hipinmode[GPIO_NPORTS] = @@ -142,6 +209,9 @@ const uint32_t g_hipinmode[GPIO_NPORTS] = 0, LPC17_PINCONN_PINMODE7, LPC17_PINCONN_PINMODE9 +#if GPIO_NPORTS > 5 + , 0 +#endif }; const uint32_t g_odmode[GPIO_NPORTS] = @@ -151,6 +221,9 @@ const uint32_t g_odmode[GPIO_NPORTS] = LPC17_PINCONN_ODMODE2, LPC17_PINCONN_ODMODE3, LPC17_PINCONN_ODMODE4 +#if GPIO_NPORTS > 5 + , 0 +#endif }; /**************************************************************************** @@ -347,6 +420,27 @@ static void lpc17_clropendrain(unsigned int port, unsigned int pin) putreg32(regval, regaddr); } +/**************************************************************************** + * Name: lpc17_configiocon + * + * Description: + * Set the LPC178x IOCON register + ****************************************************************************/ + +#ifdef LPC178x +static int lpc17_configiocon(unsigned int port, unsigned int pin, + unsigned int value) +{ + uint32_t regaddr; + uint32_t regval; + + regaddr = (g_ioconbase[port] + g_ioconpin[pin]); + regval = getreg32(regaddr); + regval &= value; + putreg32(regval, regaddr); +} +#endif + /**************************************************************************** * Name: lpc17_configinput * @@ -361,9 +455,9 @@ static inline int lpc17_configinput(lpc17_pinset_t cfgset, unsigned int port, un uint32_t fiobase; uint32_t intbase; uint32_t pinmask = (1 << pin); - + /* Set up FIO registers */ - + fiobase = g_fiobase[port]; /* Set as input */ @@ -378,13 +472,13 @@ static inline int lpc17_configinput(lpc17_pinset_t cfgset, unsigned int port, un if (intbase != 0) { /* Disable any rising edge interrupts */ - + regval = getreg32(intbase + LPC17_GPIOINT_INTENR_OFFSET); regval &= ~pinmask; putreg32(regval, intbase + LPC17_GPIOINT_INTENR_OFFSET); /* Disable any falling edge interrupts */ - + regval = getreg32(intbase + LPC17_GPIOINT_INTENF_OFFSET); regval &= ~pinmask; putreg32(regval, intbase + LPC17_GPIOINT_INTENF_OFFSET); @@ -396,6 +490,8 @@ static inline int lpc17_configinput(lpc17_pinset_t cfgset, unsigned int port, un #endif } +#ifdef defined(LPC176x) + /* Set up PINSEL registers */ /* Configure as GPIO */ @@ -408,6 +504,40 @@ static inline int lpc17_configinput(lpc17_pinset_t cfgset, unsigned int port, un /* Open drain only applies to outputs */ lpc17_clropendrain(port, pin); + +#elif defined(LPC178x) + + uint32_t value; + + /* Configure as GPIO */ + + if ((cfgset & GPIO_FILTER) != 0) + { + value = (IOCON_FUNC_GPIO | ~GPIO_IOCON_TYPE_W_MASK); + } + else + { + value = (IOCON_FUNC_GPIO | ~GPIO_IOCON_TYPE_D_MASK); + } + + /* Set pull-up mode */ + + value |= ((cfgset & GPIO_PUMODE_MASK) >> GPIO_PINMODE_SHIFT); + + /* Clear open drain: open drain only applies to outputs */ + + value &= ~IOCON_OD_MASK ; + + /* Clear input hysteresis, invertion, slew */ + + value &= ~(IOCON_HYS_MASK | IOCON_INV_MASK | IOCON_SLEW_MASK); + + /* Set IOCON register */ + + lpc17_configiocon(port, pin, value); + +#endif + return OK; } @@ -541,7 +671,7 @@ int lpc17_configgpio(lpc17_pinset_t cfgset) unsigned int port; unsigned int pin; int ret = -EINVAL; - + /* Verify that this hardware supports the select GPIO port */ port = (cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; @@ -581,6 +711,26 @@ int lpc17_configgpio(lpc17_pinset_t cfgset) ret = lpc17_configalternate(cfgset, port, pin, PINCONN_PINSEL_ALT3); break; +#ifdef LPC178x + + case GPIO_ALT4: /* Alternate function 4 */ + ret = ; + break; + + case GPIO_ALT5: /* Alternate function 5 */ + ret = ; + break; + + case GPIO_ALT6: /* Alternate function 6 */ + ret = ; + break; + + case GPIO_ALT7: /* Alternate function 7 */ + ret = ; + break; + +#endif + default: break; } diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h index 993369aa2..62bf2d018 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h @@ -187,19 +187,20 @@ */ #define GPIO_IOCON_TYPE_D_MASK (0x0000067f) /* All port except where ADC/DAC, USB, I2C is present */ -#define GPIO_IOCON_TYPE_A_MASK (0x000105df) /* USB/ADC/DAC P0:12 to 13, P0:23 to 26, P1:30 to 31 */ +#define GPIO_IOCON_TYPE_A_MASK (0x000105df) /* USB/ADC/DAC P0:12-13, P0:23-26, P1:30-31 */ #define GPIO_IOCON_TYPE_U_MASK (0x00000007) /* USB P0:29 to 31 */ -#define GPIO_IOCON_TYPE_I_MASK (0x00000347) /* I2C/USB P0:27 to 28, P5:2 to 3 */ -#define GPIO_IOCON_TYPE_W_MASK (0x000007ff) /* I2S P0:7 to 9 */ - -# define GPIO_HYS (1 << 16) /* Bit 16: HYSTERESIS: 0-Disable, 1-Enabled */ -# define GPIO_INV (1 << 17) /* Bit 17: Input: 0-Not Inverted, 1-Inverted */ -# define GPIO_SLEW (1 << 18) /* Bit 18: Rate Control: 0-Standard mode, 1-Fast mode */ -# define GPIO_ADMODE (1 << 19) /* Bit 19: A/D Modes: 0-Analog, 1-Digital */ -# define GPIO_FILTER (1 << 20) /* Bit 20: Filter: 0-Off, 1-ON */ -# define GPIO_DACEN (1 << 21) /* Bit 21: DAC: 0-Disabled, 1-Enabled, P0:26 only */ -# define GPIO_I2CHS (1 << 22) /* Bit 22: Filter and Rate Control: 0-Enabled, 1-Disabled */ -# define GPIO_HIDRIVE (1 << 23) /* Bit 23: Current Sink: 0-4mA, 1-20mA P5:2 and P5:3 only,*/ +#define GPIO_IOCON_TYPE_I_MASK (0x00000347) /* I2C/USB P0:27-28, P5:2-3 */ +#define GPIO_IOCON_TYPE_W_MASK (0x000007ff) /* I2S P0:7-9 */ + +#define GPIO_IOCON_MASK (0x00FF0000) +# define GPIO_HYS (1 << 16) /* Bit 16: HYSTERESIS: 0-Disable, 1-Enabled */ +# define GPIO_INV (1 << 17) /* Bit 17: Input: 0-Not Inverted, 1-Inverted */ +# define GPIO_SLEW (1 << 18) /* Bit 18: Rate Control: 0-Standard mode, 1-Fast mode */ +# define GPIO_ADMODE (1 << 19) /* Bit 19: A/D Modes: 0-Analog, 1-Digital */ +# define GPIO_FILTER (1 << 20) /* Bit 20: Filter: 0-Off, 1-ON */ +# define GPIO_DACEN (1 << 21) /* Bit 21: DAC: 0-Disabled, 1-Enabled, P0:26 only */ +# define GPIO_I2CHS (1 << 22) /* Bit 22: Filter and Rate Control: 0-Enabled, 1-Disabled */ +# define GPIO_HIDRIVE (1 << 23) /* Bit 23: Current Sink: 0-4mA, 1-20mA P5:2 and P5:3 only,*/ /* Pin Function bits: FFFF * Only meaningful when the GPIO function is GPIO_PIN @@ -239,12 +240,13 @@ /* Pin Mode: MM */ +#define GPIO_PINMODE_SHIFT (7) #define GPIO_PUMODE_SHIFT (10) /* Bits 10-11: Pin pull-up mode */ #define GPIO_PUMODE_MASK (3 << GPIO_PUMODE_SHIFT) -# define GPIO_PULLUP (0 << GPIO_PUMODE_SHIFT) /* Pull-up resistor enabled */ -# define GPIO_REPEATER (1 << GPIO_PUMODE_SHIFT) /* Repeater mode enabled */ -# define GPIO_FLOAT (2 << GPIO_PUMODE_SHIFT) /* Neither pull-up nor -down */ -# define GPIO_PULLDN (3 << GPIO_PUMODE_SHIFT) /* Pull-down resistor enabled */ +# define GPIO_FLOAT (0 << GPIO_PUMODE_SHIFT) /* Pull-up resistor enabled */ +# define GPIO_PULLDN (1 << GPIO_PUMODE_SHIFT) /* Repeater mode enabled */ +# define GPIO_PULLUP (2 << GPIO_PUMODE_SHIFT) /* Neither pull-up nor -down */ +# define GPIO_REPEATER (3 << GPIO_PUMODE_SHIFT) /* Pull-down resistor enabled */ /* Open drain: O */ @@ -350,6 +352,10 @@ EXTERN const uint32_t g_hipinsel[GPIO_NPORTS]; EXTERN const uint32_t g_lopinmode[GPIO_NPORTS]; EXTERN const uint32_t g_hipinmode[GPIO_NPORTS]; EXTERN const uint32_t g_odmode[GPIO_NPORTS]; +#ifdef LPC178x +EXTERN const uint32_t g_ioconport[GPIO_NPORTS]; +EXTERN const uint32_t g_ioconpin[32]; +#endif /**************************************************************************** * Public Functions -- cgit v1.2.3 From 37d3293690108d09bf24ac1a5fb2e77cdf5ef89c Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 30 Jan 2013 14:42:10 +0000 Subject: Remove the g_iocon[] arrary git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5584 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h | 4 +-- nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c | 40 +------------------------ nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h | 1 - 3 files changed, 3 insertions(+), 42 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h index a3c247caf..ca4ab6b1d 100755 --- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h +++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h @@ -52,7 +52,7 @@ /* Register offsets *****************************************************************/ -#define LPC17_IOCON_PP_OFFSET(p) ((p) << 2) +#define LPC17_IOCON_PP_OFFSET(p) ((unsigned int)(p) << 2) #define LPC17_IOCON_PP0_OFFSET (0x0000) /* IOCON Port(n) register 0 */ #define LPC17_IOCON_PP1_OFFSET (0x0004) /* IOCON Port(n) register 1 */ #define LPC17_IOCON_PP2_OFFSET (0x0008) /* IOCON Port(n) register 2 */ @@ -88,7 +88,7 @@ /* Register addresses ***************************************************************/ -#define LPC17_IOCON_P_BASE(b) (LPC17_IOCON_BASE + ((b) << 7)) +#define LPC17_IOCON_P_BASE(b) (LPC17_IOCON_BASE + (unsigned int(b) << 7)) #define LPC17_IOCON_P0_BASE (LPC17_IOCON_BASE + 0x0000) #define LPC17_IOCON_P1_BASE (LPC17_IOCON_BASE + 0x0080) #define LPC17_IOCON_P2_BASE (LPC17_IOCON_BASE + 0x0100) diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c index ece6adc5f..e3085ff78 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c @@ -110,44 +110,6 @@ const uint32_t g_ioconport[GPIO_NPORTS] = LPC17_IOCON_P4, LPC17_IOCON_P5 } - -/* Register offsets */ - -const uint32_t g_ioconpin[32] = -{ - LPC17_IOCON_PP0_OFFSET, - LPC17_IOCON_PP1_OFFSET, - LPC17_IOCON_PP2_OFFSET, - LPC17_IOCON_PP3_OFFSET, - LPC17_IOCON_PP4_OFFSET, - LPC17_IOCON_PP5_OFFSET, - LPC17_IOCON_PP6_OFFSET, - LPC17_IOCON_PP7_OFFSET, - LPC17_IOCON_PP8_OFFSET, - LPC17_IOCON_PP9_OFFSET, - LPC17_IOCON_PP10_OFFSET, - LPC17_IOCON_PP11_OFFSET, - LPC17_IOCON_PP12_OFFSET, - LPC17_IOCON_PP13_OFFSET, - LPC17_IOCON_PP14_OFFSET, - LPC17_IOCON_PP15_OFFSET, - LPC17_IOCON_PP16_OFFSET, - LPC17_IOCON_PP17_OFFSET, - LPC17_IOCON_PP18_OFFSET, - LPC17_IOCON_PP19_OFFSET, - LPC17_IOCON_PP20_OFFSET, - LPC17_IOCON_PP21_OFFSET, - LPC17_IOCON_PP22_OFFSET, - LPC17_IOCON_PP23_OFFSET, - LPC17_IOCON_PP24_OFFSET, - LPC17_IOCON_PP25_OFFSET, - LPC17_IOCON_PP26_OFFSET, - LPC17_IOCON_PP27_OFFSET, - LPC17_IOCON_PP28_OFFSET, - LPC17_IOCON_PP29_OFFSET, - LPC17_IOCON_PP30_OFFSET, - LPC17_IOCON_PP31_OFFSET -}; #endif /* Port 0 and Port 2 can provide a single interrupt for any combination of @@ -434,7 +396,7 @@ static int lpc17_configiocon(unsigned int port, unsigned int pin, uint32_t regaddr; uint32_t regval; - regaddr = (g_ioconbase[port] + g_ioconpin[pin]); + regaddr = (g_ioconbase[port] + LPC17_IOCON_PP_OFFSET(pin)); regval = getreg32(regaddr); regval &= value; putreg32(regval, regaddr); diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h index 62bf2d018..99a0b67e9 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h @@ -354,7 +354,6 @@ EXTERN const uint32_t g_hipinmode[GPIO_NPORTS]; EXTERN const uint32_t g_odmode[GPIO_NPORTS]; #ifdef LPC178x EXTERN const uint32_t g_ioconport[GPIO_NPORTS]; -EXTERN const uint32_t g_ioconpin[32]; #endif /**************************************************************************** -- cgit v1.2.3 From e44fbfdc5a033611f4ebfb12b0dd67b263bb8d14 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 30 Jan 2013 16:44:26 +0000 Subject: Add LM3S/4F family definitions git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5585 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/lm/chip.h | 12 ++++++++++++ 1 file changed, 12 insertions(+) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/include/lm/chip.h b/nuttx/arch/arm/include/lm/chip.h index 6761e029e..86e21c14d 100644 --- a/nuttx/arch/arm/include/lm/chip.h +++ b/nuttx/arch/arm/include/lm/chip.h @@ -50,6 +50,8 @@ /* Get customizations for each supported chip (only the LM3S6918 and 65 right now) */ #if defined(CONFIG_ARCH_CHIP_LM3S6918) +# define LM3S 1 /* LM3S family */ +# undef LM4F /* Not LM4F family */ # define LM_NTIMERS 4 /* Four general purpose timers */ # define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ @@ -63,6 +65,8 @@ # define LM_NPORTS 8 /* 8 Ports (GPIOA-H) 5-38 GPIOs */ # define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S6432) +# define LM3S 1 /* LM3S family */ +# undef LM4F /* Not LM4F family */ # define LM_NTIMERS 3 /* Three general purpose timers */ # define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ @@ -76,6 +80,8 @@ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ # define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S6965) +# define LM3S 1 /* LM3S family */ +# undef LM4F /* Not LM4F family */ # define LM_NTIMERS 4 /* Four general purpose timers */ # define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ @@ -89,6 +95,8 @@ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ # define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S9B96) +# define LM3S 1 /* LM3S family */ +# undef LM4F /* Not LM4F family */ # define LM_NTIMERS 4 /* Four general purpose timers */ # define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ @@ -103,6 +111,8 @@ # define LM_NPORTS 9 /* 9 Ports (GPIOA-H,J) 0-65 GPIOs */ # define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S8962) +# define LM3S 1 /* LM3S family */ +# undef LM4F /* Not LM4F family */ # define LM_NTIMERS 6 /* Four general purpose timers */ # define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ @@ -115,6 +125,8 @@ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 5-42 GPIOs */ # define LM_NCANCONTROLLER 1 /* One CAN controller */ #elif defined(CONFIG_ARCH_CHIP_LM4F120) +# undef LM3S /* Not LM3S family */ +# define LM4F 1 /* LM4F family */ # define LM_NTIMERS 6 /* Six general purpose timers */ # define LM_NWIDETIMERS 6 /* Six general purpose wide timers */ # define LM_NETHCONTROLLERS 0 /* No Ethernet controller */ -- cgit v1.2.3 From 4a3b0823cb1f58f03b2cb36a8b0df52c189fb511 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 30 Jan 2013 18:48:13 +0000 Subject: LM4F update from JP git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5586 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h | 6 +- nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h | 7 +- nuttx/arch/arm/src/lm/chip/lm_gpio.h | 695 ++++++++++++++++------------ nuttx/arch/arm/src/stm32/stm32_otgfsdev.c | 31 +- nuttx/include/nuttx/usb/usbdev_trace.h | 5 + 5 files changed, 434 insertions(+), 310 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h b/nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h index 8caeada17..d4bae8358 100644 --- a/nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h +++ b/nuttx/arch/arm/src/lm/chip/lm3s_memorymap.h @@ -137,7 +137,7 @@ /* -0x47fff: Reserved */ # define LM_ETHCON_BASE (LM_PERIPH_BASE + 0x48000) /* -0x48fff: Ethernet Controller */ /* -0xfcfff: Reserved */ -# define LM_HIBERNATE_BASE (LM_PERIPH_BASE + 0xfc000) /* -0xfcfff: Ethernet Controller */ +# define LM_HIBERNATE_BASE (LM_PERIPH_BASE + 0xfc000) /* -0xfcfff: Hibernation Controller */ # define LM_FLASHCON_BASE (LM_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */ # define LM_SYSCON_BASE (LM_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */ /* -0x1ffffff: Reserved */ @@ -176,7 +176,7 @@ /* -0x47fff: Reserved */ # define LM_ETHCON_BASE (LM_PERIPH_BASE + 0x48000) /* -0x48fff: Ethernet Controller */ /* -0xfcfff: Reserved */ -# define LM_HIBERNATE_BASE (LM_PERIPH_BASE + 0xfc000) /* -0xfcfff: Ethernet Controller */ +# define LM_HIBERNATE_BASE (LM_PERIPH_BASE + 0xfc000) /* -0xfcfff: Hibernation Controller */ # define LM_FLASHCON_BASE (LM_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */ # define LM_SYSCON_BASE (LM_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */ /* -0x1ffffff: Reserved */ @@ -223,7 +223,7 @@ /* -0x47fff: Reserved */ # define LM_ETHCON_BASE (LM_PERIPH_BASE + 0x48000) /* -0x48fff: Ethernet Controller */ /* -0xfcfff: Reserved */ -# define LM_HIBERNATE_BASE (LM_PERIPH_BASE + 0xfc000) /* -0xfcfff: Ethernet Controller */ +# define LM_HIBERNATE_BASE (LM_PERIPH_BASE + 0xfc000) /* -0xfcfff: Hibernation Controller */ # define LM_FLASHCON_BASE (LM_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */ # define LM_SYSCON_BASE (LM_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */ /* -0x1ffffff: Reserved */ diff --git a/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h index c8c62d4b4..4d715e470 100644 --- a/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h +++ b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h @@ -146,7 +146,12 @@ /* -0xaefff: Reserved */ # define LM_EEPROM_BASE (LM_PERIPH_BASE + 0xaf000) /* -0xaffff: EEPROM and Key Locker */ /* -0xf8fff: Reserved */ -/* @TODO */ +# define LM_SYSEXC_BASE (LM_PERIPH_BASE + 0xf9000) /* -0xf9fff: System Exception Control */ + /* -0xfbfff: Reserved */ +# define LM_HIBERNATE_BASE (LM_PERIPH_BASE + 0xfc000) /* -0xfcfff: Hibernation Controller */ +# define LM_FLASHCON_BASE (LM_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */ +# define LM_SYSCON_BASE (LM_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */ +# define LM_UDMA_BASE (LM_PERIPH_BASE + 0xff000) /* -0xfffff: Micro Direct Memory Access */ #else # error "Peripheral base addresses not specified for this Stellaris chip" #endif diff --git a/nuttx/arch/arm/src/lm/chip/lm_gpio.h b/nuttx/arch/arm/src/lm/chip/lm_gpio.h index 30b850fca..ebb5aa94f 100644 --- a/nuttx/arch/arm/src/lm/chip/lm_gpio.h +++ b/nuttx/arch/arm/src/lm/chip/lm_gpio.h @@ -2,7 +2,8 @@ * arch/arm/src/lm/chip/lm_gpio.h * * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Authors: Gregory Nutt + * Jose Pablo Carballo * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -68,6 +69,14 @@ #define LM_GPIO_DEN_OFFSET 0x51C /* GPIO Digital Enable */ #define LM_GPIO_LOCK_OFFSET 0x520 /* GPIO Lock */ #define LM_GPIO_CR_OFFSET 0x524 /* GPIO Commit */ + +#ifdef LM4F +# define LM_GPIO_AMSEL_OFFSET 0x528 /* GPIO Analog Mode Select */ +# define LM_GPIO_PCTL_OFFSET 0x52c /* GPIO Port Control */ +# define LM_GPIO_ADCCTL_OFFSET 0x530 /* GPIO ADC Control */ +# define LM_GPIO_DMACTL_OFFSET 0x534 /* GPIO DMA Control */ +#endif + #define LM_GPIO_PERIPHID4_OFFSET 0xfd0 /* GPIO Peripheral Identification 4 */ #define LM_GPIO_PERIPHID5_OFFSET 0xfd4 /* GPIO Peripheral Identification 5 */ #define LM_GPIO_PERIPHID6_OFFSET 0xfd8 /* GPIO Peripheral Identification 6 */ @@ -83,302 +92,394 @@ /* GPIO Register Addresses **********************************************************/ -#define LM_GPIOA_DATA (LM_GPIOA_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOA_DIR (LM_GPIOA_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOA_IS (LM_GPIOA_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOA_IBE (LM_GPIOA_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOA_IEV (LM_GPIOA_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOA_IM (LM_GPIOA_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOA_RIS (LM_GPIOA_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOA_MIS (LM_GPIOA_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOA_ICR (LM_GPIOA_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOA_AFSEL (LM_GPIOA_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOA_DR2R (LM_GPIOA_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOA_DR4R (LM_GPIOA_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOA_DR8R (LM_GPIOA_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOA_ODR (LM_GPIOA_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOA_PUR (LM_GPIOA_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOA_PDR (LM_GPIOA_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOA_SLR (LM_GPIOA_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOA_DEN (LM_GPIOA_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOA_LOCK (LM_GPIOA_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOA_CR (LM_GPIOA_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOA_PERIPHID4 (LM_GPIOA_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOA_PERIPHID5 (LM_GPIOA_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOA_PERIPHID6 (LM_GPIOA_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOA_PERIPHID7 (LM_GPIOA_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOA_PERIPHID0 (LM_GPIOA_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOA_PERIPHID1 (LM_GPIOA_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOA_PERIPHID2 (LM_GPIOA_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOA_PERIPHID3 (LM_GPIOA_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOA_PCELLID0 (LM_GPIOA_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOA_PCELLID1 (LM_GPIOA_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOA_PCELLID2 (LM_GPIOA_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOA_PCELLID3 (LM_GPIOA_BASE + LM_GPIO_PCELLID3_OFFSET) - -#define LM_GPIOB_DATA (LM_GPIOB_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOB_DIR (LM_GPIOB_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOB_IS (LM_GPIOB_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOB_IBE (LM_GPIOB_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOB_IEV (LM_GPIOB_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOB_IM (LM_GPIOB_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOB_RIS (LM_GPIOB_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOB_MIS (LM_GPIOB_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOB_ICR (LM_GPIOB_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOB_AFSEL (LM_GPIOB_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOB_DR2R (LM_GPIOB_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOB_DR4R (LM_GPIOB_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOB_DR8R (LM_GPIOB_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOB_ODR (LM_GPIOB_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOB_PUR (LM_GPIOB_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOB_PDR (LM_GPIOB_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOB_SLR (LM_GPIOB_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOB_DEN (LM_GPIOB_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOB_LOCK (LM_GPIOB_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOB_CR (LM_GPIOB_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOB_PERIPHID4 (LM_GPIOB_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOB_PERIPHID5 (LM_GPIOB_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOB_PERIPHID6 (LM_GPIOB_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOB_PERIPHID7 (LM_GPIOB_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOB_PERIPHID0 (LM_GPIOB_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOB_PERIPHID1 (LM_GPIOB_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOB_PERIPHID2 (LM_GPIOB_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOB_PERIPHID3 (LM_GPIOB_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOB_PCELLID0 (LM_GPIOB_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOB_PCELLID1 (LM_GPIOB_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOB_PCELLID2 (LM_GPIOB_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOB_PCELLID3 (LM_GPIOB_BASE + LM_GPIO_PCELLID3_OFFSET) - -#define LM_GPIOC_DATA (LM_GPIOC_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOC_DIR (LM_GPIOC_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOC_IS (LM_GPIOC_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOC_IBE (LM_GPIOC_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOC_IEV (LM_GPIOC_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOC_IM (LM_GPIOC_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOC_RIS (LM_GPIOC_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOC_MIS (LM_GPIOC_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOC_ICR (LM_GPIOC_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOC_AFSEL (LM_GPIOC_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOC_DR2R (LM_GPIOC_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOC_DR4R (LM_GPIOC_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOC_DR8R (LM_GPIOC_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOC_ODR (LM_GPIOC_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOC_PUR (LM_GPIOC_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOC_PDR (LM_GPIOC_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOC_SLR (LM_GPIOC_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOC_DEN (LM_GPIOC_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOC_LOCK (LM_GPIOC_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOC_CR (LM_GPIOC_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOC_PERIPHID4 (LM_GPIOC_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOC_PERIPHID5 (LM_GPIOC_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOC_PERIPHID6 (LM_GPIOC_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOC_PERIPHID7 (LM_GPIOC_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOC_PERIPHID0 (LM_GPIOC_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOC_PERIPHID1 (LM_GPIOC_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOC_PERIPHID2 (LM_GPIOC_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOC_PERIPHID3 (LM_GPIOC_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOC_PCELLID0 (LM_GPIOC_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOC_PCELLID1 (LM_GPIOC_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOC_PCELLID2 (LM_GPIOC_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOC_PCELLID3 (LM_GPIOC_BASE + LM_GPIO_PCELLID3_OFFSET) - -#define LM_GPIOD_DATA (LM_GPIOD_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOD_DIR (LM_GPIOD_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOD_IS (LM_GPIOD_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOD_IBE (LM_GPIOD_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOD_IEV (LM_GPIOD_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOD_IM (LM_GPIOD_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOD_RIS (LM_GPIOD_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOD_MIS (LM_GPIOD_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOD_ICR (LM_GPIOD_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOD_AFSEL (LM_GPIOD_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOD_DR2R (LM_GPIOD_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOD_DR4R (LM_GPIOD_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOD_DR8R (LM_GPIOD_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOD_ODR (LM_GPIOD_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOD_PUR (LM_GPIOD_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOD_PDR (LM_GPIOD_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOD_SLR (LM_GPIOD_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOD_DEN (LM_GPIOD_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOD_LOCK (LM_GPIOD_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOD_CR (LM_GPIOD_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOD_PERIPHID4 (LM_GPIOD_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOD_PERIPHID5 (LM_GPIOD_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOD_PERIPHID6 (LM_GPIOD_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOD_PERIPHID7 (LM_GPIOD_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOD_PERIPHID0 (LM_GPIOD_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOD_PERIPHID1 (LM_GPIOD_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOD_PERIPHID2 (LM_GPIOD_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOD_PERIPHID3 (LM_GPIOD_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOD_PCELLID0 (LM_GPIOD_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOD_PCELLID1 (LM_GPIOD_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOD_PCELLID2 (LM_GPIOD_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOD_PCELLID3 (LM_GPIOD_BASE + LM_GPIO_PCELLID3_OFFSET) - -#define LM_GPIOE_DATA (LM_GPIOE_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOE_DIR (LM_GPIOE_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOE_IS (LM_GPIOE_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOE_IBE (LM_GPIOE_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOE_IEV (LM_GPIOE_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOE_IM (LM_GPIOE_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOE_RIS (LM_GPIOE_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOE_MIS (LM_GPIOE_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOE_ICR (LM_GPIOE_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOE_AFSEL (LM_GPIOE_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOE_DR2R (LM_GPIOE_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOE_DR4R (LM_GPIOE_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOE_DR8R (LM_GPIOE_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOE_ODR (LM_GPIOE_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOE_PUR (LM_GPIOE_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOE_PDR (LM_GPIOE_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOE_SLR (LM_GPIOE_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOE_DEN (LM_GPIOE_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOE_LOCK (LM_GPIOE_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOE_CR (LM_GPIOE_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOE_PERIPHID4 (LM_GPIOE_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOE_PERIPHID5 (LM_GPIOE_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOE_PERIPHID6 (LM_GPIOE_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOE_PERIPHID7 (LM_GPIOE_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOE_PERIPHID0 (LM_GPIOE_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOE_PERIPHID1 (LM_GPIOE_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOE_PERIPHID2 (LM_GPIOE_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOE_PERIPHID3 (LM_GPIOE_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOE_PCELLID0 (LM_GPIOE_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOE_PCELLID1 (LM_GPIOE_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOE_PCELLID2 (LM_GPIOE_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOE_PCELLID3 (LM_GPIOE_BASE + LM_GPIO_PCELLID3_OFFSET) - -#define LM_GPIOF_DATA (LM_GPIOF_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOF_DIR (LM_GPIOF_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOF_IS (LM_GPIOF_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOF_IBE (LM_GPIOF_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOF_IEV (LM_GPIOF_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOF_IM (LM_GPIOF_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOF_RIS (LM_GPIOF_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOF_MIS (LM_GPIOF_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOF_ICR (LM_GPIOF_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOF_AFSEL (LM_GPIOF_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOF_DR2R (LM_GPIOF_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOF_DR4R (LM_GPIOF_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOF_DR8R (LM_GPIOF_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOF_ODR (LM_GPIOF_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOF_PUR (LM_GPIOF_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOF_PDR (LM_GPIOF_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOF_SLR (LM_GPIOF_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOF_DEN (LM_GPIOF_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOF_LOCK (LM_GPIOF_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOF_CR (LM_GPIOF_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOF_PERIPHID4 (LM_GPIOF_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOF_PERIPHID5 (LM_GPIOF_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOF_PERIPHID6 (LM_GPIOF_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOF_PERIPHID7 (LM_GPIOF_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOF_PERIPHID0 (LM_GPIOF_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOF_PERIPHID1 (LM_GPIOF_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOF_PERIPHID2 (LM_GPIOF_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOF_PERIPHID3 (LM_GPIOF_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOF_PCELLID0 (LM_GPIOF_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOF_PCELLID1 (LM_GPIOF_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOF_PCELLID2 (LM_GPIOF_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOF_PCELLID3 (LM_GPIOF_BASE + LM_GPIO_PCELLID3_OFFSET) - -#define LM_GPIOG_DATA (LM_GPIOG_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOG_DIR (LM_GPIOG_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOG_IS (LM_GPIOG_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOG_IBE (LM_GPIOG_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOG_IEV (LM_GPIOG_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOG_IM (LM_GPIOG_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOG_RIS (LM_GPIOG_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOG_MIS (LM_GPIOG_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOG_ICR (LM_GPIOG_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOG_AFSEL (LM_GPIOG_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOG_DR2R (LM_GPIOG_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOG_DR4R (LM_GPIOG_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOG_DR8R (LM_GPIOG_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOG_ODR (LM_GPIOG_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOG_PUR (LM_GPIOG_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOG_PDR (LM_GPIOG_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOG_SLR (LM_GPIOG_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOG_DEN (LM_GPIOG_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOG_LOCK (LM_GPIOG_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOG_CR (LM_GPIOG_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOG_PERIPHID4 (LM_GPIOG_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOG_PERIPHID5 (LM_GPIOG_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOG_PERIPHID6 (LM_GPIOG_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOG_PERIPHID7 (LM_GPIOG_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOG_PERIPHID0 (LM_GPIOG_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOG_PERIPHID1 (LM_GPIOG_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOG_PERIPHID2 (LM_GPIOG_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOG_PERIPHID3 (LM_GPIOG_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOG_PCELLID0 (LM_GPIOG_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOG_PCELLID1 (LM_GPIOG_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOG_PCELLID2 (LM_GPIOG_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOG_PCELLID3 (LM_GPIOG_BASE + LM_GPIO_PCELLID3_OFFSET) - -#define LM_GPIOH_DATA (LM_GPIOH_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOH_DIR (LM_GPIOH_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOH_IS (LM_GPIOH_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOH_IBE (LM_GPIOH_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOH_IEV (LM_GPIOH_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOH_IM (LM_GPIOH_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOH_RIS (LM_GPIOH_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOH_MIS (LM_GPIOH_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOH_ICR (LM_GPIOH_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOH_AFSEL (LM_GPIOH_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOH_DR2R (LM_GPIOH_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOH_DR4R (LM_GPIOH_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOH_DR8R (LM_GPIOH_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOH_ODR (LM_GPIOH_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOH_PUR (LM_GPIOH_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOH_PDR (LM_GPIOH_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOH_SLR (LM_GPIOH_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOH_DEN (LM_GPIOH_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOH_LOCK (LM_GPIOH_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOH_CR (LM_GPIOH_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOH_PERIPHID4 (LM_GPIOH_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOH_PERIPHID5 (LM_GPIOH_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOH_PERIPHID6 (LM_GPIOH_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOH_PERIPHID7 (LM_GPIOH_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOH_PERIPHID0 (LM_GPIOH_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOH_PERIPHID1 (LM_GPIOH_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOH_PERIPHID2 (LM_GPIOH_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOH_PERIPHID3 (LM_GPIOH_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOH_PCELLID0 (LM_GPIOH_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOH_PCELLID1 (LM_GPIOH_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOH_PCELLID2 (LM_GPIOH_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOH_PCELLID3 (LM_GPIOH_BASE + LM_GPIO_PCELLID3_OFFSET) - -#define LM_GPIOJ_DATA (LM_GPIOJ_BASE + LM_GPIO_DATA_OFFSET) -#define LM_GPIOJ_DIR (LM_GPIOJ_BASE + LM_GPIO_DIR_OFFSET) -#define LM_GPIOJ_IS (LM_GPIOJ_BASE + LM_GPIO_IS_OFFSET) -#define LM_GPIOJ_IBE (LM_GPIOJ_BASE + LM_GPIO_IBE_OFFSET) -#define LM_GPIOJ_IEV (LM_GPIOJ_BASE + LM_GPIO_IEV_OFFSET) -#define LM_GPIOJ_IM (LM_GPIOJ_BASE + LM_GPIO_IM_OFFSET) -#define LM_GPIOJ_RIS (LM_GPIOJ_BASE + LM_GPIO_RIS_OFFSET) -#define LM_GPIOJ_MIS (LM_GPIOJ_BASE + LM_GPIO_MIS_OFFSET) -#define LM_GPIOJ_ICR (LM_GPIOJ_BASE + LM_GPIO_ICR_OFFSET) -#define LM_GPIOJ_AFSEL (LM_GPIOJ_BASE + LM_GPIO_AFSEL_OFFSET) -#define LM_GPIOJ_DR2R (LM_GPIOJ_BASE + LM_GPIO_DR2R_OFFSET) -#define LM_GPIOJ_DR4R (LM_GPIOJ_BASE + LM_GPIO_DR4R_OFFSET) -#define LM_GPIOJ_DR8R (LM_GPIOJ_BASE + LM_GPIO_DR8R_OFFSET) -#define LM_GPIOJ_ODR (LM_GPIOJ_BASE + LM_GPIO_ODR_OFFSET) -#define LM_GPIOJ_PUR (LM_GPIOJ_BASE + LM_GPIO_PUR_OFFSET) -#define LM_GPIOJ_PDR (LM_GPIOJ_BASE + LM_GPIO_PDR_OFFSET) -#define LM_GPIOJ_SLR (LM_GPIOJ_BASE + LM_GPIO_SLR_OFFSET) -#define LM_GPIOJ_DEN (LM_GPIOJ_BASE + LM_GPIO_DEN_OFFSET) -#define LM_GPIOJ_LOCK (LM_GPIOJ_BASE + LM_GPIO_LOCK_OFFSET) -#define LM_GPIOJ_CR (LM_GPIOJ_BASE + LM_GPIO_CR_OFFSET) -#define LM_GPIOJ_PERIPHID4 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID4_OFFSET) -#define LM_GPIOJ_PERIPHID5 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID5_OFFSET) -#define LM_GPIOJ_PERIPHID6 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID6_OFFSET) -#define LM_GPIOJ_PERIPHID7 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID7_OFFSET) -#define LM_GPIOJ_PERIPHID0 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID0_OFFSET) -#define LM_GPIOJ_PERIPHID1 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID1_OFFSET) -#define LM_GPIOJ_PERIPHID2 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID2_OFFSET) -#define LM_GPIOJ_PERIPHID3 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID3_OFFSET) -#define LM_GPIOJ_PCELLID0 (LM_GPIOJ_BASE + LM_GPIO_PCELLID0_OFFSET) -#define LM_GPIOJ_PCELLID1 (LM_GPIOJ_BASE + LM_GPIO_PCELLID1_OFFSET) -#define LM_GPIOJ_PCELLID2 (LM_GPIOJ_BASE + LM_GPIO_PCELLID2_OFFSET) -#define LM_GPIOJ_PCELLID3 (LM_GPIOJ_BASE + LM_GPIO_PCELLID3_OFFSET) +#if LM_NPORTS > 0 + +# define LM_GPIOA_DATA (LM_GPIOA_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOA_DIR (LM_GPIOA_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOA_IS (LM_GPIOA_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOA_IBE (LM_GPIOA_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOA_IEV (LM_GPIOA_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOA_IM (LM_GPIOA_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOA_RIS (LM_GPIOA_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOA_MIS (LM_GPIOA_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOA_ICR (LM_GPIOA_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOA_AFSEL (LM_GPIOA_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOA_DR2R (LM_GPIOA_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOA_DR4R (LM_GPIOA_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOA_DR8R (LM_GPIOA_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOA_ODR (LM_GPIOA_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOA_PUR (LM_GPIOA_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOA_PDR (LM_GPIOA_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOA_SLR (LM_GPIOA_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOA_DEN (LM_GPIOA_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOA_LOCK (LM_GPIOA_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOA_CR (LM_GPIOA_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOA_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOA_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOA_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOA_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOA_PERIPHID4 (LM_GPIOA_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOA_PERIPHID5 (LM_GPIOA_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOA_PERIPHID6 (LM_GPIOA_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOA_PERIPHID7 (LM_GPIOA_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOA_PERIPHID0 (LM_GPIOA_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOA_PERIPHID1 (LM_GPIOA_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOA_PERIPHID2 (LM_GPIOA_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOA_PERIPHID3 (LM_GPIOA_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOA_PCELLID0 (LM_GPIOA_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOA_PCELLID1 (LM_GPIOA_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOA_PCELLID2 (LM_GPIOA_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOA_PCELLID3 (LM_GPIOA_BASE + LM_GPIO_PCELLID3_OFFSET) + +#elif LM_NPORTS > 1 + +# define LM_GPIOB_DATA (LM_GPIOB_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOB_DIR (LM_GPIOB_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOB_IS (LM_GPIOB_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOB_IBE (LM_GPIOB_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOB_IEV (LM_GPIOB_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOB_IM (LM_GPIOB_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOB_RIS (LM_GPIOB_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOB_MIS (LM_GPIOB_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOB_ICR (LM_GPIOB_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOB_AFSEL (LM_GPIOB_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOB_DR2R (LM_GPIOB_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOB_DR4R (LM_GPIOB_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOB_DR8R (LM_GPIOB_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOB_ODR (LM_GPIOB_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOB_PUR (LM_GPIOB_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOB_PDR (LM_GPIOB_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOB_SLR (LM_GPIOB_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOB_DEN (LM_GPIOB_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOB_LOCK (LM_GPIOB_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOB_CR (LM_GPIOB_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOB_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOB_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOB_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOB_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOB_PERIPHID4 (LM_GPIOB_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOB_PERIPHID5 (LM_GPIOB_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOB_PERIPHID6 (LM_GPIOB_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOB_PERIPHID7 (LM_GPIOB_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOB_PERIPHID0 (LM_GPIOB_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOB_PERIPHID1 (LM_GPIOB_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOB_PERIPHID2 (LM_GPIOB_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOB_PERIPHID3 (LM_GPIOB_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOB_PCELLID0 (LM_GPIOB_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOB_PCELLID1 (LM_GPIOB_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOB_PCELLID2 (LM_GPIOB_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOB_PCELLID3 (LM_GPIOB_BASE + LM_GPIO_PCELLID3_OFFSET) + +#elif LM_NPORTS > 2 + +# define LM_GPIOC_DATA (LM_GPIOC_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOC_DIR (LM_GPIOC_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOC_IS (LM_GPIOC_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOC_IBE (LM_GPIOC_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOC_IEV (LM_GPIOC_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOC_IM (LM_GPIOC_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOC_RIS (LM_GPIOC_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOC_MIS (LM_GPIOC_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOC_ICR (LM_GPIOC_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOC_AFSEL (LM_GPIOC_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOC_DR2R (LM_GPIOC_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOC_DR4R (LM_GPIOC_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOC_DR8R (LM_GPIOC_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOC_ODR (LM_GPIOC_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOC_PUR (LM_GPIOC_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOC_PDR (LM_GPIOC_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOC_SLR (LM_GPIOC_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOC_DEN (LM_GPIOC_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOC_LOCK (LM_GPIOC_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOC_CR (LM_GPIOC_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOC_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOC_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOC_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOC_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOC_PERIPHID4 (LM_GPIOC_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOC_PERIPHID5 (LM_GPIOC_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOC_PERIPHID6 (LM_GPIOC_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOC_PERIPHID7 (LM_GPIOC_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOC_PERIPHID0 (LM_GPIOC_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOC_PERIPHID1 (LM_GPIOC_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOC_PERIPHID2 (LM_GPIOC_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOC_PERIPHID3 (LM_GPIOC_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOC_PCELLID0 (LM_GPIOC_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOC_PCELLID1 (LM_GPIOC_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOC_PCELLID2 (LM_GPIOC_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOC_PCELLID3 (LM_GPIOC_BASE + LM_GPIO_PCELLID3_OFFSET) + +#elif LM_NPORTS > 3 + +# define LM_GPIOD_DATA (LM_GPIOD_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOD_DIR (LM_GPIOD_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOD_IS (LM_GPIOD_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOD_IBE (LM_GPIOD_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOD_IEV (LM_GPIOD_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOD_IM (LM_GPIOD_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOD_RIS (LM_GPIOD_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOD_MIS (LM_GPIOD_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOD_ICR (LM_GPIOD_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOD_AFSEL (LM_GPIOD_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOD_DR2R (LM_GPIOD_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOD_DR4R (LM_GPIOD_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOD_DR8R (LM_GPIOD_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOD_ODR (LM_GPIOD_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOD_PUR (LM_GPIOD_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOD_PDR (LM_GPIOD_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOD_SLR (LM_GPIOD_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOD_DEN (LM_GPIOD_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOD_LOCK (LM_GPIOD_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOD_CR (LM_GPIOD_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOD_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOD_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOD_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOD_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOD_PERIPHID4 (LM_GPIOD_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOD_PERIPHID5 (LM_GPIOD_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOD_PERIPHID6 (LM_GPIOD_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOD_PERIPHID7 (LM_GPIOD_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOD_PERIPHID0 (LM_GPIOD_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOD_PERIPHID1 (LM_GPIOD_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOD_PERIPHID2 (LM_GPIOD_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOD_PERIPHID3 (LM_GPIOD_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOD_PCELLID0 (LM_GPIOD_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOD_PCELLID1 (LM_GPIOD_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOD_PCELLID2 (LM_GPIOD_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOD_PCELLID3 (LM_GPIOD_BASE + LM_GPIO_PCELLID3_OFFSET) + +#elif LM_NPORTS > 4 + +# define LM_GPIOE_DATA (LM_GPIOE_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOE_DIR (LM_GPIOE_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOE_IS (LM_GPIOE_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOE_IBE (LM_GPIOE_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOE_IEV (LM_GPIOE_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOE_IM (LM_GPIOE_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOE_RIS (LM_GPIOE_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOE_MIS (LM_GPIOE_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOE_ICR (LM_GPIOE_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOE_AFSEL (LM_GPIOE_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOE_DR2R (LM_GPIOE_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOE_DR4R (LM_GPIOE_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOE_DR8R (LM_GPIOE_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOE_ODR (LM_GPIOE_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOE_PUR (LM_GPIOE_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOE_PDR (LM_GPIOE_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOE_SLR (LM_GPIOE_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOE_DEN (LM_GPIOE_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOE_LOCK (LM_GPIOE_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOE_CR (LM_GPIOE_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOE_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOE_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOE_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOE_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOE_PERIPHID4 (LM_GPIOE_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOE_PERIPHID5 (LM_GPIOE_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOE_PERIPHID6 (LM_GPIOE_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOE_PERIPHID7 (LM_GPIOE_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOE_PERIPHID0 (LM_GPIOE_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOE_PERIPHID1 (LM_GPIOE_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOE_PERIPHID2 (LM_GPIOE_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOE_PERIPHID3 (LM_GPIOE_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOE_PCELLID0 (LM_GPIOE_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOE_PCELLID1 (LM_GPIOE_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOE_PCELLID2 (LM_GPIOE_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOE_PCELLID3 (LM_GPIOE_BASE + LM_GPIO_PCELLID3_OFFSET) + +#elif LM_NPORTS > 5 + +# define LM_GPIOF_DATA (LM_GPIOF_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOF_DIR (LM_GPIOF_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOF_IS (LM_GPIOF_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOF_IBE (LM_GPIOF_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOF_IEV (LM_GPIOF_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOF_IM (LM_GPIOF_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOF_RIS (LM_GPIOF_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOF_MIS (LM_GPIOF_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOF_ICR (LM_GPIOF_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOF_AFSEL (LM_GPIOF_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOF_DR2R (LM_GPIOF_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOF_DR4R (LM_GPIOF_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOF_DR8R (LM_GPIOF_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOF_ODR (LM_GPIOF_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOF_PUR (LM_GPIOF_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOF_PDR (LM_GPIOF_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOF_SLR (LM_GPIOF_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOF_DEN (LM_GPIOF_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOF_LOCK (LM_GPIOF_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOF_CR (LM_GPIOF_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOF_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOF_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOF_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOF_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOF_PERIPHID4 (LM_GPIOF_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOF_PERIPHID5 (LM_GPIOF_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOF_PERIPHID6 (LM_GPIOF_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOF_PERIPHID7 (LM_GPIOF_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOF_PERIPHID0 (LM_GPIOF_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOF_PERIPHID1 (LM_GPIOF_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOF_PERIPHID2 (LM_GPIOF_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOF_PERIPHID3 (LM_GPIOF_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOF_PCELLID0 (LM_GPIOF_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOF_PCELLID1 (LM_GPIOF_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOF_PCELLID2 (LM_GPIOF_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOF_PCELLID3 (LM_GPIOF_BASE + LM_GPIO_PCELLID3_OFFSET) + +#elif LM_NPORTS > 6 + +# define LM_GPIOG_DATA (LM_GPIOG_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOG_DIR (LM_GPIOG_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOG_IS (LM_GPIOG_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOG_IBE (LM_GPIOG_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOG_IEV (LM_GPIOG_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOG_IM (LM_GPIOG_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOG_RIS (LM_GPIOG_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOG_MIS (LM_GPIOG_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOG_ICR (LM_GPIOG_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOG_AFSEL (LM_GPIOG_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOG_DR2R (LM_GPIOG_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOG_DR4R (LM_GPIOG_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOG_DR8R (LM_GPIOG_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOG_ODR (LM_GPIOG_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOG_PUR (LM_GPIOG_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOG_PDR (LM_GPIOG_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOG_SLR (LM_GPIOG_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOG_DEN (LM_GPIOG_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOG_LOCK (LM_GPIOG_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOG_CR (LM_GPIOG_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOG_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOG_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOG_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOG_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOG_PERIPHID4 (LM_GPIOG_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOG_PERIPHID5 (LM_GPIOG_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOG_PERIPHID6 (LM_GPIOG_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOG_PERIPHID7 (LM_GPIOG_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOG_PERIPHID0 (LM_GPIOG_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOG_PERIPHID1 (LM_GPIOG_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOG_PERIPHID2 (LM_GPIOG_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOG_PERIPHID3 (LM_GPIOG_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOG_PCELLID0 (LM_GPIOG_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOG_PCELLID1 (LM_GPIOG_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOG_PCELLID2 (LM_GPIOG_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOG_PCELLID3 (LM_GPIOG_BASE + LM_GPIO_PCELLID3_OFFSET) + +#elif LM_NPORTS > 7 + +# define LM_GPIOH_DATA (LM_GPIOH_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOH_DIR (LM_GPIOH_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOH_IS (LM_GPIOH_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOH_IBE (LM_GPIOH_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOH_IEV (LM_GPIOH_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOH_IM (LM_GPIOH_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOH_RIS (LM_GPIOH_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOH_MIS (LM_GPIOH_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOH_ICR (LM_GPIOH_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOH_AFSEL (LM_GPIOH_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOH_DR2R (LM_GPIOH_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOH_DR4R (LM_GPIOH_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOH_DR8R (LM_GPIOH_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOH_ODR (LM_GPIOH_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOH_PUR (LM_GPIOH_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOH_PDR (LM_GPIOH_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOH_SLR (LM_GPIOH_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOH_DEN (LM_GPIOH_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOH_LOCK (LM_GPIOH_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOH_CR (LM_GPIOH_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOH_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOH_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOH_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOH_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOH_PERIPHID4 (LM_GPIOH_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOH_PERIPHID5 (LM_GPIOH_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOH_PERIPHID6 (LM_GPIOH_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOH_PERIPHID7 (LM_GPIOH_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOH_PERIPHID0 (LM_GPIOH_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOH_PERIPHID1 (LM_GPIOH_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOH_PERIPHID2 (LM_GPIOH_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOH_PERIPHID3 (LM_GPIOH_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOH_PCELLID0 (LM_GPIOH_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOH_PCELLID1 (LM_GPIOH_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOH_PCELLID2 (LM_GPIOH_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOH_PCELLID3 (LM_GPIOH_BASE + LM_GPIO_PCELLID3_OFFSET) + +#elif LM_NPORTS > 8 + +# define LM_GPIOJ_DATA (LM_GPIOJ_BASE + LM_GPIO_DATA_OFFSET) +# define LM_GPIOJ_DIR (LM_GPIOJ_BASE + LM_GPIO_DIR_OFFSET) +# define LM_GPIOJ_IS (LM_GPIOJ_BASE + LM_GPIO_IS_OFFSET) +# define LM_GPIOJ_IBE (LM_GPIOJ_BASE + LM_GPIO_IBE_OFFSET) +# define LM_GPIOJ_IEV (LM_GPIOJ_BASE + LM_GPIO_IEV_OFFSET) +# define LM_GPIOJ_IM (LM_GPIOJ_BASE + LM_GPIO_IM_OFFSET) +# define LM_GPIOJ_RIS (LM_GPIOJ_BASE + LM_GPIO_RIS_OFFSET) +# define LM_GPIOJ_MIS (LM_GPIOJ_BASE + LM_GPIO_MIS_OFFSET) +# define LM_GPIOJ_ICR (LM_GPIOJ_BASE + LM_GPIO_ICR_OFFSET) +# define LM_GPIOJ_AFSEL (LM_GPIOJ_BASE + LM_GPIO_AFSEL_OFFSET) +# define LM_GPIOJ_DR2R (LM_GPIOJ_BASE + LM_GPIO_DR2R_OFFSET) +# define LM_GPIOJ_DR4R (LM_GPIOJ_BASE + LM_GPIO_DR4R_OFFSET) +# define LM_GPIOJ_DR8R (LM_GPIOJ_BASE + LM_GPIO_DR8R_OFFSET) +# define LM_GPIOJ_ODR (LM_GPIOJ_BASE + LM_GPIO_ODR_OFFSET) +# define LM_GPIOJ_PUR (LM_GPIOJ_BASE + LM_GPIO_PUR_OFFSET) +# define LM_GPIOJ_PDR (LM_GPIOJ_BASE + LM_GPIO_PDR_OFFSET) +# define LM_GPIOJ_SLR (LM_GPIOJ_BASE + LM_GPIO_SLR_OFFSET) +# define LM_GPIOJ_DEN (LM_GPIOJ_BASE + LM_GPIO_DEN_OFFSET) +# define LM_GPIOJ_LOCK (LM_GPIOJ_BASE + LM_GPIO_LOCK_OFFSET) +# define LM_GPIOJ_CR (LM_GPIOJ_BASE + LM_GPIO_CR_OFFSET) + +# ifdef LM4F +# define LM_GPIOJ_AMSEL (LM_GPIOA_BASE + LM_GPIO_AMSEL_OFFSET) +# define LM_GPIOJ_PCTL (LM_GPIOA_BASE + LM_GPIO_PCTL_OFFSET) +# define LM_GPIOJ_ADCCTL (LM_GPIOA_BASE + LM_GPIO_ADCCTL_OFFSET) +# define LM_GPIOJ_DMACTL (LM_GPIOA_BASE + LM_GPIO_DMACTL_OFFSET) +# endif + +# define LM_GPIOJ_PERIPHID4 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID4_OFFSET) +# define LM_GPIOJ_PERIPHID5 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID5_OFFSET) +# define LM_GPIOJ_PERIPHID6 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID6_OFFSET) +# define LM_GPIOJ_PERIPHID7 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID7_OFFSET) +# define LM_GPIOJ_PERIPHID0 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID0_OFFSET) +# define LM_GPIOJ_PERIPHID1 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID1_OFFSET) +# define LM_GPIOJ_PERIPHID2 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID2_OFFSET) +# define LM_GPIOJ_PERIPHID3 (LM_GPIOJ_BASE + LM_GPIO_PERIPHID3_OFFSET) +# define LM_GPIOJ_PCELLID0 (LM_GPIOJ_BASE + LM_GPIO_PCELLID0_OFFSET) +# define LM_GPIOJ_PCELLID1 (LM_GPIOJ_BASE + LM_GPIO_PCELLID1_OFFSET) +# define LM_GPIOJ_PCELLID2 (LM_GPIOJ_BASE + LM_GPIO_PCELLID2_OFFSET) +# define LM_GPIOJ_PCELLID3 (LM_GPIOJ_BASE + LM_GPIO_PCELLID3_OFFSET) + +#endif /* LM_NPORTS */ /************************************************************************************ * Public Types diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c index 94772b693..9307545a3 100644 --- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c @@ -184,8 +184,9 @@ #define STM32_TRACEERR_NOEP 0x18 #define STM32_TRACEERR_NOTCONFIGURED 0x19 #define STM32_TRACEERR_EPOUTQEMPTY 0x1a -#define STM32_TRACEERR_EPINQEMPTY 0x1b +#define STM32_TRACEERR_EPINREQEMPTY 0x1b #define STM32_TRACEERR_NOOUTSETUP 0x1c +#define STM32_TRACEERR_POLLTIMEOUT 0x1d /* Trace interrupt codes */ @@ -1084,6 +1085,7 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, uint32_t regval; #ifdef ENABLE_DTXFSTS_POLLHACK int32_t timeout; + int avail; #endif uint8_t *buf; int nbytes; @@ -1113,7 +1115,7 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, privreq = stm32_rqpeek(privep); if (!privreq) { - usbtrace(TRACE_DEVERROR(STM32_TRACEERR_EPINQEMPTY), privep->epphy); + usbtrace(TRACE_DEVERROR(STM32_TRACEERR_EPINREQEMPTY), privep->epphy); /* There is no TX transfer in progress and no new pending TX * requests to send. To stop transmitting any data on a particular @@ -1221,18 +1223,28 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, #ifdef ENABLE_DTXFSTS_POLLHACK /* If ENABLE_DTXFSTS_POLLHACK is enabled , then poll DTXFSTS until - * space in the TxFIFO is available. If it doesn't become available, - * in a reasonable amount of time, then just pretend that it is. + * space in the TxFIFO is available. */ for (timeout = 250000; timeout > 0; timeout--) { - regval = stm32_getreg(regaddr); - if ((regval & OTGFS_DTXFSTS_MASK) >= nwords) + avail = stm32_getreg(regaddr) & OTGFS_DTXFSTS_MASK; + if (avail >= nwords) { break; } } + + /* If it did not become available in a reasonable amount of time, + * then just return. We should come back through this logic later + * anyway. + */ + + if (avail < nwords) + { + usbtrace(TRACE_DEVERROR(STM32_TRACEERR_POLLTIMEOUT), avail); + return; + } #else /* If ENABLE_DTXFSTS_POLLHACK is not enabled, then check once for * space in the TxFIFO. If space in the TxFIFO is not available, @@ -1290,11 +1302,12 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, if (privreq->req.xfrd >= privreq->req.len && !privep->zlp) { usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd); - stm32_req_complete(privep, OK); - /* The endpoint is no longer transferring data */ + /* We are finished with the request (although the transfer has not + * yet completed). + */ - privep->active = false; + stm32_req_complete(privep, OK); } } diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h index ab3a5f4be..860f48983 100644 --- a/nuttx/include/nuttx/usb/usbdev_trace.h +++ b/nuttx/include/nuttx/usb/usbdev_trace.h @@ -104,6 +104,7 @@ #define TRACE_DEVUNINIT TRACE_EVENT(TRACE_INIT_ID, 0x0002) #define TRACE_DEVREGISTER TRACE_EVENT(TRACE_INIT_ID, 0x0003) #define TRACE_DEVUNREGISTER TRACE_EVENT(TRACE_INIT_ID, 0x0004) +#define TRACE_DEVINIT_USER TRACE_EVENT(TRACE_INIT_ID, 0x0005) /* First user-defined */ /* API calls (see usbdev.h) */ @@ -117,6 +118,7 @@ #define TRACE_EPCANCEL TRACE_EVENT(TRACE_EP_ID, 0x0008) #define TRACE_EPSTALL TRACE_EVENT(TRACE_EP_ID, 0x0009) #define TRACE_EPRESUME TRACE_EVENT(TRACE_EP_ID, 0x000a) +#define TRACE_EPAPI_USER TRACE_EVENT(TRACE_EP_ID, 0x000b) /* First user-defined */ #define TRACE_DEVALLOCEP TRACE_EVENT(TRACE_DEV_ID, 0x0001) #define TRACE_DEVFREEEP TRACE_EVENT(TRACE_DEV_ID, 0x0002) @@ -124,6 +126,7 @@ #define TRACE_DEVWAKEUP TRACE_EVENT(TRACE_DEV_ID, 0x0004) #define TRACE_DEVSELFPOWERED TRACE_EVENT(TRACE_DEV_ID, 0x0005) #define TRACE_DEVPULLUP TRACE_EVENT(TRACE_DEV_ID, 0x0006) +#define TRACE_DEVAPI_USER TRACE_EVENT(TRACE_DEV_ID, 0x0007) /* First user-defined */ #define TRACE_CLASSBIND TRACE_EVENT(TRACE_CLASS_ID, 0x0001) #define TRACE_CLASSUNBIND TRACE_EVENT(TRACE_CLASS_ID, 0x0002) @@ -135,6 +138,8 @@ #define TRACE_CLASSRDCOMPLETE TRACE_EVENT(TRACE_CLASS_ID, 0x0007) #define TRACE_CLASSWRCOMPLETE TRACE_EVENT(TRACE_CLASS_ID, 0x0008) +#define TRACE_CLASSAPI_USER TRACE_EVENT(TRACE_CLASS_ID, 0x0009) /* First user-defined */ + #define TRACE_CLASSAPI(id) TRACE_EVENT(TRACE_CLASSAPI_ID, id) #define TRACE_CLASSSTATE(id) TRACE_EVENT(TRACE_CLASSSTATE_ID, id) -- cgit v1.2.3 From b433eca18dc2a8e09f22d95b0f13e32dd2193e1a Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 30 Jan 2013 22:25:25 +0000 Subject: The STM32 F2/4 OTG FS device driver seems to be functional git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5587 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/stm32_otgfsdev.c | 76 ++++++++++++++++++++++--------- 1 file changed, 54 insertions(+), 22 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c index 9307545a3..17aa7313d 100644 --- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c @@ -509,7 +509,7 @@ static void stm32_ep0out_ctrlsetup(FAR struct stm32_usbdev_s *priv); static void stm32_txfifo_write(FAR struct stm32_ep_s *privep, FAR uint8_t *buf, int nbytes); static void stm32_epin_transfer(FAR struct stm32_ep_s *privep, - FAR uint8_t *buf, int nbytes); + FAR uint8_t *buf, int nbytes); static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, FAR struct stm32_ep_s *privep); @@ -556,7 +556,9 @@ static inline void stm32_epout_interrupt(FAR struct stm32_usbdev_s *priv); static inline void stm32_epin_runtestmode(FAR struct stm32_usbdev_s *priv); static inline void stm32_epin(FAR struct stm32_usbdev_s *priv, uint8_t epno); +#ifndef ENABLE_DTXFSTS_POLLHACK static inline void stm32_epin_txfifoempty(FAR struct stm32_usbdev_s *priv, int epno); +#endif static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv); /* Other second level interrupt processing */ @@ -963,7 +965,7 @@ static void stm32_txfifo_write(FAR struct stm32_ep_s *privep, regval |= ((uint32_t)*buf++) << 16; regval |= ((uint32_t)*buf++) << 24; - /* Then write the packed data to the TxFIFO */ + /* Then write the packet data to the TxFIFO */ stm32_putreg(regval, regaddr); } @@ -1153,13 +1155,20 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, privep->zlp = true; } - /* Loop while there are still bytes to be transferred (or a zero-length- - * packet, ZLP, to be sent). The loop will also be terminated if there - * is insufficient space remaining in the TxFIFO to send a complete - * packet. + /* Add one more packet to the TxFIFO. We will wait for the transfer + * complete event before we add the next packet (or part of a packet + * to the TxFIFO). + * + * The documentation says that we can can multiple packets to the TxFIFO, + * but it seems that we need to get the transfer complete event before + * we can add the next (or maybe I have got something wrong?) */ +#if 0 while (privreq->req.xfrd < privreq->req.len || privep->zlp) +#else + if (privreq->req.xfrd < privreq->req.len || privep->zlp) +#endif { /* Get the number of bytes left to be sent in the request */ @@ -1240,8 +1249,11 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, * anyway. */ + DEBUGASSERT(avail < nwords); if (avail < nwords) { + /* We will probably not recover from what we are about to do */ + usbtrace(TRACE_DEVERROR(STM32_TRACEERR_POLLTIMEOUT), avail); return; } @@ -1265,9 +1277,11 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, empmsk |= OTGFS_DIEPEMPMSK(privep->epphy); stm32_putreg(empmsk, STM32_OTGFS_DIEPEMPMSK); - /* Terminate the transfer loop */ + /* Terminate the transfer loop. We will try again when the + * TxFIFO empty interrupt is received. + */ - break; + return; } #endif @@ -2698,17 +2712,19 @@ static inline void stm32_epin(FAR struct stm32_usbdev_s *priv, uint8_t epno) * ****************************************************************************/ +#ifndef ENABLE_DTXFSTS_POLLHACK static inline void stm32_epin_txfifoempty(FAR struct stm32_usbdev_s *priv, int epno) { FAR struct stm32_ep_s *privep = &priv->epin[epno]; /* Continue processing the write request queue. This may mean sending - * more dat from the exisiting request or terminating the current requests + * more data from the exisiting request or terminating the current requests * and (perhaps) starting the IN transfer from the next write request. */ stm32_epin_request(priv, privep); } +#endif /******************************************************************************* * Name: stm32_epin_interrupt @@ -2754,16 +2770,20 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) mask = stm32_getreg(STM32_OTGFS_DIEPMSK); - /* Check for FIFO not empty. Bits n corresponds to endpoint n. - * That condition corresponds to bit 7 of the DIEPINT interrupt - * status register. + /* Check if the TxFIFO not empty interrupt is enabled for this + * endpoint in the DIEPMSK register. Bits n corresponds to + * endpoint n in the register. That condition corresponds to + * bit 7 of the DIEPINT interrupt status register. There is + * no TXFE bit in the mask register, so we fake one here. */ +#ifndef ENABLE_DTXFSTS_POLLHACK empty = stm32_getreg(STM32_OTGFS_DIEPEMPMSK); if ((empty & OTGFS_DIEPEMPMSK(epno)) != 0) { mask |= OTGFS_DIEPINT_TXFE; } +#endif /* Now, read the interrupt status and mask out all disabled * interrupts. @@ -2776,15 +2796,19 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) if ((diepint & OTGFS_DIEPINT_XFRC) != 0) { - usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_XFRC), (uint16_t)diepint); - - /* It is possible that logic may be waiting for a the TxFIFO to become - * empty. We disable the TxFIFO empty interrupt here; it will be - * re-enabled if there is still insufficient space in the TxFIFO. + usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_XFRC), + (uint16_t)diepint); + +#ifndef ENABLE_DTXFSTS_POLLHACK + /* It is possible that logic may be waiting for a the + * TxFIFO to become empty. We disable the TxFIFO empty + * interrupt here; it will be re-enabled if there is still + * insufficient space in the TxFIFO. */ empty &= ~OTGFS_DIEPEMPMSK(epno); stm32_putreg(empty, STM32_OTGFS_DIEPEMPMSK); +#endif stm32_putreg(OTGFS_DIEPINT_XFRC, STM32_OTGFS_DIEPINT(epno)); /* IN transfer complete */ @@ -2836,12 +2860,13 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) #endif /* Transmit FIFO empty */ +#ifndef ENABLE_DTXFSTS_POLLHACK if ((diepint & OTGFS_DIEPINT_TXFE) != 0) { usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_TXFE), (uint16_t)diepint); /* If we were waiting for TxFIFO to become empty, the we might have both - * XFRC and TXFE interrups pending. Since we do the same thing for both + * XFRC and TXFE interrupts pending. Since we do the same thing for both * cases, ignore the TXFE if we have already processed the XFRC. */ @@ -2863,6 +2888,7 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) stm32_putreg(OTGFS_DIEPINT_TXFE, STM32_OTGFS_DIEPINT(epno)); } +#endif } epno++; @@ -4970,8 +4996,9 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv) /* At startup the core is in FS mode. */ - /* Disable the USB global interrupt by clearing GINTMSK in the global OTG - * FS AHB configuration register. + /* Disable global interrupts by clearing the GINTMASK bit in the GAHBCFG + * register; Set the TXFELVL bit in the GAHBCFG register so that TxFIFO + * interrupts will occur when the TxFIFO is truly empty (not just half full). */ stm32_putreg(OTGFS_GAHBCFG_TXFELVL, STM32_OTGFS_GAHBCFG); @@ -5087,6 +5114,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv) stm32_putreg(0, STM32_OTGFS_DIEPMSK); stm32_putreg(0, STM32_OTGFS_DOEPMSK); + stm32_putreg(0, STM32_OTGFS_DIEPEMPMSK); stm32_putreg(0xffffffff, STM32_OTGFS_DAINT); stm32_putreg(0, STM32_OTGFS_DAINTMSK); @@ -5168,10 +5196,13 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv) stm32_putreg(regval, STM32_OTGFS_GINTMSK); /* Enable the USB global interrupt by setting GINTMSK in the global OTG - * FS AHB configuration register. + * FS AHB configuration register; Set the TXFELVL bit in the GAHBCFG + * register so that TxFIFO interrupts will occur when the TxFIFO is truly + * empty (not just half full). */ - stm32_putreg(OTGFS_GAHBCFG_GINTMSK | OTGFS_GAHBCFG_TXFELVL, STM32_OTGFS_GAHBCFG); + stm32_putreg(OTGFS_GAHBCFG_GINTMSK | OTGFS_GAHBCFG_TXFELVL, + STM32_OTGFS_GAHBCFG); } /******************************************************************************* @@ -5327,6 +5358,7 @@ void up_usbuninitialize(void) stm32_putreg(0, STM32_OTGFS_DIEPMSK); stm32_putreg(0, STM32_OTGFS_DOEPMSK); + stm32_putreg(0, STM32_OTGFS_DIEPEMPMSK); stm32_putreg(0, STM32_OTGFS_DAINTMSK); stm32_putreg(0xffffffff, STM32_OTGFS_DAINT); -- cgit v1.2.3 From 94360f34746f039953b1465a2590d2d70d396282 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 30 Jan 2013 23:22:51 +0000 Subject: With the last fixes to the STM32 OTG FS driver, the old poll hack no longer seems necessary git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5588 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/TODO | 7 +--- nuttx/arch/arm/src/stm32/stm32_otgfsdev.c | 61 +++---------------------------- 2 files changed, 6 insertions(+), 62 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/TODO b/nuttx/TODO index 6b2c6c883..b5958f397 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 28, 2013) +NuttX TODO List (Last updated January 30, 2013) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -1505,11 +1505,6 @@ o ARM/STM32 (arch/arm/src/stm32/) Status: Open Priority: Low - Title: STM32 F4 USB OTG FS DEVICE-SIDE DRIVER - Description: This driver is reported to be buggy and to need some TLC. - Status: Open - Priority: High - o AVR (arch/avr) ^^^^^^^^^^^^^^ diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c index 17aa7313d..a2de6d138 100644 --- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c @@ -146,15 +146,6 @@ # error "CONFIG_USBDEV_EP3_TXFIFO_SIZE is out of range" #endif -/* REVISIT! This forces a hack that polls DTXFSTS for space in the Tx FIFO. - * Enabling this option is a BAD thing. It will cause inline waits inside - * of the USB interrupt handler. The correct way to handle this is to - * enable the correct TxFIFO interrupt and wait until the Tx FIFO is empty. - * Unfortunately, the interrupt driven logic is not working... Please fix! - */ - -#define ENABLE_DTXFSTS_POLLHACK 1 - /* Debug ***********************************************************************/ /* Trace error codes */ @@ -556,9 +547,7 @@ static inline void stm32_epout_interrupt(FAR struct stm32_usbdev_s *priv); static inline void stm32_epin_runtestmode(FAR struct stm32_usbdev_s *priv); static inline void stm32_epin(FAR struct stm32_usbdev_s *priv, uint8_t epno); -#ifndef ENABLE_DTXFSTS_POLLHACK static inline void stm32_epin_txfifoempty(FAR struct stm32_usbdev_s *priv, int epno); -#endif static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv); /* Other second level interrupt processing */ @@ -1085,10 +1074,8 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, struct stm32_req_s *privreq; uint32_t regaddr; uint32_t regval; -#ifdef ENABLE_DTXFSTS_POLLHACK int32_t timeout; int avail; -#endif uint8_t *buf; int nbytes; int nwords; @@ -1230,38 +1217,9 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, regaddr = STM32_OTGFS_DTXFSTS(privep->epphy); -#ifdef ENABLE_DTXFSTS_POLLHACK - /* If ENABLE_DTXFSTS_POLLHACK is enabled , then poll DTXFSTS until - * space in the TxFIFO is available. - */ - - for (timeout = 250000; timeout > 0; timeout--) - { - avail = stm32_getreg(regaddr) & OTGFS_DTXFSTS_MASK; - if (avail >= nwords) - { - break; - } - } - - /* If it did not become available in a reasonable amount of time, - * then just return. We should come back through this logic later - * anyway. - */ - - DEBUGASSERT(avail < nwords); - if (avail < nwords) - { - /* We will probably not recover from what we are about to do */ - - usbtrace(TRACE_DEVERROR(STM32_TRACEERR_POLLTIMEOUT), avail); - return; - } -#else - /* If ENABLE_DTXFSTS_POLLHACK is not enabled, then check once for - * space in the TxFIFO. If space in the TxFIFO is not available, - * then set up an interrupt to resume the transfer when the TxFIFO - * is empty. + /* Check for space in the TxFIFO. If space in the TxFIFO is not + * available, then set up an interrupt to resume the transfer when + * the TxFIFO is empty. */ regval = stm32_getreg(regaddr); @@ -1277,13 +1235,12 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, empmsk |= OTGFS_DIEPEMPMSK(privep->epphy); stm32_putreg(empmsk, STM32_OTGFS_DIEPEMPMSK); - /* Terminate the transfer loop. We will try again when the - * TxFIFO empty interrupt is received. + /* Terminate the transfer. We will try again when the TxFIFO empty + * interrupt is received. */ return; } -#endif /* Transfer data to the TxFIFO */ @@ -2712,7 +2669,6 @@ static inline void stm32_epin(FAR struct stm32_usbdev_s *priv, uint8_t epno) * ****************************************************************************/ -#ifndef ENABLE_DTXFSTS_POLLHACK static inline void stm32_epin_txfifoempty(FAR struct stm32_usbdev_s *priv, int epno) { FAR struct stm32_ep_s *privep = &priv->epin[epno]; @@ -2724,7 +2680,6 @@ static inline void stm32_epin_txfifoempty(FAR struct stm32_usbdev_s *priv, int e stm32_epin_request(priv, privep); } -#endif /******************************************************************************* * Name: stm32_epin_interrupt @@ -2777,13 +2732,11 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) * no TXFE bit in the mask register, so we fake one here. */ -#ifndef ENABLE_DTXFSTS_POLLHACK empty = stm32_getreg(STM32_OTGFS_DIEPEMPMSK); if ((empty & OTGFS_DIEPEMPMSK(epno)) != 0) { mask |= OTGFS_DIEPINT_TXFE; } -#endif /* Now, read the interrupt status and mask out all disabled * interrupts. @@ -2799,7 +2752,6 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_XFRC), (uint16_t)diepint); -#ifndef ENABLE_DTXFSTS_POLLHACK /* It is possible that logic may be waiting for a the * TxFIFO to become empty. We disable the TxFIFO empty * interrupt here; it will be re-enabled if there is still @@ -2808,7 +2760,6 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) empty &= ~OTGFS_DIEPEMPMSK(epno); stm32_putreg(empty, STM32_OTGFS_DIEPEMPMSK); -#endif stm32_putreg(OTGFS_DIEPINT_XFRC, STM32_OTGFS_DIEPINT(epno)); /* IN transfer complete */ @@ -2860,7 +2811,6 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) #endif /* Transmit FIFO empty */ -#ifndef ENABLE_DTXFSTS_POLLHACK if ((diepint & OTGFS_DIEPINT_TXFE) != 0) { usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_TXFE), (uint16_t)diepint); @@ -2888,7 +2838,6 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv) stm32_putreg(OTGFS_DIEPINT_TXFE, STM32_OTGFS_DIEPINT(epno)); } -#endif } epno++; -- cgit v1.2.3 From 28a0241ccd48963a13638c1dfbef161ab1bf557e Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 31 Jan 2013 19:20:26 +0000 Subject: Missing calls to class SUSPEND/RESUME methods in all USB drivers git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5590 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c | 16 +++++ nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c | 18 +++++- nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c | 51 +++++++++++++--- nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c | 46 ++++++++++++-- nuttx/arch/arm/src/stm32/stm32_otgfsdev.c | 23 +++++-- nuttx/arch/arm/src/stm32/stm32_usbdev.c | 14 +++++ nuttx/arch/avr/src/at90usb/at90usb_usbdev.c | 16 +++++ nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c | 19 +++++- nuttx/drivers/usbdev/cdcacm.c | 90 +++++++++++++++++++++++++++- nuttx/drivers/usbdev/pl2303.c | 84 ++++++++++++++++++++++++++ 10 files changed, 353 insertions(+), 24 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c index b1ddb5928..753f82326 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c @@ -2175,6 +2175,22 @@ static int lpc17_usbinterrupt(int irq, FAR void *context) { usbtrace(TRACE_INTDECODE(LPC17_TRACEINTID_SUSPENDCHG), (uint16_t)g_usbdev.devstatus); + + /* Inform the Class driver of the change */ + + if (priv->driver) + { + if (DEVSTATUS_SUSPEND(g_usbdev.devstatus)) + { + CLASS_SUSPEND(priv->driver, &priv->usbdev); + } + else + { + CLASS_RESUME(priv->driver, &priv->usbdev); + } + } + + /* TODO: Perform power management operations here. */ } /* Device reset */ diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c index 78a5fe1c3..78dc86992 100644 --- a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c +++ b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c @@ -1,7 +1,7 @@ /******************************************************************************* * arch/arm/src/lpc214x/lpc214x_usbdev.c * - * Copyright (C) 2008-2010, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2010, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -2139,6 +2139,22 @@ static int lpc214x_usbinterrupt(int irq, FAR void *context) { usbtrace(TRACE_INTDECODE(LPC214X_TRACEINTID_SUSPENDCHG), (uint16_t)g_usbdev.devstatus); + + /* Inform the Class driver of the change */ + + if (priv->driver) + { + if (DEVSTATUS_SUSPEND(g_usbdev.devstatus)) + { + CLASS_SUSPEND(priv->driver, &priv->usbdev); + } + else + { + CLASS_RESUME(priv->driver, &priv->usbdev); + } + } + + /* TODO: Perform power management operations here. */ } /* Device reset */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c index 386abb5b8..ddeb1bf6b 100644 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c @@ -6,7 +6,7 @@ * * Part of the NuttX OS and based, in part, on the LPC2148 USB driver: * - * Copyright (C) 2010-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2010-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -160,8 +160,9 @@ #define LPC31_TRACEINTID_IFGETSTATUS 0x0015 #define LPC31_TRACEINTID_SETCONFIG 0x0016 #define LPC31_TRACEINTID_SETFEATURE 0x0017 -#define LPC31_TRACEINTID_SUSPENDCHG 0x0018 -#define LPC31_TRACEINTID_SYNCHFRAME 0x0019 +#define LPC31_TRACEINTID_SUSPENDED 0x0018 +#define LPC31_TRACEINTID_RESUMED 0x0019 +#define LPC31_TRACEINTID_SYNCHFRAME 0x001a /* Hardware interface **********************************************************/ @@ -309,6 +310,7 @@ struct lpc31_usbdev_s uint8_t selfpowered:1; /* 1: Device is self powered */ uint8_t paddrset:1; /* 1: Peripheral addr has been set */ uint8_t attached:1; /* 1: Host attached */ + uint8_t suspended:1; /* 1: Suspended */ uint32_t softprio; /* Bitset of high priority interrupts */ uint32_t epavail; /* Bitset of available endpoints */ #ifdef CONFIG_LPC31_USBDEV_FRAME_INTERRUPT @@ -1065,7 +1067,9 @@ static void lpc31_usbreset(struct lpc31_usbdev_s *priv) * driver should then accept any new configurations. */ if (priv->driver) + { CLASS_DISCONNECT(priv->driver, &priv->usbdev); + } /* Set the interrupt Threshold control interval to 0 */ lpc31_chgbits(USBDEV_USBCMD_ITC_MASK, USBDEV_USBCMD_ITCIMME, LPC31_USBDEV_USBCMD); @@ -1649,6 +1653,7 @@ static int lpc31_usbinterrupt(int irq, FAR void *context) usbtrace(TRACE_INTENTRY(LPC31_TRACEINTID_USB), 0); /* Read the interrupts and then clear them */ + disr = lpc31_getreg(LPC31_USBDEV_USBSTS); lpc31_putreg(disr, LPC31_USBDEV_USBSTS); @@ -1661,11 +1666,43 @@ static int lpc31_usbinterrupt(int irq, FAR void *context) usbtrace(TRACE_INTEXIT(LPC31_TRACEINTID_USB), 0); return OK; } - - if (disr & USBDEV_USBSTS_SLI) + + /* When the device controller enters a suspend state from an active state, + * the SLI bit will be set to a one. + */ + + if (!priv->suspended && (disr & USBDEV_USBSTS_SLI) != 0) { - // FIXME: what do we need to do here... - usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_SUSPENDCHG),0); + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_SUSPENDED),0); + + /* Inform the Class driver of the suspend event */ + + priv->suspended = 1; + if (priv->driver) + { + CLASS_SUSPEND(priv->driver, &priv->usbdev); + } + + /* TODO: Perform power management operations here. */ + } + + /* The device controller clears the SLI bit upon exiting from a suspend + * state. This bit can also be cleared by software writing a one to it. + */ + + else if (priv->suspended && (disr & USBDEV_USBSTS_SLI) == 0) + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_RESUMED),0); + + /* Inform the Class driver of the resume event */ + + priv->suspended = 0; + if (priv->driver) + { + CLASS_RESUME(priv->driver, &priv->usbdev); + } + + /* TODO: Perform power management operations here. */ } if (disr & USBDEV_USBSTS_PCI) diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c b/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c index a40d6492d..d0af116d6 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c @@ -1,7 +1,7 @@ /******************************************************************************* * arch/arm/src/lpc43xx/lpc43_usbdev.c * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Part of the NuttX OS and based, in part, on the LPC31xx USB driver: @@ -163,8 +163,9 @@ #define LPC43_TRACEINTID_IFGETSTATUS 0x0015 #define LPC43_TRACEINTID_SETCONFIG 0x0016 #define LPC43_TRACEINTID_SETFEATURE 0x0017 -#define LPC43_TRACEINTID_SUSPENDCHG 0x0018 -#define LPC43_TRACEINTID_SYNCHFRAME 0x0019 +#define LPC43_TRACEINTID_SUSPENDED 0x0018 +#define LPC43_TRACEINTID_RESUMED 0x0019 +#define LPC43_TRACEINTID_SYNCHFRAME 0x001a /* Hardware interface **********************************************************/ @@ -312,6 +313,7 @@ struct lpc43_usbdev_s uint8_t selfpowered:1; /* 1: Device is self powered */ uint8_t paddrset:1; /* 1: Peripheral addr has been set */ uint8_t attached:1; /* 1: Host attached */ + uint8_t suspended:1; /* 1: Suspended */ uint32_t softprio; /* Bitset of high priority interrupts */ uint32_t epavail; /* Bitset of available endpoints */ #ifdef CONFIG_LPC43_USBDEV_FRAME_INTERRUPT @@ -1665,10 +1667,42 @@ static int lpc43_usbinterrupt(int irq, FAR void *context) return OK; } - if (disr & USBDEV_USBSTS_SLI) + /* When the device controller enters a suspend state from an active state, + * the SLI bit will be set to a one. + */ + + if (!priv->suspended && (disr & USBDEV_USBSTS_SLI) != 0) + { + usbtrace(TRACE_INTDECODE(LPC43_TRACEINTID_SUSPENDED),0); + + /* Inform the Class driver of the suspend event */ + + priv->suspended = 1; + if (priv->driver) + { + CLASS_SUSPEND(priv->driver, &priv->usbdev); + } + + /* TODO: Perform power management operations here. */ + } + + /* The device controller clears the SLI bit upon exiting from a suspend + * state. This bit can also be cleared by software writing a one to it. + */ + + else if (priv->suspended && (disr & USBDEV_USBSTS_SLI) == 0) { - // FIXME: what do we need to do here... - usbtrace(TRACE_INTDECODE(LPC43_TRACEINTID_SUSPENDCHG),0); + usbtrace(TRACE_INTDECODE(LPC43_TRACEINTID_RESUMED),0); + + /* Inform the Class driver of the resume event */ + + priv->suspended = 0; + if (priv->driver) + { + CLASS_RESUME(priv->driver, &priv->usbdev); + } + + /* TODO: Perform power management operations here. */ } if (disr & USBDEV_USBSTS_PCI) diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c index a2de6d138..bcce3ce60 100644 --- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c @@ -424,7 +424,6 @@ struct stm32_usbdev_s uint8_t stalled:1; /* 1: Protocol stalled */ uint8_t selfpowered:1; /* 1: Device is self powered */ - uint8_t connected:1; /* 1: Host connected */ uint8_t addressed:1; /* 1: Peripheral address has been set */ uint8_t configured:1; /* 1: Class driver has been configured */ uint8_t wakeup:1; /* 1: Device remote wake-up */ @@ -1074,8 +1073,6 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv, struct stm32_req_s *privreq; uint32_t regaddr; uint32_t regval; - int32_t timeout; - int avail; uint8_t *buf; int nbytes; int nwords; @@ -2874,6 +2871,13 @@ static inline void stm32_resumeinterrupt(FAR struct stm32_usbdev_s *priv) /* Restore full power -- whatever that means for this particular board */ stm32_usbsuspend((struct usbdev_s *)priv, true); + + /* Notify the class driver of the resume event */ + + if (priv->driver) + { + CLASS_RESUME(priv->driver, &priv->usbdev); + } } /******************************************************************************* @@ -2888,7 +2892,16 @@ static inline void stm32_suspendinterrupt(FAR struct stm32_usbdev_s *priv) { #ifdef CONFIG_USBDEV_LOWPOWER uint32_t regval; +#endif + /* Notify the class driver of the suspend event */ + + if (priv->driver) + { + CLASS_SUSPEND(priv->driver, &priv->usbdev); + } + +#ifdef CONFIG_USBDEV_LOWPOWER /* OTGFS_DSTS_SUSPSTS is set as long as the suspend condition is detected * on USB. Check if we are still have the suspend condition, that we are * connected to the host, and that we have been configured. @@ -2896,9 +2909,7 @@ static inline void stm32_suspendinterrupt(FAR struct stm32_usbdev_s *priv) regval = stm32_getreg(STM32_OTGFS_DSTS); - if ((regval & OTGFS_DSTS_SUSPSTS) != 0 && - priv->connected && - devstate == DEVSTATE_CONFIGURED) + if ((regval & OTGFS_DSTS_SUSPSTS) != 0 && devstate == DEVSTATE_CONFIGURED) { /* Switch off OTG FS clocking. Setting OTGFS_PCGCCTL_STPPCLK stops the * PHY clock. diff --git a/nuttx/arch/arm/src/stm32/stm32_usbdev.c b/nuttx/arch/arm/src/stm32/stm32_usbdev.c index 602de3824..d13ac8f96 100644 --- a/nuttx/arch/arm/src/stm32/stm32_usbdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_usbdev.c @@ -2346,6 +2346,13 @@ static void stm32_suspend(struct stm32_usbdev_s *priv) { uint16_t regval; + /* Notify the class driver of the suspend event */ + + if (priv->driver) + { + CLASS_SUSPEND(priv->driver, &priv->usbdev); + } + /* Disable ESOF polling, disable the SUSP interrupt, and enable the WKUP * interrupt. Clear any pending WKUP interrupt. */ @@ -2411,6 +2418,13 @@ static void stm32_initresume(struct stm32_usbdev_s *priv) /* Reset FSUSP bit and enable normal interrupt handling */ stm32_putreg(STM32_CNTR_SETUP, STM32_USB_CNTR); + + /* Notify the class driver of the resume event */ + + if (priv->driver) + { + CLASS_RESUME(priv->driver, &priv->usbdev); + } } /**************************************************************************** diff --git a/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c b/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c index 89949e662..0e3ac6487 100644 --- a/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c +++ b/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c @@ -1955,6 +1955,15 @@ static inline void avr_gensuspend(void) { usbtrace(TRACE_INTENTRY(AVR_TRACEINTID_SUSPEND), UDIEN); + /* Notify the class driver of the suspend event */ + + if (g_usbdev.driver) + { + CLASS_SUSPEND(g_usbdev.driver, &g_usbdev.usbdev); + } + + /* Disable suspend event interrupts; enable wakeup event interrupt */ + UDIEN &= ~(1 << SUSPE); UDIEN |= (1 << WAKEUPE); @@ -1992,6 +2001,13 @@ static void avr_genwakeup(void) USBCON &= ~(1 << FRZCLK); UDIEN &= ~(1 << WAKEUPE); UDIEN |= (1 << SUSPE); + + /* Notify the class driver of the resume event */ + + if (g_usbdev.driver) + { + CLASS_RESUME(g_usbdev.driver, &g_usbdev.usbdev); + } } /******************************************************************************* diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c b/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c index dafd35aa0..8d9f7c058 100644 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c @@ -2901,6 +2901,13 @@ static void pic32mx_suspend(struct pic32mx_usbdev_s *priv) { uint16_t regval; + /* Notify the class driver of the suspend event */ + + if (priv->driver) + { + CLASS_SUSPEND(priv->driver, &priv->usbdev); + } + /* Enable the ACTV interrupt. * * NOTE: Do not clear UIRbits.ACTVIF here! Reason: ACTVIF is only @@ -2977,8 +2984,16 @@ static void pic32mx_resume(struct pic32mx_usbdev_s *priv) * PLL to lock. */ - pic32mx_putreg(USB_INT_IDLE, PIC32MX_USBOTG_IR); - irqrestore(flags); + pic32mx_putreg(USB_INT_IDLE, PIC32MX_USBOTG_IR); + + /* Notify the class driver of the resume event */ + + if (priv->driver) + { + CLASS_RESUME(priv->driver, &priv->usbdev); + } + + irqrestore(flags); } /**************************************************************************** diff --git a/nuttx/drivers/usbdev/cdcacm.c b/nuttx/drivers/usbdev/cdcacm.c index 9b6fae1d6..cb8679976 100644 --- a/nuttx/drivers/usbdev/cdcacm.c +++ b/nuttx/drivers/usbdev/cdcacm.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/usbdev/cdcacm.c * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -188,6 +188,12 @@ static int cdcacm_setup(FAR struct usbdevclass_driver_s *driver, size_t outlen); static void cdcacm_disconnect(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev); +#ifdef CONFIG_SERIAL_REMOVABLE +static void cdcacm_suspend(FAR struct usbdevclass_driver_s *driver, + FAR struct usbdev_s *dev); +static void cdcacm_resume(FAR struct usbdevclass_driver_s *driver, + FAR struct usbdev_s *dev); +#endif /* UART Operations **********************************************************/ @@ -211,8 +217,13 @@ static const struct usbdevclass_driverops_s g_driverops = cdcacm_unbind, /* unbind */ cdcacm_setup, /* setup */ cdcacm_disconnect, /* disconnect */ +#ifdef CONFIG_SERIAL_REMOVABLE + cdcacm_suspend, /* suspend */ + cdcacm_resume, /* resume */ +#else NULL, /* suspend */ NULL, /* resume */ +#endif }; /* Serial port **************************************************************/ @@ -841,6 +852,7 @@ static void cdcacm_rdcomplete(FAR struct usbdev_ep_s *ep, { usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_RDSUBMIT), (uint16_t)-req->result); } + irqrestore(flags); } @@ -950,6 +962,7 @@ static int cdcacm_bind(FAR struct usbdevclass_driver_s *driver, ret = -ENOMEM; goto errout; } + priv->ctrlreq->callback = cdcacm_ep0incomplete; /* Pre-allocate all endpoints... the endpoints will not be functional @@ -1621,6 +1634,79 @@ static void cdcacm_disconnect(FAR struct usbdevclass_driver_s *driver, #endif } +/**************************************************************************** + * Name: cdcacm_suspend + * + * Description: + * Handle the USB suspend event. + * + ****************************************************************************/ + +#ifdef CONFIG_SERIAL_REMOVABLE +static void cdcacm_suspend(FAR struct usbdevclass_driver_s *driver, + FAR struct usbdev_s *dev) +{ + FAR struct cdcacm_dev_s *priv; + + usbtrace(TRACE_CLASSSUSPEND, 0); + +#ifdef CONFIG_DEBUG + if (!driver || !dev) + { + usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0); + return; + } +#endif + + /* Extract reference to private data */ + + priv = ((FAR struct cdcacm_driver_s*)driver)->dev; + + /* And let the "upper half" driver now that we are suspended */ + + uart_connected(&priv->serdev, false); +} +#endif + +/**************************************************************************** + * Name: cdcacm_resume + * + * Description: + * Handle the USB resume event. + * + ****************************************************************************/ + +#ifdef CONFIG_SERIAL_REMOVABLE +static void cdcacm_resume(FAR struct usbdevclass_driver_s *driver, + FAR struct usbdev_s *dev) +{ + FAR struct cdcacm_dev_s *priv; + + usbtrace(TRACE_CLASSRESUME, 0); + +#ifdef CONFIG_DEBUG + if (!driver || !dev) + { + usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0); + return; + } +#endif + + /* Extract reference to private data */ + + priv = ((FAR struct cdcacm_driver_s*)driver)->dev; + + /* Are we still configured? */ + + if (priv->config != CDCACM_CONFIGIDNONE) + { + /* Yes.. let the "upper half" know that have resumed */ + + uart_connected(&priv->serdev, true); + } +} +#endif + /**************************************************************************** * Serial Device Methods ****************************************************************************/ @@ -2179,7 +2265,7 @@ int cdcacm_initialize(int minor, FAR void **handle) * * Description: * Un-initialize the USB storage class driver. This function is used - * internally by the USB composite driver to unitialized the CDC/ACM + * internally by the USB composite driver to unitialize the CDC/ACM * driver. This same interface is available (with an untyped input * parameter) when the CDC/ACM driver is used standalone. * diff --git a/nuttx/drivers/usbdev/pl2303.c b/nuttx/drivers/usbdev/pl2303.c index 98163f133..7b07a9cba 100644 --- a/nuttx/drivers/usbdev/pl2303.c +++ b/nuttx/drivers/usbdev/pl2303.c @@ -343,6 +343,12 @@ static int usbclass_setup(FAR struct usbdevclass_driver_s *driver, size_t outlen); static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev); +#ifdef CONFIG_SERIAL_REMOVABLE +static void usbclass_suspend(FAR struct usbdevclass_driver_s *driver, + FAR struct usbdev_s *dev); +static void usbclass_resume(FAR struct usbdevclass_driver_s *driver, + FAR struct usbdev_s *dev); +#endif /* Serial port *************************************************************/ @@ -366,8 +372,13 @@ static const struct usbdevclass_driverops_s g_driverops = usbclass_unbind, /* unbind */ usbclass_setup, /* setup */ usbclass_disconnect, /* disconnect */ +#ifdef CONFIG_SERIAL_REMOVABLE + usbclass_suspend, /* suspend */ + usbclass_resume, /* resume */ +#else NULL, /* suspend */ NULL, /* resume */ +#endif }; /* Serial port *************************************************************/ @@ -1888,6 +1899,79 @@ static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver, DEV_CONNECT(dev); } +/**************************************************************************** + * Name: usbclass_suspend + * + * Description: + * Handle the USB suspend event. + * + ****************************************************************************/ + +#ifdef CONFIG_SERIAL_REMOVABLE +static void usbclass_suspend(FAR struct usbdevclass_driver_s *driver, + FAR struct usbdev_s *dev) +{ + FAR struct cdcacm_dev_s *priv; + + usbtrace(TRACE_CLASSSUSPEND, 0); + +#ifdef CONFIG_DEBUG + if (!driver || !dev) + { + usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0); + return; + } +#endif + + /* Extract reference to private data */ + + priv = ((FAR struct cdcacm_driver_s*)driver)->dev; + + /* And let the "upper half" driver now that we are suspended */ + + uart_connected(&priv->serdev, false); +} +#endif + +/**************************************************************************** + * Name: usbclass_resume + * + * Description: + * Handle the USB resume event. + * + ****************************************************************************/ + +#ifdef CONFIG_SERIAL_REMOVABLE +static void usbclass_resume(FAR struct usbdevclass_driver_s *driver, + FAR struct usbdev_s *dev) +{ + FAR struct cdcacm_dev_s *priv; + + usbtrace(TRACE_CLASSRESUME, 0); + +#ifdef CONFIG_DEBUG + if (!driver || !dev) + { + usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0); + return; + } +#endif + + /* Extract reference to private data */ + + priv = ((FAR struct cdcacm_driver_s*)driver)->dev; + + /* Are we still configured? */ + + if (priv->config != PL2303_CONFIGIDNONE) + { + /* Yes.. let the "upper half" know that have resumed */ + + uart_connected(&priv->serdev, true); + } +} +#endif + /**************************************************************************** * Serial Device Methods ****************************************************************************/ -- cgit v1.2.3 From 966e801032745429ec2f28f9e5ab0b3fc8a68d3d Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 31 Jan 2013 23:29:34 +0000 Subject: Misc clean; mark assertions as non-returning; allow toolchain prefix to be overriden from make command line git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5591 42af7a65-404d-4744-a932-0658087f49c3 --- apps/system/readline/readline.c | 1 - nuttx/ChangeLog | 5 ++++ nuttx/README.txt | 11 ++++++-- nuttx/arch/8051/src/up_assert.c | 3 ++- nuttx/arch/arm/src/arm/Toolchain.defs | 26 +++++++++---------- nuttx/arch/arm/src/arm/up_assert.c | 3 ++- nuttx/arch/arm/src/armv7-m/Toolchain.defs | 42 +++++++++++++++---------------- nuttx/arch/arm/src/armv7-m/up_assert.c | 3 ++- nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c | 2 +- nuttx/arch/avr/src/avr/Toolchain.defs | 10 ++++---- nuttx/arch/avr/src/common/up_assert.c | 3 ++- nuttx/arch/hc/src/m9s12/m9s12_assert.c | 3 ++- nuttx/arch/mips/src/mips32/Toolchain.defs | 24 +++++++++--------- nuttx/arch/mips/src/mips32/up_assert.c | 5 ++-- nuttx/arch/sh/src/common/up_assert.c | 3 ++- nuttx/arch/x86/src/common/up_assert.c | 3 ++- nuttx/drivers/serial/serial.c | 7 +++++- nuttx/include/assert.h | 21 ++++++++++------ 18 files changed, 102 insertions(+), 73 deletions(-) (limited to 'nuttx/arch') diff --git a/apps/system/readline/readline.c b/apps/system/readline/readline.c index 11c53cb50..bac7eee8c 100644 --- a/apps/system/readline/readline.c +++ b/apps/system/readline/readline.c @@ -151,7 +151,6 @@ static inline int readline_rawgetc(int infd) int errcode = errno; if (errcode != EINTR) - { return -errcode; } diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 5c41a0e9c..26b82fde4 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4074,3 +4074,8 @@ removable serial devices (like USB serial). This support is enabled by CONFIG_SERIAL_REMOVABLE and requires VBUS sensing support from the board-specific logic. + * arch/*/src/*/Toolchain.defs: Change assignment so that we can + override CROSSDEV with a make command line argument. + * include/assert.h: Mark assertion functions as non-returning. + * arch/*/src/*/up_assert.h: Mark _up_assert() as non-returning. + diff --git a/nuttx/README.txt b/nuttx/README.txt index 340087791..571f8e04e 100644 --- a/nuttx/README.txt +++ b/nuttx/README.txt @@ -523,8 +523,15 @@ NuttX Buildroot Toolchain Disadvantages: This tool chain is not was well supported as some other toolchains. GNU tools are not my priority and so the buildroot tools - often get behind. For example, the is still no EABI support in the - NuttX buildroot toolchain for ARM. + often get behind. For example, until recently there was no EABI support + in the NuttX buildroot toolchain for ARM. + + NOTE: For Cortex-M3/4, there are OABI and EABI versions of the buildroot + toolchains. If you are using the older OABI toolchain the prefix for + the tools will be arm-nuttx-elf-; for the EABI toolchin the prefix will + be arm-nuttx-eabi-. If you are using the older OABI toolchain with + an ARM Cortex-M3/4, you will need to set CONFIG_ARMV7M_OABI_TOOLCHAIN + in the .config file in order to pick the right tool prefix. SHELLS ^^^^^^ diff --git a/nuttx/arch/8051/src/up_assert.c b/nuttx/arch/8051/src/up_assert.c index 46d731041..5e59d6af0 100644 --- a/nuttx/arch/8051/src/up_assert.c +++ b/nuttx/arch/8051/src/up_assert.c @@ -65,7 +65,8 @@ * Name: _up_assert ************************************************************************/ -static void _up_assert(int errorcode) /* noreturn_function */ +static void _up_assert(int errorcode) noreturn_function; +static void _up_assert(int errorcode) { /* Are we in an interrupt handler or the idle task? */ diff --git a/nuttx/arch/arm/src/arm/Toolchain.defs b/nuttx/arch/arm/src/arm/Toolchain.defs index daa825842..cd16d7ec9 100644 --- a/nuttx/arch/arm/src/arm/Toolchain.defs +++ b/nuttx/arch/arm/src/arm/Toolchain.defs @@ -1,7 +1,7 @@ ############################################################################ # arch/arm/src/armv/Toolchain.defs # -# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2012-2013 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -103,11 +103,11 @@ endif ifeq ($(CONFIG_ARM_TOOLCHAIN),BUILDROOT) ifeq ($(CONFIG_ARM_OABI_TOOLCHAIN),y) - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- + CROSSDEV ?= arm-nuttx-elf- + ARCROSSDEV ?= arm-nuttx-elf- else - CROSSDEV = arm-nuttx-eabi- - ARCROSSDEV = arm-nuttx-eabi- + CROSSDEV ?= arm-nuttx-eabi- + ARCROSSDEV ?= arm-nuttx-eabi- endif MAXOPTIMIZATION = -Os endif @@ -115,16 +115,16 @@ endif # CodeSourcery under Linux ifeq ($(CONFIG_ARM_TOOLCHAIN),CODESOURCERYL) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- MAXOPTIMIZATION = -O2 endif # CodeSourcery under Windows ifeq ($(CONFIG_ARM_TOOLCHAIN),CODESOURCERYW) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- MAXOPTIMIZATION = -O2 ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y @@ -134,8 +134,8 @@ endif # devkitARM under Windows ifeq ($(CONFIG_ARM_TOOLCHAIN),DEVKITARM) - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- + CROSSDEV ?= arm-eabi- + ARCROSSDEV ?= arm-eabi- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif @@ -144,8 +144,8 @@ endif # Generic GNU EABI toolchain on OS X, Linux or any typical Posix system ifeq ($(CONFIG_ARM_TOOLCHAIN),GNU_EABI) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- MAXOPTIMIZATION = -O3 endif diff --git a/nuttx/arch/arm/src/arm/up_assert.c b/nuttx/arch/arm/src/arm/up_assert.c index 3cc79df01..5f713c34d 100644 --- a/nuttx/arch/arm/src/arm/up_assert.c +++ b/nuttx/arch/arm/src/arm/up_assert.c @@ -252,7 +252,8 @@ static void up_dumpstate(void) * Name: _up_assert ****************************************************************************/ -static void _up_assert(int errorcode) /* noreturn_function */ +static void _up_assert(int errorcode) noreturn_function; +static void _up_assert(int errorcode) { /* Are we in an interrupt handler or the idle task? */ diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs index 45ee9e36c..4de5b49f4 100644 --- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs +++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs @@ -1,7 +1,7 @@ ############################################################################ # arch/arm/src/armv7-m/Toolchain.defs # -# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2012-2013 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -141,8 +141,8 @@ endif # Atollic toolchain under Windows ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),ATOLLIC) - CROSSDEV = arm-atollic-eabi- - ARCROSSDEV = arm-atollic-eabi- + CROSSDEV ?= arm-atollic-eabi- + ARCROSSDEV ?= arm-atollic-eabi- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif @@ -161,12 +161,12 @@ endif ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),BUILDROOT) ifeq ($(CONFIG_ARMV7M_OABI_TOOLCHAIN),y) - CROSSDEV = arm-nuttx-elf- - ARCROSSDEV = arm-nuttx-elf- + CROSSDEV ?= arm-nuttx-elf- + ARCROSSDEV ?= arm-nuttx-elf- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft else - CROSSDEV = arm-nuttx-eabi- - ARCROSSDEV = arm-nuttx-eabi- + CROSSDEV ?= arm-nuttx-eabi- + ARCROSSDEV ?= arm-nuttx-eabi- ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft endif MAXOPTIMIZATION = -Os @@ -175,8 +175,8 @@ endif # Code Red RedSuite under Linux ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDL) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- ifeq ($(CONFIG_ARCH_CORTEXM4),y) ifeq ($(CONFIG_ARCH_FPU),y) ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard @@ -191,8 +191,8 @@ endif # Code Red RedSuite under Windows ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDW) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif @@ -210,8 +210,8 @@ endif # CodeSourcery under Linux ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYL) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft MAXOPTIMIZATION = -O2 endif @@ -219,8 +219,8 @@ endif # CodeSourcery under Windows ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYW) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif @@ -230,8 +230,8 @@ endif # devkitARM under Windows ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM) - CROSSDEV = arm-eabi- - ARCROSSDEV = arm-eabi- + CROSSDEV ?= arm-eabi- + ARCROSSDEV ?= arm-eabi- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif @@ -241,8 +241,8 @@ endif # Generic GNU EABI toolchain on OS X, Linux or any typical Posix system ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),GNU_EABI) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- MAXOPTIMIZATION = -O3 ifeq ($(CONFIG_ARCH_CORTEXM4),y) ifeq ($(CONFIG_ARCH_FPU),y) @@ -258,8 +258,8 @@ endif # Raisonance RIDE7 under Windows ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),RAISONANCE) - CROSSDEV = arm-none-eabi- - ARCROSSDEV = arm-none-eabi- + CROSSDEV ?= arm-none-eabi- + ARCROSSDEV ?= arm-none-eabi- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif diff --git a/nuttx/arch/arm/src/armv7-m/up_assert.c b/nuttx/arch/arm/src/armv7-m/up_assert.c index 8e29bfe80..b40b1090c 100644 --- a/nuttx/arch/arm/src/armv7-m/up_assert.c +++ b/nuttx/arch/arm/src/armv7-m/up_assert.c @@ -267,7 +267,8 @@ static void up_dumpstate(void) * Name: _up_assert ****************************************************************************/ -static void _up_assert(int errorcode) /* noreturn_function */ +static void _up_assert(int errorcode) noreturn_function; +static void _up_assert(int errorcode) { /* Are we in an interrupt handler or the idle task? */ diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c index e3085ff78..84c4e7951 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c @@ -452,7 +452,7 @@ static inline int lpc17_configinput(lpc17_pinset_t cfgset, unsigned int port, un #endif } -#ifdef defined(LPC176x) +#if defined(LPC176x) /* Set up PINSEL registers */ /* Configure as GPIO */ diff --git a/nuttx/arch/avr/src/avr/Toolchain.defs b/nuttx/arch/avr/src/avr/Toolchain.defs index 96eb273f6..09035a30f 100644 --- a/nuttx/arch/avr/src/avr/Toolchain.defs +++ b/nuttx/arch/avr/src/avr/Toolchain.defs @@ -1,7 +1,7 @@ ############################################################################ # arch/avr/src/avr/Toolchain.defs # -# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2012-2013 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -82,7 +82,7 @@ endif # NuttX buildroot GCC toolchain under Linux or Cygwin ifeq ($(CONFIG_AVR_TOOLCHAIN),BUILDROOT) - CROSSDEV = avr-nuttx-elf- + CROSSDEV ?= avr-nuttx-elf- MAXOPTIMIZATION = -O2 LDFLAGS += -nostartfiles -nodefaultlibs endif @@ -90,7 +90,7 @@ endif # AVR CrossPack under OS X ifeq ($(CONFIG_AVR_TOOLCHAIN),CROSSPACK) - CROSSDEV = avr- + CROSSDEV ?= avr- MAXOPTIMIZATION = -O2 LDFLAGS += -nostartfiles -nodefaultlibs endif @@ -98,7 +98,7 @@ endif # GCC toolchain under Linux ifeq ($(CONFIG_AVR_TOOLCHAIN),LINUXGCC) - CROSSDEV = avr- + CROSSDEV ?= avr- MAXOPTIMIZATION = -O2 LDFLAGS += -nostartfiles -nodefaultlibs endif @@ -106,7 +106,7 @@ endif # WinAVR toolchain under Windows/Cygwin ifeq ($(CONFIG_AVR_TOOLCHAIN),WINAVR) - CROSSDEV = avr- + CROSSDEV ?= avr- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif diff --git a/nuttx/arch/avr/src/common/up_assert.c b/nuttx/arch/avr/src/common/up_assert.c index 3e90094eb..be7f635e8 100644 --- a/nuttx/arch/avr/src/common/up_assert.c +++ b/nuttx/arch/avr/src/common/up_assert.c @@ -90,7 +90,8 @@ * Name: _up_assert ****************************************************************************/ -static void _up_assert(int errorcode) /* noreturn_function */ +static void _up_assert(int errorcode) noreturn_function; +static void _up_assert(int errorcode) { /* Are we in an interrupt handler or the idle task? */ diff --git a/nuttx/arch/hc/src/m9s12/m9s12_assert.c b/nuttx/arch/hc/src/m9s12/m9s12_assert.c index 65cc75590..37ad5e30d 100644 --- a/nuttx/arch/hc/src/m9s12/m9s12_assert.c +++ b/nuttx/arch/hc/src/m9s12/m9s12_assert.c @@ -247,7 +247,8 @@ static void up_dumpstate(void) * Name: _up_assert ****************************************************************************/ -static void _up_assert(int errorcode) /* noreturn_function */ +static void _up_assert(int errorcode) noreturn_function; +static void _up_assert(int errorcode) { /* Are we in an interrupt handler or the idle task? */ diff --git a/nuttx/arch/mips/src/mips32/Toolchain.defs b/nuttx/arch/mips/src/mips32/Toolchain.defs index bd509b86c..09c68db12 100644 --- a/nuttx/arch/mips/src/mips32/Toolchain.defs +++ b/nuttx/arch/mips/src/mips32/Toolchain.defs @@ -1,7 +1,7 @@ ############################################################################ # arch/mips/src/mips32/Toolchain.defs # -# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2012-2013 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -103,7 +103,7 @@ endif # including Pinguino mips-elf toolchain ifeq ($(CONFIG_MIPS32_TOOLCHAIN),GNU_ELF) - CROSSDEV = mips-elf- + CROSSDEV ?= mips-elf- MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL ARCHPICFLAGS = -fpic -membedded-pic @@ -114,8 +114,8 @@ endif # Microchip C32 toolchain under Linux ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPL) - CROSSDEV = pic32- - # CROSSDEV = xc32- + CROSSDEV ?= pic32- + # CROSSDEV ?= xc32- MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data ARCHPICFLAGS = -fpic -membedded-pic @@ -126,8 +126,8 @@ endif # Microchip C32 toolchain under Windows ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPW) - CROSSDEV = pic32- - # CROSSDEV = xc32- + CROSSDEV ?= pic32- + # CROSSDEV ?= xc32- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif @@ -141,8 +141,8 @@ endif # Microchip C32 toolchain under Linux ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPL_LITE) - CROSSDEV = pic32- - # CROSSDEV = xc32- + CROSSDEV ?= pic32- + # CROSSDEV ?= xc32- # MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data ARCHPICFLAGS = -fpic -membedded-pic @@ -153,8 +153,8 @@ endif # Microchip C32 toolchain under Windows ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPW_LITE) - CROSSDEV = pic32- - # CROSSDEV = xc32- + CROSSDEV ?= pic32- + # CROSSDEV ?= xc32- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif @@ -168,7 +168,7 @@ endif # microchipOpen toolchain under Linux ifeq ($(CONFIG_MIPS32_TOOLCHAIN),MICROCHIPOPENL) - CROSSDEV = mypic32- + CROSSDEV ?= mypic32- # MAXOPTIMIZATION = -O2 ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data ARCHPICFLAGS = -fpic -membedded-pic @@ -179,7 +179,7 @@ endif # Pinguino mips-elf toolchain under Windows ifeq ($(CONFIG_MIPS32_TOOLCHAIN),PINGUINOW) - CROSSDEV = mips- + CROSSDEV ?= mips- ifneq ($(CONFIG_WINDOWS_NATIVE),y) WINTOOL = y endif diff --git a/nuttx/arch/mips/src/mips32/up_assert.c b/nuttx/arch/mips/src/mips32/up_assert.c index 7d98e7427..f27bc0ebe 100644 --- a/nuttx/arch/mips/src/mips32/up_assert.c +++ b/nuttx/arch/mips/src/mips32/up_assert.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/mips/src/mips32/up_assert.c * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -90,7 +90,8 @@ * Name: _up_assert ****************************************************************************/ -static void _up_assert(int errorcode) /* noreturn_function */ +static void _up_assert(int errorcode) noreturn_function; +static void _up_assert(int errorcode) { /* Are we in an interrupt handler or the idle task? */ diff --git a/nuttx/arch/sh/src/common/up_assert.c b/nuttx/arch/sh/src/common/up_assert.c index 5b56e7731..62889fa5a 100644 --- a/nuttx/arch/sh/src/common/up_assert.c +++ b/nuttx/arch/sh/src/common/up_assert.c @@ -76,7 +76,8 @@ * Name: _up_assert ****************************************************************************/ -static void _up_assert(int errorcode) /* noreturn_function */ +static void _up_assert(int errorcode) noreturn_function; +static void _up_assert(int errorcode) { /* Are we in an interrupt handler or the idle task? */ diff --git a/nuttx/arch/x86/src/common/up_assert.c b/nuttx/arch/x86/src/common/up_assert.c index 87958baa6..653e8e562 100644 --- a/nuttx/arch/x86/src/common/up_assert.c +++ b/nuttx/arch/x86/src/common/up_assert.c @@ -209,7 +209,8 @@ static void up_dumpstate(void) * Name: _up_assert ****************************************************************************/ -static void _up_assert(int errorcode) /* noreturn_function */ +static void _up_assert(int errorcode) noreturn_function; +static void _up_assert(int errorcode) { /* Are we in an interrupt handler or the idle task? */ diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c index 0548d8c25..9c6acf2ee 100644 --- a/nuttx/drivers/serial/serial.c +++ b/nuttx/drivers/serial/serial.c @@ -1041,8 +1041,11 @@ void uart_datasent(FAR uart_dev_t *dev) #ifdef CONFIG_SERIAL_REMOVABLE void uart_connected(FAR uart_dev_t *dev, bool connected) { + irqstate_t flags; + /* Is the device disconnected? */ + flags = irqsave(); dev->disconnected = !connected; if (!connected) { @@ -1070,10 +1073,12 @@ void uart_connected(FAR uart_dev_t *dev, bool connected) (void)sem_post(&dev->recvsem); } - /* Notify all poll/select waiters that and hangup/error occurred */ + /* Notify all poll/select waiters that and hangup occurred */ uart_pollnotify(dev, (POLLERR|POLLHUP)); } + + irqrestore(flags); } #endif diff --git a/nuttx/include/assert.h b/nuttx/include/assert.h index 31c9edf48..62ffb3a6e 100644 --- a/nuttx/include/assert.h +++ b/nuttx/include/assert.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/assert.h * - * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -100,23 +100,28 @@ ****************************************************************************/ /**************************************************************************** - * Global Function Prototypes + * Public Data ****************************************************************************/ #ifdef __cplusplus #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + #ifdef CONFIG_HAVE_FILENAME -EXTERN void up_assert(FAR const uint8_t *filename, int linenum); -EXTERN void up_assert_code(FAR const uint8_t *filename, int linenum, - int errcode); +void up_assert(FAR const uint8_t *filename, int linenum) noreturn_function; +void up_assert_code(FAR const uint8_t *filename, int linenum, int errcode) + noreturn_function; #else -EXTERN void up_assert(void); -EXTERN void up_assert_code(int errcode); +void up_assert(void) noreturn_function; +void up_assert_code(int errcode) noreturn_function; #endif #undef EXTERN -- cgit v1.2.3 From a6d4497461d9a129572ab0d4327dd88c1f99986a Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 1 Feb 2013 15:32:39 +0000 Subject: Additional patches from Petteri Aimonen for FAT, STM32 SPI, and AT25 git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5593 42af7a65-404d-4744-a932-0658087f49c3 --- NxWidgets/ChangeLog.txt | 3 ++ nuttx/ChangeLog | 19 +++++++++++- nuttx/arch/arm/src/stm32/chip/stm32_spi.h | 8 ++++- nuttx/arch/arm/src/stm32/stm32_spi.c | 51 +++++++++++++++++++++++++------ nuttx/drivers/mmcsd/mmcsd_spi.c | 10 ++++-- nuttx/drivers/mtd/at25.c | 16 +++++----- nuttx/fs/fat/fs_configfat.c | 14 ++++----- nuttx/fs/fat/fs_fat32.c | 3 ++ nuttx/fs/fat/fs_fat32util.c | 4 +-- 9 files changed, 97 insertions(+), 31 deletions(-) (limited to 'nuttx/arch') diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt index be55a2e78..88e15d7db 100644 --- a/NxWidgets/ChangeLog.txt +++ b/NxWidgets/ChangeLog.txt @@ -263,3 +263,6 @@ for other widgets. Subclasses will override drawContents and decide themselves how to draw the background. * CNxWidgets::CTabPanel: A new widget contributed by Petteri Aimonen. + This widget provides a tab panel, which has a button bar at the top + and panels below it. Pressing a button will select the corresponding + panel. diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 26b82fde4..db62b9cf4 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4078,4 +4078,21 @@ override CROSSDEV with a make command line argument. * include/assert.h: Mark assertion functions as non-returning. * arch/*/src/*/up_assert.h: Mark _up_assert() as non-returning. - + * drivers/mtd/at25.c: When the AT25 device was not available the + initialization did not fail like it should. From Petteri Aimonen. + * fs/fat/fs_configfat.c: Fix some errors in FAT formatting logic + for large devices and for FAT32. From Petteri Aimonen. + * fs/fat/fs_fat32util.c: Fix an initialization error found by + Petteri Aimonen. freecount and next freecount initialization were + reversed. + * drivers/mmcsd/mmcsd_spi.c: Some SD cards will appear busy until + switched to SPI mode for first time. Having a pull-up resistor on + MISO may avoid this problem, but this patch makes it work also + without pull-up. From Petteri Aimonen. + * fs/fat/fs_fat32.c: Fix a compilation error when FAT_DMAMEMORY=y. + From Petteri Aimonen. + * arch/arm/src/stm32/chip/stm32_spi.h: STM32F4 max SPI clock freq is + 37.5 MHz. Patch from Petteri Aimonen. + * arch/arm/src/stm32/stm32_spi.c: Fixes for SPI DMA work on the + STM32F4. Includes untested additions for the F1 implementation as + well. From Petteri Aimonen. diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_spi.h b/nuttx/arch/arm/src/stm32/chip/stm32_spi.h index d80c447bb..7731d03b0 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32_spi.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32_spi.h @@ -47,7 +47,13 @@ * Pre-processor Definitions ************************************************************************************/ -#define STM32_SPI_CLK_MAX 18000000UL /* Maximum allowed speed as per specifications for all SPIs */ +/* Maximum allowed speed as per specifications for all SPIs */ + +#if defined(CONFIG_STM32_STM32F40XX) +# define STM32_SPI_CLK_MAX 37500000UL +#else +# define STM32_SPI_CLK_MAX 18000000UL +#endif /* Register Offsets *****************************************************************/ diff --git a/nuttx/arch/arm/src/stm32/stm32_spi.c b/nuttx/arch/arm/src/stm32/stm32_spi.c index 8de698cd5..b4a4f36ab 100644 --- a/nuttx/arch/arm/src/stm32/stm32_spi.c +++ b/nuttx/arch/arm/src/stm32/stm32_spi.c @@ -130,14 +130,28 @@ /* DMA channel configuration */ -#define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC ) -#define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC ) -#define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS ) -#define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS ) -#define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR) -#define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR) -#define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR) -#define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR) +#if defined(CONFIG_STM32_STM32F10XX) +# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC ) +# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC ) +# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS ) +# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS ) +# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR) +# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR) +# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR) +# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR) +#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) +# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_P2M) +# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_P2M) +# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_P2M) +# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_P2M) +# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_M2P) +# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_M2P) +# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_M2P) +# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_M2P) +#else +# error "Unknown STM32 DMA" +#endif + /* Debug ****************************************************************************/ /* Check if (non-standard) SPI debug is enabled */ @@ -549,6 +563,21 @@ static inline void spi_dmarxwakeup(FAR struct stm32_spidev_s *priv) } #endif +/************************************************************************************ + * Name: spi_dmatxwakeup + * + * Description: + * Signal that DMA is complete + * + ************************************************************************************/ + +#ifdef CONFIG_STM32_SPI_DMA +static inline void spi_dmatxwakeup(FAR struct stm32_spidev_s *priv) +{ + (void)sem_post(&priv->txsem); +} +#endif + /************************************************************************************ * Name: spi_dmarxcallback * @@ -1183,8 +1212,8 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, FAR void *rxbuffer, size_t nwords) { FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev; - uint16_t rxdummy = 0xffff; - uint16_t txdummy; + static uint16_t rxdummy = 0xffff; + static const uint16_t txdummy = 0xffff; spivdbg("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords); DEBUGASSERT(priv && priv->spibase); @@ -1330,6 +1359,8 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv) priv->rxdma = stm32_dmachannel(priv->rxch); priv->txdma = stm32_dmachannel(priv->txch); DEBUGASSERT(priv->rxdma && priv->txdma); + + spi_putreg(priv, STM32_SPI_CR2_OFFSET, SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN); #endif /* Enable spi */ diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c index d437b7fea..3d4cf1dd1 100644 --- a/nuttx/drivers/mmcsd/mmcsd_spi.c +++ b/nuttx/drivers/mmcsd/mmcsd_spi.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/mmcsd/mmcsd_spi.c * - * Copyright (C) 2008-2010, 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2010, 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -409,10 +409,14 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot, int ret; int i; - /* Wait until the card is not busy */ + /* Wait until the card is not busy. Some SD cards will not enter the IDLE + * state until CMD0 is sent for the first time, switching the card to SPI + * mode. Having a pull-up resistor on MISO may avoid this problem, but + * this check makes it work also without the pull-up. + */ ret = mmcsd_waitready(slot); - if (ret != OK) + if (ret != OK && cmd != &g_cmd0) { return ret; } diff --git a/nuttx/drivers/mtd/at25.c b/nuttx/drivers/mtd/at25.c index e35b794a5..c58b16122 100644 --- a/nuttx/drivers/mtd/at25.c +++ b/nuttx/drivers/mtd/at25.c @@ -691,14 +691,16 @@ FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev) kfree(priv); priv = NULL; } - - /* Unprotect all sectors */ + else + { + /* Unprotect all sectors */ - at25_writeenable(priv); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); - (void)SPI_SEND(priv->dev, AT25_WRSR); - (void)SPI_SEND(priv->dev, AT25_SR_UNPROT); - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + at25_writeenable(priv); + SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + (void)SPI_SEND(priv->dev, AT25_WRSR); + (void)SPI_SEND(priv->dev, AT25_SR_UNPROT); + SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + } } /* Return the implementation-specific state structure as the MTD device */ diff --git a/nuttx/fs/fat/fs_configfat.c b/nuttx/fs/fat/fs_configfat.c index 2075caa9f..04141ee2b 100644 --- a/nuttx/fs/fat/fs_configfat.c +++ b/nuttx/fs/fat/fs_configfat.c @@ -406,7 +406,7 @@ mkfatfs_clustersearchlimits(FAR struct fat_format_s *fmt, FAR struct fat_var_s * } /**************************************************************************** - * Name: mkfatfs_try12 + * Name: mkfatfs_tryfat12 * * Description: * Try to define a FAT12 filesystem on the device using the candidate @@ -462,7 +462,7 @@ mkfatfs_tryfat12(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, * FAT12 (remembering that two FAT cluster slots are reserved). */ - if (config->fc_nclusters > maxnclusters - 2) + if (config->fc_nclusters + 2 > maxnclusters) { fvdbg("Too many clusters for FAT12\n"); return -ENFILE; @@ -472,7 +472,7 @@ mkfatfs_tryfat12(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, } /**************************************************************************** - * Name: mkfatfs_try16 + * Name: mkfatfs_tryfat16 * * Description: * Try to define a FAT16 filesystem on the device using the candidate @@ -532,7 +532,7 @@ mkfatfs_tryfat16(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, * be confused as a FAT12 at mount time. */ - if ((config->fc_nclusters > maxnclusters - 2) || + if ((config->fc_nclusters + 2 > maxnclusters) || (config->fc_nclusters < FAT_MINCLUST16)) { fvdbg("Too few or too many clusters for FAT16\n"); @@ -543,7 +543,7 @@ mkfatfs_tryfat16(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, } /**************************************************************************** - * Name: mkfatfs_try32 + * Name: mkfatfs_tryfat32 * * Description: * Try to define a FAT32 filesystem on the device using the candidate @@ -587,7 +587,7 @@ mkfatfs_tryfat32(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, * maxnclusters = nfatsects * sectorsize / 4 - 2 */ - maxnclusters = (config->fc_nfatsects >> (var->fv_sectshift - 2)); + maxnclusters = (config->fc_nfatsects << (var->fv_sectshift - 2)); if (maxnclusters > FAT_MAXCLUST32) { maxnclusters = FAT_MAXCLUST32; @@ -599,7 +599,7 @@ mkfatfs_tryfat32(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var, * FAT32 (remembering that two FAT cluster slots are reserved). */ - if ((config->fc_nclusters > maxnclusters - 3) || + if ((config->fc_nclusters + 3 > maxnclusters) || (config->fc_nclusters < FAT_MINCLUST32 && fmt->ff_fattype != 32)) { fvdbg("Too few or too many clusters for FAT32\n"); diff --git a/nuttx/fs/fat/fs_fat32.c b/nuttx/fs/fat/fs_fat32.c index c10c28a5c..df8962b51 100644 --- a/nuttx/fs/fat/fs_fat32.c +++ b/nuttx/fs/fat/fs_fat32.c @@ -381,6 +381,7 @@ static int fat_close(FAR struct file *filep) { struct inode *inode; struct fat_file_s *ff; + struct fat_mountpt_s *fs; int ret = OK; /* Sanity checks */ @@ -391,6 +392,7 @@ static int fat_close(FAR struct file *filep) ff = filep->f_priv; inode = filep->f_inode; + fs = inode->i_private; /* Do not check if the mount is healthy. We must support closing of * the file even when there is healthy mount. @@ -408,6 +410,7 @@ static int fat_close(FAR struct file *filep) if (ff->ff_buffer) { + (void)fs; /* Unused if fat_io_free == free(). */ fat_io_free(ff->ff_buffer, fs->fs_hwsectorsize); } diff --git a/nuttx/fs/fat/fs_fat32util.c b/nuttx/fs/fat/fs_fat32util.c index 9aa1d3992..8edef7735 100644 --- a/nuttx/fs/fat/fs_fat32util.c +++ b/nuttx/fs/fat/fs_fat32util.c @@ -106,8 +106,8 @@ static int fat_checkfsinfo(struct fat_mountpt_s *fs) FSI_GETSTRUCTSIG(fs->fs_buffer) == 0x61417272 && FSI_GETTRAILSIG(fs->fs_buffer) == BOOT_SIGNATURE32) { - fs->fs_fsinextfree = FSI_GETFREECOUNT(fs->fs_buffer); - fs->fs_fsifreecount = FSI_GETNXTFREE(fs->fs_buffer); + fs->fs_fsifreecount = FSI_GETFREECOUNT(fs->fs_buffer); + fs->fs_fsinextfree = FSI_GETNXTFREE(fs->fs_buffer); return OK; } } -- cgit v1.2.3 From 7791704ef2784de04a7dadd7389e200ede78d738 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 3 Feb 2013 19:36:10 -0800 Subject: Back out the ADC DMA support. We aren't using or maintaining it, and it doesn't work "right" either. --- nuttx/arch/arm/src/stm32/stm32_adc.c | 315 +++++------------------------------ nuttx/arch/arm/src/stm32/stm32_adc.h | 6 + 2 files changed, 48 insertions(+), 273 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c index 844f1fd0f..b5033b057 100644 --- a/nuttx/arch/arm/src/stm32/stm32_adc.c +++ b/nuttx/arch/arm/src/stm32/stm32_adc.c @@ -118,25 +118,12 @@ struct stm32_dev_s uint32_t freq; /* The desired frequency of conversions */ #endif uint8_t chanlist[ADC_MAX_SAMPLES]; -#ifdef CONFIG_ADC_DMA - const unsigned int rxdma_channel; /* DMA channel assigned */ - DMA_HANDLE rxdma; /* currently-open receive DMA stream */ - bool rxenable; /* DMA-based reception en/disable */ - uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */ - int32_t *const rxfifo; /* Receive DMA buffer */ -#endif }; /**************************************************************************** * Private Function Prototypes ****************************************************************************/ -# ifdef CONFIG_ADC_DMA -static int16_t g_adc3dmarxfifo[ADC_MAX_SAMPLES]; -# endif - - - /* ADC Register access */ static uint32_t adc_getreg(struct stm32_dev_s *priv, int offset); @@ -179,15 +166,6 @@ static int adc_timinit(FAR struct stm32_dev_s *priv); static void adc_startconv(FAR struct stm32_dev_s *priv, bool enable); #endif -#ifdef CONFIG_ADC_DMA -static int up_dma_setup(struct adc_dev_s *dev); -static void up_dma_shutdown(struct adc_dev_s *dev); -//static int up_dma_receive(struct uart_dev_s *dev, uint32_t *status); -//static void up_dma_rxint(struct uart_dev_s *dev, bool enable); -//static bool up_dma_rxavailable(struct uart_dev_s *dev); -static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, FAR struct adc_dev_s *dev); -#endif - /**************************************************************************** * Private Data ****************************************************************************/ @@ -284,10 +262,6 @@ static struct stm32_dev_s g_adcpriv3 = .pclck = ADC3_TIMER_PCLK_FREQUENCY, .freq = CONFIG_STM32_ADC3_SAMPLE_FREQUENCY, #endif -#ifdef CONFIG_ADC_DMA - .rxdma_channel = DMAMAP_ADC3_2, - .rxfifo = g_adc3dmarxfifo, -#endif }; static struct adc_dev_s g_adcdev3 = @@ -569,7 +543,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv) * So ( prescaler = pclck / 65535 / freq ) would be optimal. */ - prescaler = 128;//(priv->pclck / priv->freq + 65534) / 65535; + prescaler = (priv->pclck / priv->freq + 65534) / 65535; /* We need to decrement the prescaler value by one, but only, the value does * not underflow. @@ -591,7 +565,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv) timclk = priv->pclck / prescaler; - reload = priv->freq;//timclk / priv->freq; + reload = timclk / priv->freq; if (reload < 1) { adbg("WARNING: Reload value underflowed.\n"); @@ -720,10 +694,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv) case 4: /* TimerX TRGO event */ { -#warning "TRGO support not yet implemented" - + /* TODO: TRGO support not yet implemented */ /* Set the event TRGO */ + ccenable = 0; egr = GTIM_EGR_TG; /* Set the duty cycle by writing to the CCR register for this channel */ @@ -936,139 +910,6 @@ static void adc_rccreset(struct stm32_dev_s *priv, bool reset) irqrestore(flags); } -/**************************************************************************** - * Name: up_dma_setup - * - * Description: - * - ****************************************************************************/ - -#ifdef CONFIG_ADC_DMA -static int up_dma_setup(FAR struct adc_dev_s *dev) -{ - - FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv; - int result; - uint32_t regval; - -// -// result = up_setup(dev); -// if (result != OK) -// { -// return result; -// } - - /* Acquire the DMA channel. This should always succeed. */ - - priv->rxdma = stm32_dmachannel(priv->rxdma_channel); - - /* Configure for circular DMA reception into the RX fifo */ - - stm32_dmasetup(priv->rxdma, - priv->base + STM32_ADC_DR_OFFSET, - (uint32_t)priv->rxfifo, - 4,//buffersize - DMA_SCR_DIR_P2M | - DMA_SCR_CIRC | - DMA_SCR_MINC | - DMA_SCR_PSIZE_16BITS | - DMA_SCR_MSIZE_16BITS | - DMA_SCR_PBURST_SINGLE | - DMA_SCR_MBURST_SINGLE); - - /* Reset our DMA shadow pointer to match the address just - * programmed above. - */ - - //priv->rxdmanext = 0; - - /* Enable DMA for the ADC */ - - /* Start the DMA channel, and arrange for callbacks at the half and - * full points in the FIFO. This ensures that we have half a FIFO - * worth of time to claim bytes before they are overwritten. - */ - - stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)dev, false); - - return OK; -} -#endif -/**************************************************************************** - * Name: up_dma_rxcallback - * - * Description: - - * - ****************************************************************************/ - -#ifdef CONFIG_ADC_DMA -static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, FAR struct adc_dev_s *dev) -{ - //struct up_dev_s *priv = (struct up_dev_s*)arg; - //uint32_t regval; - FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv; - //struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle; - - //if (priv->rxenable && up_dma_rxavailable(&priv->dev)) - { - /* Give the ADC data to the ADC driver. adc_receive accepts 3 parameters: - * - * 1) The first is the ADC device instance for this ADC block. - * 2) The second is the channel number for the data, and - * 3) The third is the converted data for the channel. - */ - - - adc_receive(dev, 10, (int32_t)g_adc3dmarxfifo[1]); - adc_receive(dev, 11, (int32_t)g_adc3dmarxfifo[2]); - adc_receive(dev, 12, (int32_t)g_adc3dmarxfifo[3]); - adc_receive(dev, 13, (int32_t)g_adc3dmarxfifo[0]); - - - /* Set the channel number of the next channel that will complete conversion */ - - priv->current++; - - if (priv->current >= priv->nchannels) - { - /* Restart the conversion sequence from the beginning */ - - priv->current = 0; - } - - - } -} -#endif - -/**************************************************************************** - * Name: up_dma_shutdown - * - * Description: - * Disable the DMA - * - ****************************************************************************/ - -#ifdef CONFIG_ADC_DMA -static void up_dma_shutdown(struct adc_dev_s *dev) -{ - - FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv; - - - /* Stop the DMA channel */ - - stm32_dmastop(priv->rxdma); - - /* Release the DMA channel */ - - stm32_dmafree(priv->rxdma); - priv->rxdma = NULL; -} -#endif - - /******************************************************************************* * Name: adc_enable * @@ -1089,7 +930,7 @@ static void adc_enable(FAR struct stm32_dev_s *priv, bool enable) { uint32_t regval; - // avdbg("enable: %d\n", enable); + avdbg("enable: %d\n", enable); regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); if (enable) @@ -1123,12 +964,14 @@ static void adc_reset(FAR struct adc_dev_s *dev) uint32_t regval; int offset; int i; +#ifdef ADC_HAVE_TIMER int ret; +#endif avdbg("intf: ADC%d\n", priv->intf); flags = irqsave(); - /* Enable ADC reset state */ + /* Enable ADC reset state */ adc_rccreset(priv, true); @@ -1146,7 +989,6 @@ static void adc_reset(FAR struct adc_dev_s *dev) adc_putreg(priv, STM32_ADC_LTR_OFFSET, 0x00000000); - /* Initialize the same sample time for each ADC 55.5 cycles * * During sample cycles channel selection bits must remain unchanged. @@ -1179,8 +1021,16 @@ static void adc_reset(FAR struct adc_dev_s *dev) regval |= ADC_CR1_AWDEN; regval |= (priv->chanlist[0] << ADC_CR1_AWDCH_SHIFT); + /* Enable interrupt flags */ + + regval |= ADC_CR1_ALLINTS; + #if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) + /* Enable or disable Overrun interrupt */ + + regval &= ~ADC_CR1_OVRIE; + /* Set the resolution of the conversion */ regval |= ACD_CR1_RES_12BIT; @@ -1229,12 +1079,6 @@ static void adc_reset(FAR struct adc_dev_s *dev) { regval |= (uint32_t)priv->chanlist[i] << offset; } - /* Set the number of conversions */ - - DEBUGASSERT(priv->nchannels <= ADC_MAX_SAMPLES); - - regval |= (((uint32_t)priv->nchannels-1) << ADC_SQR1_L_SHIFT); - adc_putreg(priv, STM32_ADC_SQR1_OFFSET, regval); /* ADC CCR configuration */ @@ -1246,7 +1090,12 @@ static void adc_reset(FAR struct adc_dev_s *dev) putreg32(regval, STM32_ADC_CCR); #endif + /* Set the number of conversions */ + DEBUGASSERT(priv->nchannels <= ADC_MAX_SAMPLES); + + regval |= (((uint32_t)priv->nchannels-1) << ADC_SQR1_L_SHIFT); + adc_putreg(priv, STM32_ADC_SQR1_OFFSET, regval); /* Set the channel index of the first conversion */ @@ -1269,30 +1118,25 @@ static void adc_reset(FAR struct adc_dev_s *dev) */ adc_enable(priv, true); -#else -#ifdef CONFIG_ADC_DMA - //nothing #else adc_startconv(priv, true); -#endif #endif /* CONFIG_STM32_STM32F10XX */ #endif /* ADC_HAVE_TIMER */ - irqrestore(flags); -// avdbg("SR: 0x%08x CR1: 0x%08x CR2: 0x%08x\n", -// adc_getreg(priv, STM32_ADC_SR_OFFSET), -// adc_getreg(priv, STM32_ADC_CR1_OFFSET), -// adc_getreg(priv, STM32_ADC_CR2_OFFSET)); -// avdbg("SQR1: 0x%08x SQR2: 0x%08x SQR3: 0x%08x\n", -// adc_getreg(priv, STM32_ADC_SQR1_OFFSET), -// adc_getreg(priv, STM32_ADC_SQR2_OFFSET), -// adc_getreg(priv, STM32_ADC_SQR3_OFFSET)); -//#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) -// avdbg("CCR: 0x%08x\n", -// getreg32(STM32_ADC_CCR)); -//#endif + avdbg("SR: 0x%08x CR1: 0x%08x CR2: 0x%08x\n", + adc_getreg(priv, STM32_ADC_SR_OFFSET), + adc_getreg(priv, STM32_ADC_CR1_OFFSET), + adc_getreg(priv, STM32_ADC_CR2_OFFSET)); + avdbg("SQR1: 0x%08x SQR2: 0x%08x SQR3: 0x%08x\n", + adc_getreg(priv, STM32_ADC_SQR1_OFFSET), + adc_getreg(priv, STM32_ADC_SQR2_OFFSET), + adc_getreg(priv, STM32_ADC_SQR3_OFFSET)); +#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) + avdbg("CCR: 0x%08x\n", + getreg32(STM32_ADC_CCR)); +#endif } /**************************************************************************** @@ -1314,86 +1158,21 @@ static int adc_setup(FAR struct adc_dev_s *dev) { FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv; int ret; - uint32_t regval; - - - /* the adc seems to need a full reset to be enabled correctly */ - adc_reset(dev); -#ifndef CONFIG_ADC_DMA /* Attach the ADC interrupt */ ret = irq_attach(priv->irq, priv->isr); if (ret == OK) { + /* Make sure that the ADC device is in the powered up, reset state */ + + adc_reset(dev); + /* Enable the ADC interrupt */ avdbg("Enable the ADC interrupt: irq=%d\n", priv->irq); up_enable_irq(priv->irq); } -#endif - -#ifdef CONFIG_ADC_DMA - up_dma_setup(dev); - - -//#ifndef ADC_HAVE_TIMER -// /*disable external trigger*/ -// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); -// regval |= ACD_CR2_EXTEN_NONE; -// //regval |= ADC_CR1_DISCEN; -// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); -//#else -// /*enable external trigger*/ -// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); -// regval |=ADC_CR2_EXTSEL_T4CC4; -// regval |=ACD_CR2_EXTEN_BOTH; -// //regval |= ADC_CR2_CONT; -// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); -//#endif - - - /*enable scan mode*/ - regval = adc_getreg(priv, STM32_ADC_CR1_OFFSET); - regval |= ADC_CR1_SCAN; - //regval |= ADC_CR1_DISCEN; - adc_putreg(priv, STM32_ADC_CR1_OFFSET, regval); - - /* Enable DMA request after last transfer (Single-ADC mode) */ - //ADC_DMARequestAfterLastTransferCmd(ADC3, ENABLE); - regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); - regval |= ADC_CR2_DDS; - adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); - - /* Enable ADC3 DMA */ - // ADC_DMACmd(ADC3, ENABLE); - regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); - regval |= ADC_CR2_DMA; - adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); -#endif - - -#ifndef ADC_HAVE_TIMER - /*set continuous conversion */ - regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); - regval |= ADC_CR2_CONT; - adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); -#endif - - /* Enable ADC3 */ - //ADC_Cmd(ADC3, ENABLE); - regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); - regval |= ADC_CR2_ADON; - adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); - -//// /*start conversion*/ -// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); -// regval |= ADC_CR2_SWSTART; -// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); - - - - return ret; } @@ -1415,24 +1194,14 @@ static void adc_shutdown(FAR struct adc_dev_s *dev) { FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv; -#ifdef CONFIG_ADC_DMA - up_dma_shutdown(dev); -#endif - -#ifdef ADC_HAVE_TIMER - /* stop adc timer */ - adc_timstart(priv, false); -#endif + /* Disable ADC interrupts and detach the ADC interrupt handler */ - /* power down ADC */ - adc_enable(priv, false); + up_disable_irq(priv->irq); + irq_detach(priv->irq); - adc_rxint(dev, false); + /* Disable and reset the ADC module */ - /* Disable ADC interrupts and detach the ADC interrupt handler */ - up_disable_irq(priv->irq); -// irq_detach(priv->irq); - // XXX Why is irq_detach here commented out? + adc_rccreset(priv, true); } /**************************************************************************** diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.h b/nuttx/arch/arm/src/stm32/stm32_adc.h index 7b6c13b33..060fcdfb9 100644 --- a/nuttx/arch/arm/src/stm32/stm32_adc.h +++ b/nuttx/arch/arm/src/stm32/stm32_adc.h @@ -161,6 +161,12 @@ #if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3) +/* DMA support is not yet implemented for this driver */ + +#ifdef CONFIG_ADC_DMA +# warning "DMA is not supported by the current driver" +#endif + /* Timer configuration: If a timer trigger is specified, then get information * about the timer. */ -- cgit v1.2.3 From 0c7c32ce95e2643d44fb41784c354cd6a852335c Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 3 Feb 2013 19:36:54 -0800 Subject: Merge whitespace and comments so that we are closer to in sync with trunk. --- nuttx/arch/arm/src/stm32/stm32_i2c.c | 85 ++++++++++++++++++++---------------- 1 file changed, 47 insertions(+), 38 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c index 0062c072b..82ae6af5f 100644 --- a/nuttx/arch/arm/src/stm32/stm32_i2c.c +++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c @@ -107,11 +107,11 @@ #if !defined(CONFIG_STM32_I2CTIMEOSEC) && !defined(CONFIG_STM32_I2CTIMEOMS) # define CONFIG_STM32_I2CTIMEOSEC 0 -# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */ +# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */ #elif !defined(CONFIG_STM32_I2CTIMEOSEC) # define CONFIG_STM32_I2CTIMEOSEC 0 /* User provided milliseconds */ #elif !defined(CONFIG_STM32_I2CTIMEOMS) -# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */ +# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */ #endif /* Interrupt wait time timeout in system timer ticks */ @@ -219,31 +219,31 @@ struct stm32_i2c_config_s struct stm32_i2c_priv_s { const struct stm32_i2c_config_s *config; /* Port configuration */ - int refs; /* Referernce count */ - sem_t sem_excl; /* Mutual exclusion semaphore */ + int refs; /* Referernce count */ + sem_t sem_excl; /* Mutual exclusion semaphore */ #ifndef CONFIG_I2C_POLLED - sem_t sem_isr; /* Interrupt wait semaphore */ + sem_t sem_isr; /* Interrupt wait semaphore */ #endif - volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */ + volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */ - uint8_t msgc; /* Message count */ - struct i2c_msg_s *msgv; /* Message list */ - uint8_t *ptr; /* Current message buffer */ - int dcnt; /* Current message length */ - uint16_t flags; /* Current message flags */ + uint8_t msgc; /* Message count */ + struct i2c_msg_s *msgv; /* Message list */ + uint8_t *ptr; /* Current message buffer */ + int dcnt; /* Current message length */ + uint16_t flags; /* Current message flags */ /* I2C trace support */ #ifdef CONFIG_I2C_TRACE - int tndx; /* Trace array index */ - uint32_t start_time; /* Time when the trace was started */ + int tndx; /* Trace array index */ + uint32_t start_time; /* Time when the trace was started */ /* The actual trace data */ struct stm32_trace_s trace[CONFIG_I2C_NTRACE]; #endif - uint32_t status; /* End of transfer SR2|SR1 status */ + uint32_t status; /* End of transfer SR2|SR1 status */ }; /* I2C Device, Instance */ @@ -281,7 +281,7 @@ static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t statu static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv, enum stm32_trace_e event, uint32_t parm); static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv); -#endif +#endif /* CONFIG_I2C_TRACE */ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequency); static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv); @@ -291,7 +291,7 @@ static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv); #ifdef I2C1_FSMC_CONFLICT static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv); static inline void stm32_i2c_enablefsmc(uint32_t ahbenr); -#endif +#endif /* I2C1_FSMC_CONFLICT */ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv); #ifndef CONFIG_I2C_POLLED #ifdef CONFIG_STM32_I2C1 @@ -582,15 +582,14 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int abstime.tv_sec++; abstime.tv_nsec -= 1000 * 1000 * 1000; } -#else - #if CONFIG_STM32_I2CTIMEOMS > 0 - abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000; - if (abstime.tv_nsec > 1000 * 1000 * 1000) - { - abstime.tv_sec++; - abstime.tv_nsec -= 1000 * 1000 * 1000; - } - #endif + +#elif CONFIG_STM32_I2CTIMEOMS > 0 + abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000; + if (abstime.tv_nsec > 1000 * 1000 * 1000) + { + abstime.tv_sec++; + abstime.tv_nsec -= 1000 * 1000 * 1000; + } #endif /* Wait until either the transfer is complete or the timeout expires */ @@ -932,7 +931,7 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequ { /* Fast mode speed calculation with Tlow/Thigh = 16/9 */ -#ifdef CONFIG_I2C_DUTY16_9 +#ifdef CONFIG_STM32_I2C_DUTY16_9 speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25)); /* Set DUTY and fast speed bits */ @@ -1071,7 +1070,7 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv) /* Is this I2C1 */ -#ifdef CONFIG_STM32_I2C2 +#if defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3) if (priv->config->base == STM32_I2C1_BASE) #endif { @@ -1198,26 +1197,29 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) { stm32_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt); + /* No interrupts or context switches may occur in the following + * sequence. Otherwise, additional bytes may be sent by the + * device. + */ + #ifdef CONFIG_I2C_POLLED irqstate_t state = irqsave(); #endif - /* Receive a byte */ *priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET); /* Disable acknowledge when last byte is to be received */ + priv->dcnt--; if (priv->dcnt == 1) { stm32_i2c_modifyreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_ACK, 0); } - priv->dcnt--; #ifdef CONFIG_I2C_POLLED irqrestore(state); #endif - } } @@ -1408,7 +1410,6 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) /* Enable power and reset the peripheral */ modifyreg32(STM32_RCC_APB1ENR, 0, priv->config->clk_bit); - modifyreg32(STM32_RCC_APB1RSTR, 0, priv->config->reset_bit); modifyreg32(STM32_RCC_APB1RSTR, priv->config->reset_bit, 0); @@ -1428,10 +1429,10 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) /* Attach ISRs */ #ifndef CONFIG_I2C_POLLED - irq_attach(priv->config->ev_irq, priv->config->isr); - irq_attach(priv->config->er_irq, priv->config->isr); - up_enable_irq(priv->config->ev_irq); - up_enable_irq(priv->config->er_irq); + irq_attach(priv->config->ev_irq, priv->config->isr); + irq_attach(priv->config->er_irq, priv->config->isr); + up_enable_irq(priv->config->ev_irq); + up_enable_irq(priv->config->er_irq); #endif /* Set peripheral frequency, where it must be at least 2 MHz for 100 kHz @@ -1461,17 +1462,23 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv) stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0); + /* Unconfigure GPIO pins */ + stm32_unconfiggpio(priv->config->scl_pin); stm32_unconfiggpio(priv->config->sda_pin); + /* Disable and detach interrupts */ + #ifndef CONFIG_I2C_POLLED up_disable_irq(priv->config->ev_irq); up_disable_irq(priv->config->er_irq); irq_detach(priv->config->ev_irq); irq_detach(priv->config->er_irq); #endif - modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0); + /* Disable clocking */ + + modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0); return OK; } @@ -1623,7 +1630,9 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms */ stm32_i2c_clrstart(priv); - // XXX also clear busy flag in case of timeout + + /* Clear busy flag in case of timeout */ + status = priv->status & 0xffff; } else @@ -2070,4 +2079,4 @@ out: return ret; } -#endif /* defined(CONFIG_STM32_I2C1) || defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3) */ +#endif /* CONFIG_STM32_I2C1 || CONFIG_STM32_I2C2 || CONFIG_STM32_I2C3 */ -- cgit v1.2.3