summaryrefslogtreecommitdiff
path: root/nuttx/arch/mips
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-08-14 15:53:19 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-08-14 15:53:19 +0000
commit6e69036ba018c62efcda6d93ded93850841e6f5d (patch)
tree873a42c6903c56542ef2597a0d22686b47c3e9c5 /nuttx/arch/mips
parentfcd51cbc81e18535d3b4221ae6e4cb18bf3623e9 (diff)
downloadpx4-nuttx-6e69036ba018c62efcda6d93ded93850841e6f5d.tar.gz
px4-nuttx-6e69036ba018c62efcda6d93ded93850841e6f5d.tar.bz2
px4-nuttx-6e69036ba018c62efcda6d93ded93850841e6f5d.zip
Add basic Kinetis serial support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3878 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/mips')
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-serial.c42
1 files changed, 16 insertions, 26 deletions
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
index 07ef32e4f..87f027da1 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
@@ -90,12 +90,12 @@
# ifdef CONFIG_PIC32MX_UART2
# define TTYS1_DEV g_uart1port /* UART2 is ttyS1 */
# else
-# undef TTYS1_DEV /* No ttyS1 */
+# undef TTYS1_DEV /* No ttyS1 */
# endif
# elif defined(CONFIG_UART2_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart1port /* UART2 is console */
# define TTYS0_DEV g_uart1port /* UART2 is ttyS0 */
-# undef TTYS1_DEV /* No ttyS1 */
+# undef TTYS1_DEV /* No ttyS1 */
# else
# error "I'm confused... Do we have a serial console or not?"
# endif
@@ -108,11 +108,11 @@
# ifdef CONFIG_PIC32MX_UART2
# define TTYS1_DEV g_uart1port /* UART2 is ttyS1 */
# else
-# undef TTYS1_DEV /* No ttyS1 */
+# undef TTYS1_DEV /* No ttyS1 */
# endif
# elif defined(CONFIG_PIC32MX_UART2)
# define TTYS0_DEV g_uart1port /* UART2 is ttyS0 */
-# undef TTYS1_DEV /* No ttyS1 */
+# undef TTYS1_DEV /* No ttyS1 */
# else
# undef TTYS0_DEV
# undef TTYS0_DEV
@@ -144,7 +144,7 @@ struct up_dev_s
uint8_t irq; /* IRQ associated with this UART (for attachment) */
uint8_t irqe; /* Error IRQ associated with this UART (for enable) */
uint8_t irqrx; /* RX IRQ associated with this UART (for enable) */
- uint8_t irqtx; /* RX IRQ associated with this UART (for enable) */
+ uint8_t irqtx; /* TX IRQ associated with this UART (for enable) */
uint8_t irqprio; /* Interrupt priority */
uint8_t ie; /* Interrupts enabled */
uint8_t parity; /* 0=none, 1=odd, 2=even */
@@ -193,8 +193,8 @@ struct uart_ops_s g_uart_ops =
/* I/O buffers */
#ifdef CONFIG_PIC32MX_UART1
-static char g_uart1rxbuffer[CONFIG_UART2_RXBUFSIZE];
-static char g_uart1txbuffer[CONFIG_UART2_TXBUFSIZE];
+static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE];
+static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
#endif
#ifdef CONFIG_PIC32MX_UART2
static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE];
@@ -207,27 +207,27 @@ static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE];
static struct up_dev_s g_uart1priv =
{
.uartbase = PIC32MX_UART1_K1BASE,
- .baud = CONFIG_UART2_BAUD,
+ .baud = CONFIG_UART1_BAUD,
.irq = PIC32MX_IRQ_U1,
.irqe = PIC32MX_IRQSRC_U1E,
.irqrx = PIC32MX_IRQSRC_U1RX,
.irqtx = PIC32MX_IRQSRC_U1TX,
.irqprio = CONFIG_PIC32MX_UART1PRIO,
- .parity = CONFIG_UART2_PARITY,
- .bits = CONFIG_UART2_BITS,
- .stopbits2 = CONFIG_UART2_2STOP,
+ .parity = CONFIG_UART1_PARITY,
+ .bits = CONFIG_UART1_BITS,
+ .stopbits2 = CONFIG_UART1_2STOP,
};
static uart_dev_t g_uart1port =
{
.recv =
{
- .size = CONFIG_UART2_RXBUFSIZE,
+ .size = CONFIG_UART1_RXBUFSIZE,
.buffer = g_uart1rxbuffer,
},
.xmit =
{
- .size = CONFIG_UART2_TXBUFSIZE,
+ .size = CONFIG_UART1_TXBUFSIZE,
.buffer = g_uart1txbuffer,
},
.ops = &g_uart_ops,
@@ -237,7 +237,7 @@ static uart_dev_t g_uart1port =
/* This describes the state of the AVR32 UART2 port. */
-#ifdef CONFIG_PIC32MX_UART1
+#ifdef CONFIG_PIC32MX_UART2
static struct up_dev_s g_uart2priv =
{
.uartbase = PIC32MX_UART2_K1BASE,
@@ -414,7 +414,7 @@ static void up_detach(struct uart_dev_s *dev)
up_disableuartint(priv, NULL);
- /* Dettach from the interrupt */
+ /* Detach from the interrupt */
irq_detach(priv->irq);
}
@@ -639,17 +639,7 @@ static bool up_rxavailable(struct uart_dev_s *dev)
/* Return true is data is available in the receive data buffer */
-#define UART_STA_URXDA (1 << 0) /* Bit 0: Receive buffer data available */
-#define UART_STA_RIDLE (1 << 4) /* Bit 4: Receiver idle */
-#define (1 << 8) /* Bit 8: */
-#define (1 << 9) /* Bit 9: Transmit buffer full status */
-
- /* Return TRUE if the Transmit shift register is empty */
-
- return (up_serialin(priv, PIC32MX_UART_STA_OFFSET) & UART_STA_TRMT) != 0;
-
-#warning "Missing logic"
- return false;
+ return (up_serialin(priv, PIC32MX_UART_STA_OFFSET) & UART_STA_URXDA) != 0;
}
/****************************************************************************