summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-11 15:29:11 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-11 15:29:11 +0000
commitd8ac0a01d815d109e177b6f752806f8512c4319e (patch)
tree0565d059f83e489f56f0b08bd02cd3eb311ca56d /nuttx/configs
parent6ba662ab23d592662476229148b230f4f01df197 (diff)
downloadpx4-nuttx-d8ac0a01d815d109e177b6f752806f8512c4319e.tar.gz
px4-nuttx-d8ac0a01d815d109e177b6f752806f8512c4319e.tar.bz2
px4-nuttx-d8ac0a01d815d109e177b6f752806f8512c4319e.zip
Fixes for serial monitor
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2320 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/README.txt2
-rwxr-xr-xnuttx/configs/demo9s12ne64/README.txt27
-rwxr-xr-xnuttx/configs/demo9s12ne64/include/board.h6
-rwxr-xr-xnuttx/configs/demo9s12ne64/ostest/defconfig71
-rwxr-xr-xnuttx/configs/demo9s12ne64/ostest/ld.script2
-rwxr-xr-xnuttx/configs/demo9s12ne64/src/demo9s12ne64.h16
-rwxr-xr-xnuttx/configs/demo9s12ne64/src/up_boot.c14
-rwxr-xr-xnuttx/configs/demo9s12ne64/src/up_leds.c4
-rwxr-xr-xnuttx/configs/demo9s12ne64/src/up_spi.c24
9 files changed, 77 insertions, 89 deletions
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index 447c05de8..9a74324cb 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -585,7 +585,7 @@ configs/c5471evm
This port is complete, verified, and included in the NuttX release.
configs/demo9s12ne64
- Feescale DMO9S12NE64 board based on the MC9S12NE64 hc12 cpu. This
+ Feescale DMO9S12NE64 board based on the MC9S12NE64 hcs12 cpu. This
port uses the m68hc12 GCC toolchain. STATUS: Under development.
configs/eagle100
diff --git a/nuttx/configs/demo9s12ne64/README.txt b/nuttx/configs/demo9s12ne64/README.txt
index b9581b0ed..7afcb06b1 100755
--- a/nuttx/configs/demo9s12ne64/README.txt
+++ b/nuttx/configs/demo9s12ne64/README.txt
@@ -50,7 +50,7 @@ NuttX buildroot Toolchain
building a Cortex-M3 toolchain for Cygwin under Windows.
-HC12/DEMO9S12NEC64-specific Configuration Options
+HCS12/DEMO9S12NEC64-specific Configuration Options
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
CONFIG_ARCH - Identifies the arch/ subdirectory. This should
@@ -64,7 +64,7 @@ HC12/DEMO9S12NEC64-specific Configuration Options
CONFIG_ARCH_architecture - For use in C code:
- CONFIG_ARCH_HC12=y
+ CONFIG_ARCH_HCS12=y
CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
@@ -112,31 +112,34 @@ HC12/DEMO9S12NEC64-specific Configuration Options
the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
the delay actually is 100 seconds.
- HC12 specific chip initialization
+ HCS12 specific chip initialization
- HC12 specific device driver settings
+ HCS12 specific device driver settings
- CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
+ CONFIG_HCS12_SERIALMON - Indicates that the target systems uses
+ the Freescale serial bootloader.
+
+ CONFIG_SCIO_SERIAL_CONSOLE - selects the SCIO for the
console and ttys0 (default is the UART0).
- CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received.
+ CONFIG_SCIO_RXBUFSIZE - Characters are buffered as received.
This specific the size of the receive buffer
- CONFIG_UARTn_TXBUFSIZE - Characters are buffered before
+ CONFIG_SCIO_TXBUFSIZE - Characters are buffered before
being sent. This specific the size of the transmit buffer
- CONFIG_UARTn_BAUD - The configure BAUD of the UART.
+ CONFIG_SCIO_BAUD - The configure BAUD of the UART.
- CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8.
+ CONFIG_SCIO_BITS - The number of bits. Must be either 7 or 8.
- CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity, 3=mark 1, 4=space 0
+ CONFIG_SCIO_PARTIY - 0=no parity, 1=odd parity, 2=even parity, 3=mark 1, 4=space 0
- CONFIG_UARTn_2STOP - Two stop bits
+ CONFIG_SCIO_2STOP - Two stop bits
Configurations
^^^^^^^^^^^^^^
-Each Freescale HC12 configuration is maintained in a sudirectory and
+Each Freescale HCS12 configuration is maintained in a sudirectory and
can be selected as follow:
cd tools
diff --git a/nuttx/configs/demo9s12ne64/include/board.h b/nuttx/configs/demo9s12ne64/include/board.h
index 0f2ab43a1..68bb15acf 100755
--- a/nuttx/configs/demo9s12ne64/include/board.h
+++ b/nuttx/configs/demo9s12ne64/include/board.h
@@ -87,16 +87,16 @@ extern "C" {
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
- * Name: hc12_boardinitialize
+ * Name: hcs12_boardinitialize
*
* Description:
- * All HC12 architectures must provide the following entry point. This entry point
+ * All HCS12 architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
-EXTERN void hc12_boardinitialize(void);
+EXTERN void hcs12_boardinitialize(void);
/************************************************************************************
* Button support.
diff --git a/nuttx/configs/demo9s12ne64/ostest/defconfig b/nuttx/configs/demo9s12ne64/ostest/defconfig
index 3054b562f..6e2409360 100755
--- a/nuttx/configs/demo9s12ne64/ostest/defconfig
+++ b/nuttx/configs/demo9s12ne64/ostest/defconfig
@@ -71,7 +71,7 @@
#
CONFIG_ARCH=hc
CONFIG_ARCH_HC=y
-CONFIG_ARCH_HC12=y
+CONFIG_ARCH_HCS12=y
CONFIG_ARCH_CHIP=mc9s12ne64
CONFIG_ARCH_CHIP_MCS92S12NEC64=y
CONFIG_ARCH_BOARD=demo9s12ne64
@@ -93,58 +93,27 @@ CONFIG_ARCH_DMA=n
#
# MC9S12NEC64 specific serial device driver settings
#
-# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
-# console and ttys0 (default is the UART1).
-# CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received.
+# CONFIG_HCS12_SERIALMON - Indicates that the target systems uses
+# the Freescale serial bootloader.
+# CONFIG_SCIO_SERIAL_CONSOLE - selects the SCIO for the
+# console and ttys0 (default is the SCIO).
+# CONFIG_SCIO_RXBUFSIZE - Characters are buffered as received.
# This specific the size of the receive buffer
-# CONFIG_UARTn_TXBUFSIZE - Characters are buffered before
+# CONFIG_SCIO_TXBUFSIZE - Characters are buffered before
# being sent. This specific the size of the transmit buffer
-# CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be
-# CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8.
-# CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
-# CONFIG_UARTn_2STOP - Two stop bits
-#
-CONFIG_UART1_SERIAL_CONSOLE=y
-CONFIG_UART2_SERIAL_CONSOLE=n
-CONFIG_UART3_SERIAL_CONSOLE=n
-CONFIG_UART4_SERIAL_CONSOLE=n
-CONFIG_UART5_SERIAL_CONSOLE=n
-
-CONFIG_UART1_TXBUFSIZE=256
-CONFIG_UART2_TXBUFSIZE=256
-CONFIG_UART3_TXBUFSIZE=256
-CONFIG_UART4_TXBUFSIZE=256
-CONFIG_UART5_TXBUFSIZE=256
-
-CONFIG_UART1_RXBUFSIZE=256
-CONFIG_UART2_RXBUFSIZE=256
-CONFIG_UART3_RXBUFSIZE=256
-CONFIG_UART4_RXBUFSIZE=256
-CONFIG_UART5_RXBUFSIZE=256
-
-CONFIG_UART1_BAUD=115200
-CONFIG_UART2_BAUD=115200
-CONFIG_UART3_BAUD=115200
-CONFIG_UART4_BAUD=115200
-CONFIG_UART5_BAUD=115200
-
-CONFIG_UART1_BITS=8
-CONFIG_UART2_BITS=8
-CONFIG_UART3_BITS=8
-CONFIG_UART4_BITS=8
-CONFIG_UART5_BITS=8
-
-CONFIG_UART1_PARITY=0
-CONFIG_UART2_PARITY=0
-CONFIG_UART3_PARITY=0
-CONFIG_UART4_PARITY=0
-CONFIG_UART5_PARITY=0
-
-CONFIG_UART1_2STOP=0
-CONFIG_UART2_2STOP=0
-CONFIG_UART3_2STOP=0
-CONFIG_UART4_2STOP=0
-CONFIG_UART5_2STOP=0
+# CONFIG_SCIO_BAUD - The configure BAUD of the UART. Must be
+# CONFIG_SCIO_BITS - The number of bits. Must be either 7 or 8.
+# CONFIG_SCIO_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+# CONFIG_SCIO_2STOP - Two stop bits
+#
+CONFIG_HCS12_SERIALMON=y
+CONFIG_SCIO_SERIAL_CONSOLE=y
+CONFIG_SCIO_TXBUFSIZE=256
+CONFIG_SCIO_RXBUFSIZE=256
+CONFIG_SCIO_BAUD=115200
+CONFIG_SCIO_BITS=8
+CONFIG_SCIO_PARITY=0
+CONFIG_SCIO_2STOP=0
#
# MC9S12NEC64 specific SSI device driver settings
diff --git a/nuttx/configs/demo9s12ne64/ostest/ld.script b/nuttx/configs/demo9s12ne64/ostest/ld.script
index e6fa37686..4c7c6ed32 100755
--- a/nuttx/configs/demo9s12ne64/ostest/ld.script
+++ b/nuttx/configs/demo9s12ne64/ostest/ld.script
@@ -43,7 +43,7 @@ MEMORY
sram (rwx) : ORIGIN = 0x3800, LENGTH = 8K
}
-OUTPUT_ARCH(m68hc12)
+OUTPUT_ARCH(m68hcs12)
ENTRY(_stext)
SECTIONS
{
diff --git a/nuttx/configs/demo9s12ne64/src/demo9s12ne64.h b/nuttx/configs/demo9s12ne64/src/demo9s12ne64.h
index 9f39d43b6..6d6589e1e 100755
--- a/nuttx/configs/demo9s12ne64/src/demo9s12ne64.h
+++ b/nuttx/configs/demo9s12ne64/src/demo9s12ne64.h
@@ -65,14 +65,26 @@
* Public Functions
************************************************************************************/
/************************************************************************************
- * Name: hc12_spiinitialize
+ * Name: up_ledinit
+ *
+ * Description:
+ * Configure and initialize on-board LEDs
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+extern void up_ledinit(void);
+#endif
+
+/************************************************************************************
+ * Name: hcs12_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the STM3210E-EVAL board.
*
************************************************************************************/
-extern void weak_function hc12_spiinitialize(void);
+extern void weak_function hcs12_spiinitialize(void);
#endif /* __ASSEMBLY__ */
diff --git a/nuttx/configs/demo9s12ne64/src/up_boot.c b/nuttx/configs/demo9s12ne64/src/up_boot.c
index 82ce52c41..6b5c68886 100755
--- a/nuttx/configs/demo9s12ne64/src/up_boot.c
+++ b/nuttx/configs/demo9s12ne64/src/up_boot.c
@@ -60,25 +60,25 @@
************************************************************************************/
/************************************************************************************
- * Name: hc12_boardinitialize
+ * Name: hcs12_boardinitialize
*
* Description:
- * All HC12 architectures must provide the following entry point. This entry point
+ * All INCLUDE_HCS12_ARCH architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
-void hc12_boardinitialize(void)
+void hcs12_boardinitialize(void)
{
/* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
- * hc12_spiinitialize() has been brought into the link.
+ * hcs12_spiinitialize() has been brought into the link.
*/
-#if defined(CONFIG_HC12_SPI)
- if (hc12_spiinitialize)
+#if defined(CONFIG_INCLUDE_HCS12_ARCH_SPI)
+ if (hcs12_spiinitialize)
{
- hc12_spiinitialize();
+ hcs12_spiinitialize();
}
#endif
diff --git a/nuttx/configs/demo9s12ne64/src/up_leds.c b/nuttx/configs/demo9s12ne64/src/up_leds.c
index 544284127..d7bc586b6 100755
--- a/nuttx/configs/demo9s12ne64/src/up_leds.c
+++ b/nuttx/configs/demo9s12ne64/src/up_leds.c
@@ -79,6 +79,10 @@
/****************************************************************************
* Name: up_ledinit
+ *
+ * Description:
+ * Configure and initialize on-board LEDs
+ *
****************************************************************************/
#ifdef CONFIG_ARCH_LEDS
diff --git a/nuttx/configs/demo9s12ne64/src/up_spi.c b/nuttx/configs/demo9s12ne64/src/up_spi.c
index 944320f48..12dc0a7a8 100755
--- a/nuttx/configs/demo9s12ne64/src/up_spi.c
+++ b/nuttx/configs/demo9s12ne64/src/up_spi.c
@@ -48,7 +48,7 @@
#include "demo9s12ne64.h"
-#if defined(CONFIG_HC12_SPI)
+#if defined(CONFIG_HCS12_SPI)
/************************************************************************************
* Definitions
@@ -81,31 +81,31 @@
************************************************************************************/
/************************************************************************************
- * Name: hc12_spiinitialize
+ * Name: hcs12_spiinitialize
*
* Description:
- * Called to configure SPI chip select GPIO pins for the HC1210E-EVAL board.
+ * Called to configure SPI chip select GPIO pins for the DEMO9S12NE64 board.
*
************************************************************************************/
-void weak_function hc12_spiinitialize(void)
+void weak_function hcs12_spiinitialize(void)
{
}
/****************************************************************************
- * Name: hc12_spiselect and hc12_spistatus
+ * Name: hcs12_spiselect and hcs12_spistatus
*
* Description:
- * The external functions, hc12_spiselect and hc12_spistatus must be
+ * The external functions, hcs12_spiselect and hcs12_spistatus must be
* provided by board-specific logic. They are implementations of the select
* and status methods of the SPI interface defined by struct spi_ops_s (see
* include/nuttx/spi.h). All other methods (including up_spiinitialize())
- * are provided by common HC12 logic. To use this common SPI logic on your
+ * are provided by common HCS12 logic. To use this common SPI logic on your
* board:
*
- * 1. Provide logic in hc12_boardinitialize() to configure SPI chip select
+ * 1. Provide logic in hcs12_boardinitialize() to configure SPI chip select
* pins.
- * 2. Provide hc12_spiselect() and hc12_spistatus() functions in your
+ * 2. Provide hcs12_spiselect() and hcs12_spistatus() functions in your
* board-specific logic. These functions will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 3. Add a calls to up_spiinitialize() in your low level application
@@ -117,13 +117,13 @@ void weak_function hc12_spiinitialize(void)
*
****************************************************************************/
-void hc12_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean selected)
+void hcs12_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean selected)
{
}
-ubyte hc12_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+ubyte hcs12_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return SPI_STATUS_PRESENT;
}
-#endif /* CONFIG_HC12_SPI */
+#endif /* CONFIG_HCS12_SPI */