summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr/src/at90usb
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-06-11 01:40:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-06-11 01:40:25 +0000
commit6824157a582c0ba02a97f460be9fd3bd94c1e485 (patch)
tree7b26fdaa681f6b209823f90d05f3f2c6c4bec757 /nuttx/arch/avr/src/at90usb
parent4a9833d22ceba607e7b1584a0aa0dfd2a6d0e06a (diff)
downloadpx4-nuttx-6824157a582c0ba02a97f460be9fd3bd94c1e485.tar.gz
px4-nuttx-6824157a582c0ba02a97f460be9fd3bd94c1e485.tar.bz2
px4-nuttx-6824157a582c0ba02a97f460be9fd3bd94c1e485.zip
More serial driver stuff for AVR
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3694 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/avr/src/at90usb')
-rw-r--r--nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c96
-rw-r--r--nuttx/arch/avr/src/at90usb/at90usb_serial.c21
2 files changed, 80 insertions, 37 deletions
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c b/nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c
index 3ec1b9332..648f193df 100644
--- a/nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c
+++ b/nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c
@@ -45,6 +45,7 @@
#include <arch/irq.h>
#include <arch/board/board.h>
+#include <avr/io.h>
#include "up_arch.h"
#include "up_internal.h"
@@ -55,25 +56,13 @@
* Private Definitions
******************************************************************************/
-/* Select USART parameters for the selected console -- there is only USART1 */
-
-#if defined(CONFIG_USART1_SERIAL_CONSOLE)
-# define AVR_CONSOLE_BASE AVR_USART1_BASE
-# define AVR_CONSOLE_BAUD CONFIG_USART1_BAUD
-# define AVR_CONSOLE_BITS CONFIG_USART1_BITS
-# define AVR_CONSOLE_PARITY CONFIG_USART1_PARITY
-# define AVR_CONSOLE_2STOP CONFIG_USART1_2STOP
-#else
-# error "No CONFIG_USARTn_SERIAL_CONSOLE Setting"
-#endif
-
/* Baud rate settings for normal and double speed settings */
#define AVR_NORMAL_UBRR1 \
- (((BOARD_CPU_CLOCK / 16) + (CONFIG_USART1_BAUD / 2)) / (CONFIG_USART1_BAUD)) - 1)
+ ((((BOARD_CPU_CLOCK / 16) + (CONFIG_USART1_BAUD / 2)) / (CONFIG_USART1_BAUD)) - 1)
#define AVR_DBLSPEED_UBRR1 \
- (((BOARD_CPU_CLOCK / 8) + (CONFIG_USART1_BAUD / 2)) / (CONFIG_USART1_BAUD)) - 1)
+ ((((BOARD_CPU_CLOCK / 8) + (CONFIG_USART1_BAUD / 2)) / (CONFIG_USART1_BAUD)) - 1)
/* Select normal or double speed baud settings. This is a trade-off between the
* sampling rate and the accuracy of the divisor for high baud rates.
@@ -89,34 +78,34 @@
* AVR_DBLSPEED_UBRR1 = 104 (rounded), actual baud = 9615
*/
-#undef HAVE_DOUBLE_SPEED
+#undef UART1_DOUBLE_SPEED
#if BOARD_CPU_CLOCK <= 4000000
# if CONFIG_USART1_BAUD <= 9600
# define AVR_UBRR1 AVR_NORMAL_UBRR1
# else
# define AVR_UBRR1 AVR_DBLSPEED_UBRR1
-# define HAVE_DOUBLE_SPEED 1
+# define UART1_DOUBLE_SPEED 1
# endif
#elif BOARD_CPU_CLOCK <= 8000000
# if CONFIG_USART1_BAUD <= 19200
# define AVR_UBRR1 AVR_NORMAL_UBRR1
# else
# define AVR_UBRR1 AVR_DBLSPEED_UBRR1
-# define HAVE_DOUBLE_SPEED 1
+# define UART1_DOUBLE_SPEED 1
# endif
#elif BOARD_CPU_CLOCK <= 12000000
# if CONFIG_USART1_BAUD <= 28800
# define AVR_UBRR1 AVR_NORMAL_UBRR1
# else
# define AVR_UBRR1 AVR_DBLSPEED_UBRR1
-# define HAVE_DOUBLE_SPEED 1
+# define UART1_DOUBLE_SPEED 1
# endif
#else
# if CONFIG_USART1_BAUD <= 38400
# define AVR_UBRR1 AVR_NORMAL_UBRR1
# else
# define AVR_UBRR1 AVR_DBLSPEED_UBRR1
-# define HAVE_DOUBLE_SPEED 1
+# define UART1_DOUBLE_SPEED 1
# endif
#endif
@@ -155,7 +144,14 @@
#ifdef HAVE_USART_DEVICE
void usart1_reset(void)
{
-# warning "Missing Logic"
+ UCSR1A = 0;
+ UCSR1B = 0;
+ UCSR1C = 0;
+
+ DDRD &= ~(1 << 3);
+ PORTD &= ~(1 << 2);
+
+ UBRR1 = 0;
}
#endif
@@ -170,7 +166,62 @@ void usart1_reset(void)
#ifdef HAVE_USART_DEVICE
void usart1_configure(void)
{
-# warning "Missing Logic"
+ uint8_t ucsr1b;
+ uint8_t ucsr1c;
+
+ /* Select normal or double speed. */
+
+#ifdef UART1_DOUBLE_SPEED
+ UCSR1A = (1 << U2X1);
+#else
+ UCSR1A = 0;
+#endif
+
+ /* Select baud, parity, nubmer of bits, stop bits, etc. */
+
+ ucsr1b = ((1 << TXEN1) | (1 << RXEN1));
+ ucsr1c = 0;
+
+ /* Select parity */
+
+#if CONFIG_USART1_PARITY == 1
+ ucsr1c |= (UPM11 | UPM10); /* Odd parity */
+#else
+ ucsr1c |= UPM11; /* Even parity */
+#endif
+
+ /* 1 or 2 stop bits */
+
+#if defined(CONFIG_USART1_2STOP) && CONFIG_USART1_2STOP > 0
+ ucsr1c |= USBS1; /* Two stop bits */
+#endif
+
+ /* Word size */
+
+#if CONFIG_USART1_BITS == 5
+#elif CONFIG_USART1_BITS == 6
+ ucsr1c |= UCSZ10;
+#elif CONFIG_USART1_BITS == 7
+ ucsr1c |= UCSZ11;
+#elif CONFIG_USART1_BITS == 8
+ ucsr1c |= (UCSZ10 | UCSZ11);
+#elif CONFIG_USART1_BITS == 9
+ ucsr1c |= (UCSZ10 | UCSZ11);
+ ucsr1b |= UCSZ12;
+#else
+# error "Unsupported word size"
+#endif
+ UCSR1B = ucsr1b;
+ UCSR1C = ucsr1c;
+
+ /* Configure pin */
+
+ DDRD |= (1 << 3);
+ PORTD |= (1 << 2);
+
+ /* Set the baud rate divisor */
+
+ UBRR1 = AVR_UBRR1;
}
#endif
@@ -202,7 +253,8 @@ void up_consoleinit(void)
void up_lowputc(char ch)
{
#ifdef HAVE_SERIAL_CONSOLE
-# warning "Missing Logic"
+ while ((UCSR1A & (1 << UDRE1)) == 0);
+ UDR1 = ch;
#endif
}
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_serial.c b/nuttx/arch/avr/src/at90usb/at90usb_serial.c
index a774954b4..20974fdc5 100644
--- a/nuttx/arch/avr/src/at90usb/at90usb_serial.c
+++ b/nuttx/arch/avr/src/at90usb/at90usb_serial.c
@@ -52,6 +52,7 @@
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/serial.h>
+#include <avr/io.h>
#include <arch/board/board.h>
@@ -346,23 +347,16 @@ static int usart1_ioctl(struct file *filep, int cmd, unsigned long arg)
static int usart1_receive(struct uart_dev_s *dev, uint32_t *status)
{
- /* Get the Rx byte. The USART Rx interrupt flag is cleared by side effect
- * when reading the received character.
- */
-
-# warning "Missing logic"
-
/* Return status information */
if (status)
{
-# warning "Missing logic"
+ *status = (uint32_t)UCSR1A;
}
/* Then return the actual received byte */
-# warning "Missing logic"
- return 0;
+ return UDR1;
}
/****************************************************************************
@@ -401,8 +395,7 @@ static void usart1_rxint(struct uart_dev_s *dev, bool enable)
static bool usart1_rxavailable(struct uart_dev_s *dev)
{
-# warning "Missing logic"
- return 0;
+ return (UCSR1A & (1 << RXC1)) != 0;
}
/****************************************************************************
@@ -415,8 +408,7 @@ static bool usart1_rxavailable(struct uart_dev_s *dev)
static void usart1_send(struct uart_dev_s *dev, int ch)
{
-# warning "Missing logic"
- return 0;
+ UDR1 = ch;
}
/****************************************************************************
@@ -465,8 +457,7 @@ static void usart1_txint(struct uart_dev_s *dev, bool enable)
static bool usart1_txready(struct uart_dev_s *dev)
{
-# warning "Missing logic"
- return 0;
+ return (UCSR1A & (1 << UDRE1)) != 0;
}
/****************************************************************************