From 5435b6d5327bc257c9ee1df956e66c74df82bcc8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 15 Aug 2011 14:55:36 +0000 Subject: Finishes very basic Kinetis port git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3882 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/kinetis/kinetis_config.h | 35 ++++++ nuttx/arch/arm/src/kinetis/kinetis_lowputc.c | 78 ++++++++----- nuttx/arch/arm/src/kinetis/kinetis_serial.c | 161 ++++++++++++++++++++------- nuttx/arch/arm/src/kinetis/kinetis_tsi.h | 21 +--- nuttx/configs/README.txt | 8 ++ nuttx/configs/kwikstik-k40/README.txt | 9 ++ 6 files changed, 231 insertions(+), 81 deletions(-) (limited to 'nuttx') diff --git a/nuttx/arch/arm/src/kinetis/kinetis_config.h b/nuttx/arch/arm/src/kinetis/kinetis_config.h index bad3fbf3c..229455f9e 100644 --- a/nuttx/arch/arm/src/kinetis/kinetis_config.h +++ b/nuttx/arch/arm/src/kinetis/kinetis_config.h @@ -149,6 +149,41 @@ # undef CONFIG_UART4_FLOWCONTROL # undef CONFIG_UART5_FLOWCONTROL +/* UART FIFO support is not fully implemented. + * + * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs + * (1-deep). There appears to be no way to know when the FIFO is not + * full (other than reading the FIFO length and comparing the FIFO count). + * Hence, the FIFOs are not used in this implementation and, as a result + * TDRE indeed mean that the single output buffer is available. + * + * Performance on UART0 could be improved by enabling the FIFO and by + * redesigning all of the FIFO status logic. + */ + +#undef CONFIG_KINETIS_UARTFIFOS + +/* Default Priorities */ + +#ifndef CONFIG_KINETIS_UART0PRIO +# define CONFIG_KINETIS_UART1PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_KINETIS_UART1PRIO +# define CONFIG_KINETIS_UART2PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_KINETIS_UART2PRIO +# define CONFIG_KINETIS_UART3PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_KINETIS_UART3PRIO +# define CONFIG_KINETIS_UART4PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_KINETIS_UART4PRIO +# define CONFIG_KINETIS_UART5PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_KINETIS_UART5PRIO +# define CONFIG_KINETIS_UART6PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif + /************************************************************************************ * Public Types ************************************************************************************/ diff --git a/nuttx/arch/arm/src/kinetis/kinetis_lowputc.c b/nuttx/arch/arm/src/kinetis/kinetis_lowputc.c index 34624a600..6d24f2013 100644 --- a/nuttx/arch/arm/src/kinetis/kinetis_lowputc.c +++ b/nuttx/arch/arm/src/kinetis/kinetis_lowputc.c @@ -115,7 +115,13 @@ * Private Variables **************************************************************************/ +/* This array maps an encoded FIFO depth (index) to the actual size of the + * FIFO (indexed value). NOTE: That there is no 8th value. + */ + +#ifdef CONFIG_KINETIS_UARTFIFOS static uint8_t g_sizemap[8] = {1, 4, 8, 16, 32, 64, 128, 0}; +#endif /************************************************************************** * Private Functions @@ -136,14 +142,32 @@ static uint8_t g_sizemap[8] = {1, 4, 8, 16, 32, 64, 128, 0}; void up_lowputc(char ch) { #if defined HAVE_UART_DEVICE && defined HAVE_SERIAL_CONSOLE +#ifdef CONFIG_KINETIS_UARTFIFOS + /* Wait until there is space in the TX FIFO: Read the number of bytes + * currently in the FIFO and compare that to the size of the FIFO. If + * there are fewer bytes in the FIFO than the size of the FIFO, then we + * are able to transmit. + */ - /* Wait until the transmit data register is "empty." This state depends - * on the TX watermark setting and does not mean that the transmit buffer - * is really empty. It just means that we can now add another character - * to the transmit buffer +# error "Missing logic" +#else + /* Wait until the transmit data register is "empty" (TDRE). This state + * depends on the TX watermark setting and may not mean that the transmit + * buffer is truly empty. It just means that we can now add another + * characterto the transmit buffer without exceeding the watermark. + * + * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs + * (1-deep). There appears to be no way to know when the FIFO is not + * full (other than reading the FIFO length and comparing the FIFO count). + * Hence, the FIFOs are not used in this implementation and, as a result + * TDRE indeed mean that the single output buffer is available. + * + * Performance on UART0 could be improved by enabling the FIFO and by + * redesigning all of the FIFO status logic. */ while ((getreg8(CONSOLE_BASE+KINETIS_UART_S1_OFFSET) & UART_S1_TDRE) == 0); +#endif /* Then write the character to the UART data register */ @@ -159,26 +183,6 @@ void up_lowputc(char ch) * console. Its purpose is to get the console output availabe as soon * as possible. * - * The UART0/1/2/3 peripherals are configured using the following registers: - * 1. Power: In the PCONP register, set bits PCUART0/1/2/3. - * On reset, UART0 and UART 1 are enabled (PCUART0 = 1 and PCUART1 = 1) - * and UART2/3 are disabled (PCUART1 = 0 and PCUART3 = 0). - * 2. Peripheral clock: In the PCLKSEL0 register, select PCLK_UART0 and - * PCLK_UART1; in the PCLKSEL1 register, select PCLK_UART2 and PCLK_UART3. - * 3. Baud rate: In the LCR register, set bit DLAB = 1. This enables access - * to registers DLL and DLM for setting the baud rate. Also, if needed, - * set the fractional baud rate in the fractional divider - * 4. UART FIFO: Use bit FIFO enable (bit 0) in FCR register to - * enable FIFO. - * 5. Pins: Select UART pins through the PINSEL registers and pin modes - * through the PINMODE registers. UART receive pins should not have - * pull-down resistors enabled. - * 6. Interrupts: To enable UART interrupts set bit DLAB = 0 in the LCRF - * register. This enables access to IER. Interrupts are enabled - * in the NVIC using the appropriate Interrupt Set Enable register. - * 7. DMA: UART transmit and receive functions can operate with the - * GPDMA controller. - * **************************************************************************/ void kinetis_lowsetup(void) @@ -302,7 +306,9 @@ void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t brfa; uint32_t tmp; uint8_t regval; +#ifdef CONFIG_KINETIS_UARTFIFOS unsigned int depth; +#endif /* Disable the transmitter and receiver throughout the reconfiguration */ @@ -387,10 +393,19 @@ void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, regval |= ((uint8_t)brfa << UART_C4_BRFA_SHIFT) & UART_C4_BRFA_MASK; putreg8(regval, uart_base+KINETIS_UART_C4_OFFSET); - /* Set the FIFO watermarks */ + /* Set the FIFO watermarks. + * + * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs + * (1-deep). There appears to be no way to know when the FIFO is not + * full (other than reading the FIFO length and comparing the FIFO count). + * Hence, the FIFOs are not used in this implementation and, as a result + * TDRE indeed mean that the single output buffer is available. + * + * Performance on UART0 could be improved by enabling the FIFO and by + * redesigning all of the FIFO status logic. + */ - regval = getreg8(uart_base+KINETIS_UART_PFIFO_OFFSET); - +#ifdef CONFIG_KINETIS_UARTFIFOS depth = g_sizemap[(regval & UART_PFIFO_RXFIFOSIZE_MASK) >> UART_PFIFO_RXFIFOSIZE_SHIFT]; if (depth > 1) { @@ -408,8 +423,15 @@ void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, /* Enable RX and TX FIFOs */ putreg8(UART_PFIFO_RXFE | UART_PFIFO_TXFE, uart_base+KINETIS_UART_PFIFO_OFFSET); +#else + /* Set the watermarks to zero and disable the FIFOs */ + + putreg8(0, uart_base+KINETIS_UART5_RWFIFO); + putreg8(0, uart_base+KINETIS_UART5_TWFIFO); + putreg8(0, uart_base+KINETIS_UART_PFIFO_OFFSET); +#endif - /* Now we can re-enable the transmitter and receiver */ + /* Now we can (re-)enable the transmitter and receiver */ regval = getreg8(uart_base+KINETIS_UART_C2_OFFSET); regval |= (UART_C2_RE | UART_C2_TE); diff --git a/nuttx/arch/arm/src/kinetis/kinetis_serial.c b/nuttx/arch/arm/src/kinetis/kinetis_serial.c index 808ba6902..e4988e546 100644 --- a/nuttx/arch/arm/src/kinetis/kinetis_serial.c +++ b/nuttx/arch/arm/src/kinetis/kinetis_serial.c @@ -261,7 +261,9 @@ static bool up_rxavailable(struct uart_dev_s *dev); static void up_send(struct uart_dev_s *dev, int ch); static void up_txint(struct uart_dev_s *dev, bool enable); static bool up_txready(struct uart_dev_s *dev); +#ifdef CONFIG_KINETIS_UARTFIFOS static bool up_txempty(struct uart_dev_s *dev); +#endif /**************************************************************************** * Private Variables @@ -280,7 +282,11 @@ struct uart_ops_s g_uart_ops = .send = up_send, .txint = up_txint, .txready = up_txready, +#ifdef CONFIG_KINETIS_UARTFIFOS .txempty = up_txempty, +#else + .txempty = up_txready, +#endif }; /* I/O buffers */ @@ -731,6 +737,8 @@ static int up_interrupte(int irq, void *context) { struct uart_dev_s *dev = NULL; struct up_dev_s *priv; + uint8_t s1; + uint8_t regval; #ifdef CONFIG_KINETIS_UART0 if (g_uart0priv.irq == irqe) @@ -780,16 +788,22 @@ static int up_interrupte(int irq, void *context) priv = (struct up_dev_s*)dev->priv; DEBUGASSERT(priv); - /* Handle error interrupts. */ -#warning "Missing logic" - - /* Clear the pending error interrupt */ - - up_clrpend_irq(priv->irqe); // Necessary? + /* Handle error interrupts. This interrupt may be caused by: + * + * FE: Framing error. To clear FE, read S1 with FE set and then read the + * UART data register (D). + * NF: Noise flag. To clear NF, read S1 and then read the UART data + * register (D). + * PF: Parity error flag. To clear PF, read S1 and then read the UART data + * register (D). + */ + regval = up_serialin(priv, KINETIS_UART_S1_OFFSET + lldbg("S1: %02x\n", regval); + regval = up_serialin(priv, KINETIS_UART_D_OFFSET return OK; } -#endif +#endif /* CONFIG_DEBUG */ /**************************************************************************** * Name: up_interrupts @@ -809,11 +823,15 @@ static int up_interrupts(int irq, void *context) struct up_dev_s *priv; int passes; unsigned int size; +#ifdef CONFIG_KINETIS_UARTFIFOS unsigned int count; +#else + uint8_t s1; +#endif bool handled; #ifdef CONFIG_KINETIS_UART0 - if (g_uart0priv.irq == irqe) + if (g_uart0priv.irq == irqs) { dev = &g_uart0port; } @@ -869,35 +887,66 @@ static int up_interrupts(int irq, void *context) { handled = false; - /* Check for a pending status interrupt */ + /* Read status register 1 */ - if (up_pending_irq(priv->irqs)) - { - /* Clear the pending status interrupt */ +#ifndef CONFIG_KINETIS_UARTFIFOS + s1 = up_serialin(priv, KINETIS_UART_S1_OFFSET); +#endif - up_clrpend_irq(priv->irqs); // Necessary? + /* Handle incoming, receive bytes */ - /* Handle incoming, receive bytes */ +#ifdef CONFIG_KINETIS_UARTFIFOS + /* Check the count of bytes in the RX FIFO */ - count = up_serialin(priv, KINETIS_UART_RCFIFO_OFFSET); - if (count > 0) - { - /* Process incoming bytes */ + count = up_serialin(priv, KINETIS_UART_RCFIFO_OFFSET); + if (count > 0) +#else + /* Check if the receive data register is full (RDRF). NOTE: If + * FIFOS are enabled, this does not mean that the the FIFO is full, + * rather, it means that the the number of bytes in the RX FIFO has + * exceeded the watermark setting. There may actually be RX data + * available! + * + * The RDRF status indication is cleared when the data is read from + * the RX data register. + */ - uart_recvchars(dev); - handled = true; - } + if ((s1 & UART_S1_RDRF) != 0) +#endif + { + /* Process incoming bytes */ + + uart_recvchars(dev); + handled = true; + } - /* Handle outgoing, transmit bytes */ + /* Handle outgoing, transmit bytes */ - count = up_serialin(priv, KINETIS_UART_TCFIFO_OFFSET); - #warning "Missing logic" - { - /* Process outgoing bytes */ +#ifdef CONFIG_KINETIS_UARTFIFOS + /* Read the number of bytes currently in the FIFO and compare that to + * the size of the FIFO. If there are fewer bytes in the FIFO than + * the size of the FIFO, then we are able to transmit. + */ - uart_xmitchars(dev); - handled = true; - } +# error "Missing logic" +#else + /* Check if the transmit data register is "empty." NOTE: If FIFOS + * are enabled, this does not mean that the the FIFO is empty, rather, + * it means that the the number of bytes in the TX FIFO is below the + * watermark setting. There could actually be space for additional TX + * data. + * + * The TDRE status indication is cleared when the data is written to + * the TX data register. + */ + + if ((s1 & UART_S1_TDRE) != 0) +#endif + { + /* Process outgoing bytes */ + + uart_xmitchars(dev); + handled = true; } } @@ -956,15 +1005,30 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) static int up_receive(struct uart_dev_s *dev, uint32_t *status) { struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + uint8_t s1; + + /* Get error status information: + * + * FE: Framing error. To clear FE, read S1 with FE set and then read + * read UART data register (D). + * NF: Noise flag. To clear NF, read S1 and then read the UART data + * register (D). + * PF: Parity error flag. To clear PF, read S1 and then read the UART + * data register (D). + */ + + s1 = up_serialin(priv, KINETIS_UART_S1_OFFSET); /* Return status information */ if (status) { - *status = 0; /* We are not yet tracking serial errors */ + *status = (uint32_t)s1; } - /* Then return the actual received byte */ + /* Then return the actual received byte. Reading S1 then D clears all + * RX errors. + */ return (int)up_serialin(priv, KINETIS_UART_D_OFFSET); } @@ -981,10 +1045,8 @@ static void up_rxint(struct uart_dev_s *dev, bool enable) { struct up_dev_s *priv = (struct up_dev_s*)dev->priv; irqstate_t flags; - uint8_t ie; flags = irqsave(); - ie = priv->ie; if (enable) { /* Receive an interrupt when their is anything in the Rx data register (or an Rx @@ -998,8 +1060,8 @@ static void up_rxint(struct uart_dev_s *dev, bool enable) } else { -#warning "Revisit: How are errors enabled? What is the IDLE receive interrupt. I think I need it" #ifdef CONFIG_DEBUG +# warning "Revisit: How are errors enabled?" priv->ie |= UART_C2_RIE; #else priv->ie |= UART_C2_RIE; @@ -1007,7 +1069,6 @@ static void up_rxint(struct uart_dev_s *dev, bool enable) up_setuartint(priv); } - priv->ie = ie; irqrestore(flags); } @@ -1022,12 +1083,23 @@ static void up_rxint(struct uart_dev_s *dev, bool enable) static bool up_rxavailable(struct uart_dev_s *dev) { struct up_dev_s *priv = (struct up_dev_s*)dev->priv; +#ifdef CONFIG_KINETIS_UARTFIFOS unsigned int count; /* Return true if there are any bytes in the RX FIFO */ count = up_serialin(priv, KINETIS_UART_RCFIFO_OFFSET); return count > 0; +#else + /* Return true if the receive data register is full (RDRF). NOTE: If + * FIFOS are enabled, this does not mean that the the FIFO is full, + * rather, it means that the the number of bytes in the RX FIFO has + * exceeded the watermark setting. There may actually be RX data + * available! + */ + + return (up_serialin(priv, KINETIS_UART_S1_OFFSET) & UART_S1_RDRF) != 0; +#endif } /**************************************************************************** @@ -1096,12 +1168,23 @@ static bool up_txready(struct uart_dev_s *dev) { struct up_dev_s *priv = (struct up_dev_s*)dev->priv; - /* Return true if the transmit data register is "empty." This state - * depends on the TX watermark setting and does not mean that the transmit - * buffer is really empty. +#ifdef CONFIG_KINETIS_UARTFIFOS + /* Read the number of bytes currently in the FIFO and compare that to the + * size of the FIFO. If there are fewer bytes in the FIFO than the size + * of the FIFO, then we are able to transmit. + */ + +# error "Missing logic" +#else + /* Return true if the transmit data register is "empty." NOTE: If + * FIFOS are enabled, this does not mean that the the FIFO is empty, + * rather, it means that the the number of bytes in the TX FIFO is + * below the watermark setting. There may actually be space for + * additional TX data. */ return (up_serialin(priv, KINETIS_UART_S1_OFFSET) & UART_S1_TDRE) != 0; +#endif } /**************************************************************************** @@ -1112,6 +1195,7 @@ static bool up_txready(struct uart_dev_s *dev) * ****************************************************************************/ +#ifdef CONFIG_KINETIS_UARTFIFOS static bool up_txempty(struct uart_dev_s *dev) { struct up_dev_s *priv = (struct up_dev_s*)dev->priv; @@ -1120,6 +1204,7 @@ static bool up_txempty(struct uart_dev_s *dev) return (up_serialin(priv, KINETIS_UART_SFIFO_OFFSET) & UART_SFIFO_TXEMPT) != 0; } +#endif /**************************************************************************** * Public Functions diff --git a/nuttx/arch/arm/src/kinetis/kinetis_tsi.h b/nuttx/arch/arm/src/kinetis/kinetis_tsi.h index a60ab1e0f..df96a0d8c 100644 --- a/nuttx/arch/arm/src/kinetis/kinetis_tsi.h +++ b/nuttx/arch/arm/src/kinetis/kinetis_tsi.h @@ -280,23 +280,14 @@ #define TSI_STATUS_ERROF15 (1 << 31) /* Bit 31: TouchSensing Error Flag 15 */ /* Counter Register n. Note: These values are reversed in the K40 and K60 - * documentation. I bet one is right and the other is wrong (I'd bet on the K40 - * document). + * documentation. In the K40/K60 header files, however, CNTN1 is always the + * the field in the most significant bits. Let's go with that. */ -#ifdef KINETIS_K40 -# define TSI_CNTR_CNTN1_SHIFT (0) /* Bits 0-15: TouchSensing channel n-1 16-bit counter value */ -# define TSI_CNTR_CNTN1_MASK (0xffff << TSI_CNTR_CNTN1_SHIFT) -# define TSI_CNTR_CNTN_SHIFT (16) /* Bits 16-31: TouchSensing channel n 16-bit counter value */ -# define TSI_CNTR_CNTN_MASK (0xffff << TSI_CNTR_CNTN_SHIFT) -#endif -#ifdef KINETIS_K60 -# warning "Revisit" -# define TSI_CNTR_CNTN_SHIFT (0) /* Bits 0-15: TouchSensing channel n 16-bit counter value */ -# define TSI_CNTR_CNTN_MASK (0xffff << TSI_CNTR_CNTN_SHIFT) -# define TSI_CNTR_CNTN1_SHIFT (16) /* Bits 16-31: TouchSensing channel n-1 16-bit counter value */ -# define TSI_CNTR_CNTN1_MASK (0xffff << TSI_CNTR_CNTN1_SHIFT) -#endif +#define TSI_CNTR_CNTN_SHIFT (0) /* Bits 0-15: TouchSensing channel n 16-bit counter value */ +#define TSI_CNTR_CNTN_MASK (0xffff << TSI_CNTR_CNTN_SHIFT) +#define TSI_CNTR_CNTN1_SHIFT (16) /* Bits 16-31: TouchSensing channel n-1 16-bit counter value */ +#define TSI_CNTR_CNTN1_MASK (0xffff << TSI_CNTR_CNTN1_SHIFT) /* Channel n threshold register */ diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index d42c92fb8..d90d4c655 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -1127,6 +1127,10 @@ configs/ez80f0910200zco development kit, eZ80F091 part, and the Zilog ZDS-II Windows command line tools. The development environment is Cygwin under WinXP. +configs/kwikstik-k40. + Kinetis K40 Cortex-M4 MCU. This port uses the FreeScale KwikStik-K40 + development board. + configs/lm3s6965-ek Stellaris LM3S6965 Evaluation Kit. This board is based on the an ARM Cortex-M3 MCU, the Luminary/TI LM3S6965. This OS is built with the @@ -1269,6 +1273,10 @@ configs/teensy developed by http://pjrc.com/teensy/. The Teensy++ 2.0 is based on an Atmel AT90USB1286 MCU. +configs/twr-k60n512 + Kinetis K60 Cortex-M4 MCU. This port uses the FreeScale TWR-K60N512 + development board. + configs/us7032evb1 This is a port of the Hitachi SH-1 on the Hitachi SH-1/US7032EVB1 board. STATUS: Work has just began on this port. diff --git a/nuttx/configs/kwikstik-k40/README.txt b/nuttx/configs/kwikstik-k40/README.txt index e8f3865f7..55703570b 100644 --- a/nuttx/configs/kwikstik-k40/README.txt +++ b/nuttx/configs/kwikstik-k40/README.txt @@ -298,6 +298,15 @@ KwikStik-K40-specific Configuration Options CONFIG_KINETIS_PIT -- Support Programmable Interval Timers CONFIG_ARMV7M_MPU -- Support the MPU + Kinetis interrupt prioritys (Default is the mid priority) + + CONFIG_KINETIS_UART0PRIO + CONFIG_KINETIS_UART1PRIO + CONFIG_KINETIS_UART2PRIO + CONFIG_KINETIS_UART3PRIO + CONFIG_KINETIS_UART4PRIO + CONFIG_KINETIS_UART5PRIO + Kinetis K40 specific device driver settings CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn (n=0..5) for the -- cgit v1.2.3