summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-26 14:35:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-26 14:35:25 +0000
commit84c38efeff157aac42105ccf709a604af75bf9ec (patch)
tree318232aeb96cd306ae866fff3882e4a069acc118 /nuttx
parenteb243ffb65d42ef0426e0ae75ef8f52b8adf2468 (diff)
downloadpx4-nuttx-84c38efeff157aac42105ccf709a604af75bf9ec.tar.gz
px4-nuttx-84c38efeff157aac42105ccf709a604af75bf9ec.tar.bz2
px4-nuttx-84c38efeff157aac42105ccf709a604af75bf9ec.zip
Fix a16f serial bugs
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@568 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_head.S2
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_lowuart.S18
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_serial.c35
-rw-r--r--nuttx/configs/z16f2800100zcog/README.txt3
-rw-r--r--nuttx/configs/z16f2800100zcog/ostest/defconfig4
-rwxr-xr-xnuttx/configs/z16f2800100zcog/ostest/ostest.linkcmd5
-rw-r--r--nuttx/lib/lib_dbg.c2
-rw-r--r--nuttx/lib/lib_vsprintf.c52
8 files changed, 59 insertions, 62 deletions
diff --git a/nuttx/arch/z16/src/z16f/z16f_head.S b/nuttx/arch/z16/src/z16f/z16f_head.S
index 2a1871aae..f9cdf745c 100755
--- a/nuttx/arch/z16/src/z16f/z16f_head.S
+++ b/nuttx/arch/z16/src/z16f/z16f_head.S
@@ -149,7 +149,7 @@ _z16f_reset:
#endif
/* Perform VERY early UART initialization so that we can use it here */
-#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
+#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC) || CONFIG_NFILE_DESCRIPTORS == 0
call _z16f_lowuartinit /* Initialize the UART for debugging */
#endif
/* Initialize the hardware stack overflow register */
diff --git a/nuttx/arch/z16/src/z16f/z16f_lowuart.S b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
index 037b3dd80..5e45e8c53 100755
--- a/nuttx/arch/z16/src/z16f/z16f_lowuart.S
+++ b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
@@ -41,7 +41,7 @@
#include <nuttx/config.h>
#include "chip/chip.h"
-#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
+#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC) || CONFIG_NFILE_DESCRIPTORS == 0
/*************************************************************************
* External References / External Definitions
@@ -96,31 +96,31 @@ _z16f_lowuartinit:
udiv r0, r3 /* BRG = (freq + baud * 8)/(baud * 16) */
#ifdef CONFIG_UART0_SERIAL_CONSOLE
- ld.w Z16F_UART0_BR, r0 /* Z16F_UART0_BR = BRG */
+ ld.w Z16F_UART1_BR, r0 /* Z16F_UART1_BR = BRG */
/* Set the GPIO Alternate Function Register Lo (AFL) register */
ld r0, #%30
- or.b Z16F_GPIOA_AFL, r0 /* Z16F_GPIOA_AFL |= %30 */
+ or.b Z16F_GPIOD_AFL, r0 /* Z16F_GPIOD_AFL |= %30 */
/* Enable UART receive (REN) and transmit (TEN) */
- clr.b Z16F_UART0_CTL1 /* Z16F_UART0_CTL1 = 0 */
+ clr.b Z16F_UART1_CTL1 /* Z16F_UART1_CTL1 = 0 */
ld r0, #(Z16F_UARTCTL0_TEN|Z16F_UARTCTL0_REN)
- ld.b Z16F_UART0_CTL0, r0 /* Z16F_UART0_CTL0 = %c0 */
+ ld.b Z16F_UART1_CTL0, r0 /* Z16F_UART1_CTL0 = %c0 */
#else
- ld.w Z16F_UART1_BR, r0 /* Z16F_UART1_BR = BRG */
+ ld.w Z16F_UART0_BR, r0 /* Z16F_UART0_BR = BRG */
/* Set the GPIO Alternate Function Register Lo (AFL) register */
ld r0, #%30
- or.b Z16F_GPIOD_AFL, r0 /* Z16F_GPIOD_AFL |= %30 */
+ or.b Z16F_GPIOA_AFL, r0 /* Z16F_GPIOA_AFL |= %30 */
/* Enable UART receive (REN) and transmit (TEN) */
- clr.b Z16F_UART1_CTL1 /* Z16F_UART1_CTL1 = 0 */
+ clr.b Z16F_UART0_CTL1 /* Z16F_UART0_CTL1 = 0 */
ld r0, #(Z16F_UARTCTL0_TEN|Z16F_UARTCTL0_REN)
- ld.b Z16F_UART1_CTL0, r0 /* Z16F_UART1_CTL0 = %c0 */
+ ld.b Z16F_UART0_CTL0, r0 /* Z16F_UART0_CTL0 = %c0 */
#endif
popmlo <r0, r3> /* Restore registers */
ret /* Return */
diff --git a/nuttx/arch/z16/src/z16f/z16f_serial.c b/nuttx/arch/z16/src/z16f/z16f_serial.c
index 1ca6e0377..d63c6e5dd 100644
--- a/nuttx/arch/z16/src/z16f/z16f_serial.c
+++ b/nuttx/arch/z16/src/z16f/z16f_serial.c
@@ -649,39 +649,35 @@ int up_putc(int ch)
****************************************************************************/
#ifdef CONFIG_UART1_SERIAL_CONSOLE
-# define z16f_contrde() \
- do { \
- int tmp; \
- for (tmp = 1000 ; tmp > 0 ; tmp--) \
- if ((getreg8(Z16F_UART1_STAT0) & Z16F_UARTSTAT0_TDRE) != 0) \
- break; \
- } while (0)
+# define z16f_contrde() \
+ ((getreg8(Z16F_UART1_STAT0) & Z16F_UARTSTAT0_TDRE) != 0)
# define z16f_contxd(ch) \
- putreg8((ubyte)(ch), Z16F_UART1_STAT0)
+ putreg8((ubyte)(ch), Z16F_UART1_TXD)
#else
-# define z16f_contrde() \
- do { \
- int tmp; \
- for (tmp = 1000 ; tmp > 0 ; tmp--) \
- if ((getreg8(Z16F_UART0_STAT0) & Z16F_UARTSTAT0_TDRE) != 0) \
- break; \
- } while (0)
+# define z16f_contrde() \
+ ((getreg8(Z16F_UART0_STAT0) & Z16F_UARTSTAT0_TDRE) != 0)
# define z16f_contxd(ch) \
- putreg8((ubyte)(ch), Z16F_UART0_STAT0)
+ putreg8((ubyte)(ch), Z16F_UART0_TXD)
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
+static void _up_putc(int ch)
+{
+ int tmp;
+ for (tmp = 1000 ; tmp > 0 && !z16f_contrde(); tmp--);
+ z16f_contxd(ch);
+}
+
/****************************************************************************
* Public Functions
****************************************************************************/
int up_putc(int ch)
{
- z16f_contrde();
- z16f_contxd(ch);
+ _up_putc(ch);
/* Check for LF */
@@ -689,8 +685,7 @@ int up_putc(int ch)
{
/* Add CR */
- z16f_contrde();
- z16f_contxd('\r');
+ _up_putc('\r');
}
return ch;
diff --git a/nuttx/configs/z16f2800100zcog/README.txt b/nuttx/configs/z16f2800100zcog/README.txt
index 1b198a1dc..7231ebfa4 100644
--- a/nuttx/configs/z16f2800100zcog/README.txt
+++ b/nuttx/configs/z16f2800100zcog/README.txt
@@ -11,7 +11,8 @@ from the Zilog website: http://www.zilog.com/software/zds2.asp
Thusfar, I have encountered no insolvable problems with the newer 4.11.0
version of the toolchain.
-If you use any version of ZDS-II other than 4.11.0, you will have to modify
+If you use any version of ZDS-II other than 4.11.0 or if you install ZDS-II
+at anly location other than the default location, you will have to modify
two files: (1) configs/z16f2800100zcog/*/setenv.sh and (2)
configs/z16f2800100zcog/*/Make.defs.
diff --git a/nuttx/configs/z16f2800100zcog/ostest/defconfig b/nuttx/configs/z16f2800100zcog/ostest/defconfig
index 9963672da..60c0cb788 100644
--- a/nuttx/configs/z16f2800100zcog/ostest/defconfig
+++ b/nuttx/configs/z16f2800100zcog/ostest/defconfig
@@ -83,8 +83,8 @@ CONFIG_UART0_TXBUFSIZE=256
CONFIG_UART1_TXBUFSIZE=256
CONFIG_UART0_RXBUFSIZE=256
CONFIG_UART1_RXBUFSIZE=256
-CONFIG_UART0_BAUD=115200
-CONFIG_UART1_BAUD=115200
+CONFIG_UART0_BAUD=57600
+CONFIG_UART1_BAUD=57600
CONFIG_UART0_PARITY=0
CONFIG_UART1_PARITY=0
CONFIG_UART0_2STOP=0
diff --git a/nuttx/configs/z16f2800100zcog/ostest/ostest.linkcmd b/nuttx/configs/z16f2800100zcog/ostest/ostest.linkcmd
index e277a0ccd..5ab69bb46 100755
--- a/nuttx/configs/z16f2800100zcog/ostest/ostest.linkcmd
+++ b/nuttx/configs/z16f2800100zcog/ostest/ostest.linkcmd
@@ -33,7 +33,7 @@
/* */
/****************************************************************************/
- -FORMAT=OMF695,INTEL32
+-FORMAT=OMF695,INTEL32
-map -maxhexlen=64 -quiet -sort NAME=ascending -unresolved=fatal
-warnoverlap -NOxref -warn -debug -NOigcase
@@ -68,17 +68,18 @@ define _far_stack = highaddr of ERAM
define _near_stack = highaddr of RAM
define _near_heapbot = top of RAM
define _far_heapbot = top of ERAM
+
define _SYS_CLK_SRC = 2
define _SYS_CLK_FREQ = 20000000
define __EXTCT_INIT_PARAM = $80
-
define __EXTCS0_INIT_PARAM = $8012
define __EXTCS1_INIT_PARAM = $8001
define __EXTCS2_INIT_PARAM = $0000
define __EXTCS3_INIT_PARAM = $0000
define __EXTCS4_INIT_PARAM = $0000
define __EXTCS5_INIT_PARAM = $0000
+
define __PFAF_INIT_PARAM = $ff
define __PGAF_INIT_PARAM = $ff
define __PDAF_INIT_PARAM = $ff00
diff --git a/nuttx/lib/lib_dbg.c b/nuttx/lib/lib_dbg.c
index 7ad2ac9d8..4a38b76b7 100644
--- a/nuttx/lib/lib_dbg.c
+++ b/nuttx/lib/lib_dbg.c
@@ -86,7 +86,7 @@ int lldbg(const char *format, ...)
va_end(ap);
return ret;
}
-# endif
+#endif
#ifdef CONFIG_DEBUG_VERBOSE
int vdbg(const char *format, ...)
diff --git a/nuttx/lib/lib_vsprintf.c b/nuttx/lib/lib_vsprintf.c
index ec3d34fdb..961ddf9ea 100644
--- a/nuttx/lib/lib_vsprintf.c
+++ b/nuttx/lib/lib_vsprintf.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* lib_vsprintf.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -31,56 +31,56 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Compilation Switches
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <sys/types.h>
#include <stdio.h>
#include "lib_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Type Declarations
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Constant Data
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Constant Data
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* vsprintf
- ************************************************************/
+ ****************************************************************************/
int vsprintf (char *dest, const char *src, va_list ap)
{