summaryrefslogtreecommitdiff
path: root/nuttx/arch/hc/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-20 15:19:44 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-20 15:19:44 +0000
commit2d795267b97ca49c544ca4a38dbf3771d3cd4697 (patch)
tree84c0f2def09c2c2e7712cc448ed152cb3652ad4b /nuttx/arch/hc/src
parent2beb149e9bbba41c18ec8b3d83c2ba81c39b35a0 (diff)
downloadpx4-nuttx-2d795267b97ca49c544ca4a38dbf3771d3cd4697.tar.gz
px4-nuttx-2d795267b97ca49c544ca4a38dbf3771d3cd4697.tar.bz2
px4-nuttx-2d795267b97ca49c544ca4a38dbf3771d3cd4697.zip
Add m9s12 serial logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3305 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/hc/src')
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_lowputc.S107
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_serial.h94
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_start.S5
3 files changed, 202 insertions, 4 deletions
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_lowputc.S b/nuttx/arch/hc/src/m9s12/m9s12_lowputc.S
index e4bc7858c..a04d6a1d8 100755
--- a/nuttx/arch/hc/src/m9s12/m9s12_lowputc.S
+++ b/nuttx/arch/hc/src/m9s12/m9s12_lowputc.S
@@ -41,12 +41,65 @@
#include "up_internal.h"
#include "m9s12_internal.h"
-#include "m9s12_flash.h"
+#include "m9s12_sci.h"
+#include "m9s12_serial.h"
+
+#ifdef CONFIG_HCS12_SERIALMON
+# include "m9s12_flash.h"
+#endif
/**************************************************************************
* Private Definitions
**************************************************************************/
+/* Select SCI parameters for the selected console */
+
+#if defined(CONFIG_SCI0_SERIAL_CONSOLE)
+# define HCS12_CONSOLE_BASE HCS12_SCI0_BASE
+# define HCS12_CONSOLE_BAUD CONFIG_SCI0_BAUD
+# define HCS12_CONSOLE_BITS CONFIG_SCI0_BITS
+# define HCS12_CONSOLE_PARITY CONFIG_SCI0_PARITY
+# define HCS12_CONSOLE_2STOP CONFIG_SCI0_2STOP
+#elif defined(CONFIG_SCI1_SERIAL_CONSOLE)
+# define HCS12_CONSOLE_BASE HCS12_SCI1_BASE
+# define HCS12_CONSOLE_BAUD CONFIG_SCI1_BAUD
+# define HCS12_CONSOLE_BITS CONFIG_SCI1_BITS
+# define HCS12_CONSOLE_PARITY CONFIG_SCI1_PARITY
+# define HCS12_CONSOLE_2STOP CONFIG_SCI1_2STOP
+#else
+# warning "No CONFIG_SCIn_SERIAL_CONSOLE Setting"
+#endif
+
+/* Selete the SCIBR register value */
+
+#define CONSOLE_SCIBR_VALUE SCIBR_VALUE(HCS12_CONSOLE_BAUD)
+
+/* Select the SCICR1 register settings */
+
+#if HCS12_CONSOLE_BITS == 9
+# define UART_SCICR1_NBITS SCI_CR1_M
+#elif HCS12_CONSOLE_BITS == 8
+# define UART_SCICR1_NBITS 0
+#else
+# warning "Number of bits not supported"
+#endif
+
+#if HCS12_CONSOLE_PARITY == 0
+# define UART_SCICR1_PARITY 0
+#elif HCS12_CONSOLE_PARITY == 1
+# define UART_SCICR1_PARITY SCI_CR1_PE
+#elif HCS12_CONSOLE_PARITY == 2
+# define UART_SCICR1_PARITY (SCI_CR1_PE|SCI_CR1_PT)
+#else
+# error "ERROR: Invalid parity selection"
+#endif
+
+#if HCS12_CONSOLE_2STOP != 0
+# warning "Only a single stop bit supported"
+#endif
+
+#define CONSOLE_SCICR_VALUE (UART_SCICR1_NBITS|UART_SCICR1_PARITY)
+
/**************************************************************************
* Private Types
**************************************************************************/
@@ -82,7 +135,31 @@ up_lowsetup:
#ifdef CONFIG_HCS12_SERIALMON
rts
#else
-# error "up_lowsetup not implemented"
+ /* Disable the console */
+
+ ldab #0
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_CR1_OFFSET)
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_CR2_OFFSET)
+
+ /* Set the BAUD pre-scaler value */
+
+ ldab #(CONSOLE_SCIBR_VALUE >> 8)
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_BDH_OFFSET)
+
+ ldab #(CONSOLE_SCIBR_VALUE & 0xff)
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_BDL_OFFSET)
+
+ /* Set number of bits, parity, stop bits, etc. */
+
+ ldab #CONSOLE_SCICR_VALUE
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_CR1_OFFSET)
+
+ /* Enable transmitter and receiver */
+
+ ldab #(SCI_CR2_RE|SCI_CR2_TE)
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_CR2_OFFSET)
+ rts
+
#endif
.size up_lowsetup, . - up_lowsetup
@@ -97,7 +174,31 @@ up_lowputc:
#ifdef CONFIG_HCS12_SERIALMON
jmp PutChar
#else
-# error "up_lowputc not implemented"
+# if HCS12_CONSOLE_BITS == 9
+ staa 1, -sp
+# endif
+
+ /* Wait for the transmit data register to be available (TRDE==1) */
+
+.Lwait:
+ ldaa (HCS12_CONSOLE_BASE+HCS12_SCI_SR1_OFFSET)
+ bita #SCI_SR1_TDRE
+ bne .Lwait
+
+ /* Then write the byte to the transmit data register */
+
+# if HCS12_CONSOLE_BITS == 9
+ ldaa 1, sp+
+ bita #(0x01)
+ bne .L8bit
+ ldaa #SCI_DRH_T8
+ bra .Lwrdrh
+.L8bit:
+ ldaa #0
+.Lwrdrh:
+ staa (HCS12_CONSOLE_BASE+HCS12_SCI_DRH_OFFSET)
+# endif
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_DRL_OFFSET)
rts
#endif
.size up_lowputc, . - up_lowputc
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_serial.h b/nuttx/arch/hc/src/m9s12/m9s12_serial.h
new file mode 100755
index 000000000..107440616
--- /dev/null
+++ b/nuttx/arch/hc/src/m9s12/m9s12_serial.h
@@ -0,0 +1,94 @@
+/************************************************************************************
+ * arch/hc/src/m9s12/serial.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name 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_HC_SRC_M9S12_CHIP_H
+#define __ARCH_HC_SRC_M9S12_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/board/board.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+/* Is there a SCI enabled? */
+
+#if defined(CONFIG_SCI0_DISABLE) && defined(CONFIG_SCI1_DISABLE)
+# error "No SCIs enabled"
+#endif
+
+/* Is there a serial console? */
+
+#if defined(CONFIG_SCI0_SERIAL_CONSOLE) && !defined(CONFIG_SCI0_DISABLE)
+# undef CONFIG_SCI1_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#elif defined(CONFIG_SCI1_SERIAL_CONSOLE) && !defined(CONFIG_SCI1_DISABLE)
+# undef CONFIG_SCI0_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#else
+# warning "No valid CONFIG_SCIn_SERIAL_CONSOLE Setting"
+# undef CONFIG_SCI0_SERIAL_CONSOLE
+# undef CONFIG_SCI1_SERIAL_CONSOLE
+# undef HAVE_CONSOLE
+#endif
+
+/* BAUD *****************************************************************************/
+/* Baud calculations. The SCI module is driven by the BUSCLK. The SCIBR
+ * register value divides down the BUSCLK to accomplish the required BAUD.
+ *
+ * BAUD = HCS12_BUSCLK / (16 * SCIBR)
+ * SCIBR = HCS12_BUSCLK / (16 * BAUD)
+ */
+
+#define SCIBR_VALUE(b) ((HCS12_BUSCLK * (b) + ((b) << 3))/((b) << 4))
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_HC_SRC_M9S12_CHIP_H */
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_start.S b/nuttx/arch/hc/src/m9s12/m9s12_start.S
index b7585d75b..ad5a39c0d 100755
--- a/nuttx/arch/hc/src/m9s12/m9s12_start.S
+++ b/nuttx/arch/hc/src/m9s12/m9s12_start.S
@@ -40,6 +40,8 @@
#include <nuttx/config.h>
+#include <arch/board/board.h>
+
#include "m9s12_internal.h"
#include "m9s12_mmc.h"
#include "m9s12_crg.h"
@@ -118,8 +120,9 @@
/* Set the multipler and divider and enable the PLL */
bclr *HCS12_CRG_PLLCTL #CRG_PLLCTL_PLLON
- ldab #15
+ ldab #HCS12_SYNR_VALUE
stab HCS12_CRG_SYNR
+ ldab #HCS12_REFDV_VALUE
stab HCS12_CRG_REFDV
bset *HCS12_CRG_PLLCTL #CRG_PLLCTL_PLLON