summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr/src/atmega
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/atmega
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/atmega')
-rw-r--r--nuttx/arch/avr/src/atmega/atmega_lowconsole.c253
-rw-r--r--nuttx/arch/avr/src/atmega/atmega_serial.c41
2 files changed, 244 insertions, 50 deletions
diff --git a/nuttx/arch/avr/src/atmega/atmega_lowconsole.c b/nuttx/arch/avr/src/atmega/atmega_lowconsole.c
index f841c9d78..b318dd608 100644
--- a/nuttx/arch/avr/src/atmega/atmega_lowconsole.c
+++ b/nuttx/arch/avr/src/atmega/atmega_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"
@@ -54,22 +55,110 @@
* Private Definitions
******************************************************************************/
-/* Select USART parameters for the selected console */
-
-#if defined(CONFIG_USART0_SERIAL_CONSOLE)
-# define AVR__CONSOLE_BASE AVR__USART0_BASE
-# define AVR__CONSOLE_BAUD CONFIG_USART0_BAUD
-# define AVR__CONSOLE_BITS CONFIG_USART0_BITS
-# define AVR__CONSOLE_PARITY CONFIG_USART0_PARITY
-# define AVR__CONSOLE_2STOP CONFIG_USART0_2STOP
-#elif 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
+/* USART0 Baud rate settings for normal and double speed settings */
+
+#define AVR_NORMAL_UBRR0 \
+ ((((BOARD_CPU_CLOCK / 16) + (CONFIG_USART0_BAUD / 2)) / (CONFIG_USART0_BAUD)) - 1)
+
+#define AVR_DBLSPEED_UBRR0 \
+ ((((BOARD_CPU_CLOCK / 8) + (CONFIG_USART0_BAUD / 2)) / (CONFIG_USART0_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.
+ *
+ * As examples, consider:
+ *
+ * BOARD_CPU_CLOCK=8MHz and BAUD=115200:
+ * AVR_NORMAL_UBRR1 = 4 (rounded), actual baud = 125,000
+ * AVR_DBLSPEED_UBRR1 = 9 (rounded), actual baud = 111,111
+ *
+ * BOARD_CPU_CLOCK=8MHz and BAUD=9600:
+ * AVR_NORMAL_UBRR1 = 52 (rounded), actual baud = 9615
+ * AVR_DBLSPEED_UBRR1 = 104 (rounded), actual baud = 9615
+ */
+
+#undef UART0_DOUBLE_SPEED
+#if BOARD_CPU_CLOCK <= 4000000
+# if CONFIG_USART0_BAUD <= 9600
+# define AVR_UBRR0 AVR_NORMAL_UBRR0
+# else
+# define AVR_UBRR0 AVR_DBLSPEED_UBRR0
+# define UART0_DOUBLE_SPEED 1
+# endif
+#elif BOARD_CPU_CLOCK <= 8000000
+# if CONFIG_USART0_BAUD <= 19200
+# define AVR_UBRR0 AVR_NORMAL_UBRR0
+# else
+# define AVR_UBRR0 AVR_DBLSPEED_UBRR0
+# define UART0_DOUBLE_SPEED 1
+# endif
+#elif BOARD_CPU_CLOCK <= 12000000
+# if CONFIG_USART0_BAUD <= 28800
+# define AVR_UBRR0 AVR_NORMAL_UBRR0
+# else
+# define AVR_UBRR0 AVR_DBLSPEED_UBRR0
+# define UART0_DOUBLE_SPEED 1
+# endif
#else
-# error "No CONFIG_USARTn_SERIAL_CONSOLE Setting"
+# if CONFIG_USART0_BAUD <= 38400
+# define AVR_UBRR0 AVR_NORMAL_UBRR0
+# else
+# define AVR_UBRR0 AVR_DBLSPEED_UBRR0
+# define UART0_DOUBLE_SPEED 1
+# endif
+#endif
+
+/* USART1 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)
+
+#define AVR_DBLSPEED_UBRR1 \
+ (((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.
+ *
+ * As examples, consider:
+ *
+ * BOARD_CPU_CLOCK=8MHz and BAUD=115200:
+ * AVR_NORMAL_UBRR1 = 4 (rounded), actual baud = 125,000
+ * AVR_DBLSPEED_UBRR1 = 9 (rounded), actual baud = 111,111
+ *
+ * BOARD_CPU_CLOCK=8MHz and BAUD=9600:
+ * AVR_NORMAL_UBRR1 = 52 (rounded), actual baud = 9615
+ * AVR_DBLSPEED_UBRR1 = 104 (rounded), actual baud = 9615
+ */
+
+#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 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 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 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 UART1_DOUBLE_SPEED 1
+# endif
#endif
/******************************************************************************
@@ -107,14 +196,27 @@
#ifdef CONFIG_ATMEGA_USART0
void usart0_reset(void)
{
+ UCSR0A = 0;
+ UCSR0B = 0;
+ UCSR0C = 0;
+
# warning "Missing logic"
+
+ UBRR0 = 0;
}
#endif
#ifdef CONFIG_ATMEGA_USART1
void usart1_reset(void)
{
-# warning "Missing logic"
+ UCSR1A = 0;
+ UCSR1B = 0;
+ UCSR1C = 0;
+
+ DDRD &= ~(1 << 3);
+ PORTD &= ~(1 << 2);
+
+ UBRR1 = 0;
}
#endif
@@ -129,14 +231,123 @@ void usart1_reset(void)
#ifdef CONFIG_AVR_USART0
void usart0_configure(void)
{
-# warning "Missing logic"
+ uint8_t ucsr0b;
+ uint8_t ucsr0c;
+
+ /* Select normal or double speed. */
+
+#ifdef UART0_DOUBLE_SPEED
+ UCSR0A = (1 << U2X0);
+#else
+ UCSR0A = 0;
+#endif
+
+ /* Select baud, parity, nubmer of bits, stop bits, etc. */
+
+ ucsr0b = ((1 << TXEN0) | (1 << RXEN0));
+ ucsr0c = 0;
+
+ /* Select parity */
+
+#if CONFIG_USART0_PARITY == 1
+ ucsr0c |= (UPM01 | UPM00); /* Odd parity */
+#else
+ ucsr0c |= UPM00; /* Even parity */
+#endif
+
+ /* 1 or 2 stop bits */
+
+#if defined(CONFIG_USART0_2STOP) && CONFIG_USART0_2STOP > 0
+ ucsr0c |= USBS0; /* Two stop bits */
+#endif
+
+ /* Word size */
+
+#if CONFIG_USART0_BITS == 5
+#elif CONFIG_USART0_BITS == 6
+ ucsr0c |= UCSZ00;
+#elif CONFIG_USART0_BITS == 7
+ ucsr0c |= UCSZ01;
+#elif CONFIG_USART0_BITS == 8
+ ucsr0c |= (UCSZ00 | UCSZ01);
+#elif CONFIG_USART0_BITS == 9
+ ucsr0c |= (UCSZ00 | UCSZ01);
+ ucsr0b |= UCSZ02;
+#else
+# error "Unsupported word size"
+#endif
+ UCSR0B = ucsr0b;
+ UCSR0C = ucsr0c;
+
+ /* Configure pin */
+
+#warning "Missing logic"
+
+ /* Set the baud rate divisor */
+
+ UBRR0 = AVR_UBRR0;
}
#endif
#ifdef CONFIG_AVR_USART1
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
@@ -173,9 +384,11 @@ void up_lowputc(char ch)
{
#ifdef HAVE_SERIAL_CONSOLE
# if defined(CONFIG_USART0_SERIAL_CONSOLE)
-# warning "Missing logic"
+ while ((UCSR0A & (1 << UDRE0)) == 0);
+ UDR0 = ch;
# elif defined(CONFIG_USART1_SERIAL_CONSOLE)
-# warning "Missing logic"
+ while ((UCSR1A & (1 << UDRE1)) == 0);
+ UDR1 = ch;
# endif
#endif
}
diff --git a/nuttx/arch/avr/src/atmega/atmega_serial.c b/nuttx/arch/avr/src/atmega/atmega_serial.c
index 4d3b5a23c..f55d22ec2 100644
--- a/nuttx/arch/avr/src/atmega/atmega_serial.c
+++ b/nuttx/arch/avr/src/atmega/atmega_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>
@@ -562,46 +563,32 @@ static int usart1_ioctl(struct file *filep, int cmd, unsigned long arg)
#ifdef CONFIG_AVR_USART0
static int usart0_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)UCSR0A;
}
/* Then return the actual received byte */
-# warning "Missing logic"
- return 0;
+ return UDR0;
}
#endif
#ifdef CONFIG_AVR_USART1
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;
}
#endif
@@ -664,16 +651,14 @@ static void usart1_rxint(struct uart_dev_s *dev, bool enable)
#ifdef CONFIG_AVR_USART0
static bool usart0_rxavailable(struct uart_dev_s *dev)
{
-# warning "Missing logic"
- return 0;
+ return (UCSR0A & (1 << RXC0)) != 0;
}
#endif
#ifdef CONFIG_AVR_USART1
static bool usart1_rxavailable(struct uart_dev_s *dev)
{
-# warning "Missing logic"
- return 0;
+ return (UCSR1A & (1 << RXC1)) != 0;
}
#endif
@@ -688,16 +673,14 @@ static bool usart1_rxavailable(struct uart_dev_s *dev)
#ifdef CONFIG_AVR_USART0
static void usart0_send(struct uart_dev_s *dev, int ch)
{
-# warning "Missing logic"
- return 0;
+ UDR0 = ch;
}
#endif
#ifdef CONFIG_AVR_USART0
static void usart0_send(struct uart_dev_s *dev, int ch)
{
-# warning "Missing logic"
- return 0;
+ UDR1 = ch;
}
#endif
@@ -780,16 +763,14 @@ static void usart1_txint(struct uart_dev_s *dev, bool enable)
#ifdef CONFIG_AVR_USART0
static bool usart0_txready(struct uart_dev_s *dev)
{
-# warning "Missing logic"
- return 0;
+ return (UCSR0A & (1 << UDRE0)) != 0;
}
#endif
#ifdef CONFIG_AVR_USART1
static bool usart1_txready(struct uart_dev_s *dev)
{
-# warning "Missing logic"
- return 0;
+ return (UCSR1A & (1 << UDRE1)) != 0;
}
#endif