]> git.sur5r.net Git - freertos/blobdiff - Demo/AVR32_UC3/serial/serial.c
Add FreeRTOS-Plus directory.
[freertos] / Demo / AVR32_UC3 / serial / serial.c
diff --git a/Demo/AVR32_UC3/serial/serial.c b/Demo/AVR32_UC3/serial/serial.c
deleted file mode 100644 (file)
index 83eb402..0000000
+++ /dev/null
@@ -1,373 +0,0 @@
-/*This file has been prepared for Doxygen automatic documentation generation.*/\r
-/*! \file *********************************************************************\r
- *\r
- * \brief FreeRTOS Serial Port management example for AVR32 UC3.\r
- *\r
- * - Compiler:           IAR EWAVR32 and GNU GCC for AVR32\r
- * - Supported devices:  All AVR32 devices can be used.\r
- * - AppNote:\r
- *\r
- * \author               Atmel Corporation: http://www.atmel.com \n\r
- *                       Support and FAQ: http://support.atmel.no/\r
- *\r
- *****************************************************************************/\r
-\r
-/* Copyright (c) 2007, Atmel Corporation All rights reserved.\r
- *\r
- * Redistribution and use in source and binary forms, with or without\r
- * modification, are permitted provided that the following conditions are met:\r
- *\r
- * 1. Redistributions of source code must retain the above copyright notice,\r
- * this list of conditions and the following disclaimer.\r
- *\r
- * 2. Redistributions in binary form must reproduce the above copyright notice,\r
- * this list of conditions and the following disclaimer in the documentation\r
- * and/or other materials provided with the distribution.\r
- *\r
- * 3. The name of ATMEL may not be used to endorse or promote products derived\r
- * from this software without specific prior written permission.\r
- *\r
- * THIS SOFTWARE IS PROVIDED BY ATMEL ``AS IS'' AND ANY EXPRESS OR IMPLIED\r
- * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\r
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE EXPRESSLY AND\r
- * SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT,\r
- * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\r
- * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\r
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND\r
- * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\r
- * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF\r
- * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
- */\r
-\r
-\r
-/*\r
-  BASIC INTERRUPT DRIVEN SERIAL PORT DRIVER FOR USART.\r
-*/\r
-\r
-/* Scheduler includes. */\r
-#include "FreeRTOS.h"\r
-#include "queue.h"\r
-#include "task.h"\r
-\r
-/* Demo application includes. */\r
-#include "serial.h"\r
-#include <avr32/io.h>\r
-#include "board.h"\r
-#include "gpio.h"\r
-\r
-/*-----------------------------------------------------------*/\r
-\r
-/* Constants to setup and access the USART. */\r
-#define serINVALID_COMPORT_HANDLER        ( ( xComPortHandle ) 0 )\r
-#define serINVALID_QUEUE                  ( ( xQueueHandle ) 0 )\r
-#define serHANDLE                         ( ( xComPortHandle ) 1 )\r
-#define serNO_BLOCK                       ( ( portTickType ) 0 )\r
-\r
-/*-----------------------------------------------------------*/\r
-\r
-/* Queues used to hold received characters, and characters waiting to be\r
-transmitted. */\r
-static xQueueHandle xRxedChars;\r
-static xQueueHandle xCharsForTx;\r
-\r
-/*-----------------------------------------------------------*/\r
-\r
-/* Forward declaration. */\r
-static void vprvSerialCreateQueues( unsigned portBASE_TYPE uxQueueLength,\r
-                                                                       xQueueHandle *pxRxedChars,\r
-                                                                       xQueueHandle *pxCharsForTx );\r
-\r
-/*-----------------------------------------------------------*/\r
-\r
-#if __GNUC__\r
-       __attribute__((__noinline__))\r
-#elif __ICCAVR32__\r
-       #pragma optimize = no_inline\r
-#endif\r
-\r
-static portBASE_TYPE prvUSART_ISR_NonNakedBehaviour( void )\r
-{\r
-       /* Now we can declare the local variables. */\r
-       signed portCHAR     cChar;\r
-       portBASE_TYPE     xHigherPriorityTaskWoken = pdFALSE;\r
-       unsigned portLONG     ulStatus;\r
-       volatile avr32_usart_t  *usart = serialPORT_USART;\r
-       portBASE_TYPE retstatus;\r
-\r
-       /* What caused the interrupt? */\r
-       ulStatus = usart->csr & usart->imr;\r
-\r
-       if (ulStatus & AVR32_USART_CSR_TXRDY_MASK)\r
-       {\r
-               /* The interrupt was caused by the THR becoming empty.  Are there any\r
-               more characters to transmit?\r
-               Because FreeRTOS is not supposed to run with nested interrupts, put all OS\r
-               calls in a critical section . */\r
-               portENTER_CRITICAL();\r
-                       retstatus = xQueueReceiveFromISR( xCharsForTx, &cChar, &xHigherPriorityTaskWoken );\r
-               portEXIT_CRITICAL();\r
-\r
-               if (retstatus == pdTRUE)\r
-               {\r
-                       /* A character was retrieved from the queue so can be sent to the\r
-                        THR now. */\r
-                       usart->thr = cChar;\r
-               }\r
-               else\r
-               {\r
-                       /* Queue empty, nothing to send so turn off the Tx interrupt. */\r
-                       usart->idr = AVR32_USART_IDR_TXRDY_MASK;\r
-               }\r
-       }\r
-\r
-       if (ulStatus & AVR32_USART_CSR_RXRDY_MASK)\r
-       {\r
-               /* The interrupt was caused by the receiver getting data. */\r
-               cChar = usart->rhr; //TODO\r
-\r
-               /* Because FreeRTOS is not supposed to run with nested interrupts, put all OS\r
-               calls in a critical section . */\r
-               portENTER_CRITICAL();\r
-                       xQueueSendFromISR(xRxedChars, &cChar, &xHigherPriorityTaskWoken);\r
-               portEXIT_CRITICAL();\r
-       }\r
-\r
-       /* The return value will be used by portEXIT_SWITCHING_ISR() to know if it\r
-       should perform a vTaskSwitchContext(). */\r
-       return ( xHigherPriorityTaskWoken );\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-/*\r
- * USART interrupt service routine.\r
- */\r
-#if __GNUC__\r
-       __attribute__((__naked__))\r
-#elif __ICCAVR32__\r
-       #pragma shadow_registers = full   // Naked.\r
-#endif\r
-\r
-static void vUSART_ISR( void )\r
-{\r
-       /* This ISR can cause a context switch, so the first statement must be a\r
-       call to the portENTER_SWITCHING_ISR() macro.  This must be BEFORE any\r
-       variable declarations. */\r
-       portENTER_SWITCHING_ISR();\r
-\r
-       prvUSART_ISR_NonNakedBehaviour();\r
-\r
-       /* Exit the ISR.  If a task was woken by either a character being received\r
-       or transmitted then a context switch will occur. */\r
-       portEXIT_SWITCHING_ISR();\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-\r
-/*\r
- * Init the serial port for the Minimal implementation.\r
- */\r
-xComPortHandle xSerialPortInitMinimal( unsigned portLONG ulWantedBaud, unsigned portBASE_TYPE uxQueueLength )\r
-{\r
-static const gpio_map_t USART_GPIO_MAP =\r
-{\r
-       { serialPORT_USART_RX_PIN, serialPORT_USART_RX_FUNCTION },\r
-       { serialPORT_USART_TX_PIN, serialPORT_USART_TX_FUNCTION }\r
-};\r
-\r
-xComPortHandle    xReturn = serHANDLE;\r
-volatile avr32_usart_t  *usart = serialPORT_USART;\r
-int cd; /* USART Clock Divider. */\r
-\r
-       /* Create the rx and tx queues. */\r
-       vprvSerialCreateQueues( uxQueueLength, &xRxedChars, &xCharsForTx );\r
-\r
-       /* Configure USART. */\r
-       if( ( xRxedChars != serINVALID_QUEUE ) &&\r
-         ( xCharsForTx != serINVALID_QUEUE ) &&\r
-         ( ulWantedBaud != ( unsigned portLONG ) 0 ) )\r
-       {\r
-               portENTER_CRITICAL();\r
-               {\r
-                       /**\r
-                       ** Reset USART.\r
-                       **/\r
-                       /* Disable all USART interrupt sources to begin... */\r
-                       usart->idr = 0xFFFFFFFF;\r
-\r
-                       /* Reset mode and other registers that could cause unpredictable\r
-                        behaviour after reset */\r
-                       usart->mr = 0; /* Reset Mode register. */\r
-                       usart->rtor = 0; /* Reset Receiver Time-out register. */\r
-                       usart->ttgr = 0; /* Reset Transmitter Timeguard register. */\r
-\r
-                       /* Shutdown RX and TX, reset status bits, reset iterations in CSR, reset NACK\r
-                        and turn off DTR and RTS */\r
-                       usart->cr = AVR32_USART_CR_RSTRX_MASK   |\r
-                                          AVR32_USART_CR_RSTTX_MASK   |\r
-                                          AVR32_USART_CR_RXDIS_MASK   |\r
-                                          AVR32_USART_CR_TXDIS_MASK   |\r
-                                          AVR32_USART_CR_RSTSTA_MASK  |\r
-                                          AVR32_USART_CR_RSTIT_MASK   |\r
-                                          AVR32_USART_CR_RSTNACK_MASK |\r
-                                          AVR32_USART_CR_DTRDIS_MASK  |\r
-                                          AVR32_USART_CR_RTSDIS_MASK;\r
-\r
-                       /**\r
-                       ** Configure USART.\r
-                       **/\r
-                       /* Enable USART RXD & TXD pins. */\r
-                       gpio_enable_module( USART_GPIO_MAP, sizeof( USART_GPIO_MAP ) / sizeof( USART_GPIO_MAP[0] ) );\r
-\r
-                       /* Set the USART baudrate to be as close as possible to the wanted baudrate. */\r
-                       /*\r
-                       *             ** BAUDRATE CALCULATION **\r
-                       *\r
-                       *                 Selected Clock                       Selected Clock\r
-                       *     baudrate = ----------------   or     baudrate = ----------------\r
-                       *                    16 x CD                              8 x CD\r
-                       *\r
-                       *       (with 16x oversampling)              (with 8x oversampling)\r
-                       */\r
-\r
-                       if( ulWantedBaud < ( configCPU_CLOCK_HZ / 16 ) )\r
-                       {\r
-                               /* Use 8x oversampling */\r
-                               usart->mr |= (1<<AVR32_USART_MR_OVER_OFFSET);\r
-                               cd = configCPU_CLOCK_HZ / (8*ulWantedBaud);\r
-\r
-                               if( cd < 2 )\r
-                               {\r
-                                       return serINVALID_COMPORT_HANDLER;\r
-                               }\r
-\r
-                               usart->brgr = (cd << AVR32_USART_BRGR_CD_OFFSET);\r
-                       }\r
-                       else\r
-                       {\r
-                               /* Use 16x oversampling */\r
-                               usart->mr &= ~(1<<AVR32_USART_MR_OVER_OFFSET);\r
-                               cd = configCPU_CLOCK_HZ / (16*ulWantedBaud);\r
-\r
-                               if( cd > 65535 )\r
-                               {\r
-                                       /* Baudrate is too low */\r
-                                       return serINVALID_COMPORT_HANDLER;\r
-                               }\r
-                       }\r
-\r
-                       usart->brgr = (cd << AVR32_USART_BRGR_CD_OFFSET);\r
-\r
-                       /* Set the USART Mode register: Mode=Normal(0), Clk selection=MCK(0),\r
-                       CHRL=8,  SYNC=0(asynchronous), PAR=None, NBSTOP=1, CHMODE=0, MSBF=0,\r
-                       MODE9=0, CKLO=0, OVER(previously done when setting the baudrate),\r
-                       other fields not used in this mode. */\r
-                       usart->mr |= ((8-5) << AVR32_USART_MR_CHRL_OFFSET  ) |\r
-                                       (   4  << AVR32_USART_MR_PAR_OFFSET   ) |\r
-                                       (   1  << AVR32_USART_MR_NBSTOP_OFFSET);\r
-\r
-                       /* Write the Transmit Timeguard Register */\r
-                       usart->ttgr = 0;\r
-\r
-\r
-                       /* Register the USART interrupt handler to the interrupt controller and\r
-                        enable the USART interrupt. */\r
-                       INTC_register_interrupt((__int_handler)&vUSART_ISR, serialPORT_USART_IRQ, INT1);\r
-\r
-                       /* Enable USART interrupt sources (but not Tx for now)... */\r
-                       usart->ier = AVR32_USART_IER_RXRDY_MASK;\r
-\r
-                       /* Enable receiver and transmitter... */\r
-                       usart->cr |= AVR32_USART_CR_TXEN_MASK | AVR32_USART_CR_RXEN_MASK;\r
-               }\r
-               portEXIT_CRITICAL();\r
-       }\r
-       else\r
-       {\r
-               xReturn = serINVALID_COMPORT_HANDLER;\r
-       }\r
-\r
-       return xReturn;\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-signed portBASE_TYPE xSerialGetChar( xComPortHandle pxPort, signed portCHAR *pcRxedChar, portTickType xBlockTime )\r
-{\r
-       /* The port handle is not required as this driver only supports UART0. */\r
-       ( void ) pxPort;\r
-\r
-       /* Get the next character from the buffer.  Return false if no characters\r
-       are available, or arrive before xBlockTime expires. */\r
-       if( xQueueReceive( xRxedChars, pcRxedChar, xBlockTime ) )\r
-       {\r
-               return pdTRUE;\r
-       }\r
-       else\r
-       {\r
-               return pdFALSE;\r
-       }\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-void vSerialPutString( xComPortHandle pxPort, const signed portCHAR * const pcString, unsigned portSHORT usStringLength )\r
-{\r
-signed portCHAR *pxNext;\r
-\r
-       /* NOTE: This implementation does not handle the queue being full as no\r
-       block time is used! */\r
-\r
-       /* The port handle is not required as this driver only supports UART0. */\r
-       ( void ) pxPort;\r
-\r
-       /* Send each character in the string, one at a time. */\r
-       pxNext = ( signed portCHAR * ) pcString;\r
-       while( *pxNext )\r
-       {\r
-               xSerialPutChar( pxPort, *pxNext, serNO_BLOCK );\r
-               pxNext++;\r
-       }\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-signed portBASE_TYPE xSerialPutChar( xComPortHandle pxPort, signed portCHAR cOutChar, portTickType xBlockTime )\r
-{\r
-volatile avr32_usart_t  *usart = serialPORT_USART;\r
-\r
-       /* Place the character in the queue of characters to be transmitted. */\r
-       if( xQueueSend( xCharsForTx, &cOutChar, xBlockTime ) != pdPASS )\r
-       {\r
-               return pdFAIL;\r
-       }\r
-\r
-       /* Turn on the Tx interrupt so the ISR will remove the character from the\r
-       queue and send it.   This does not need to be in a critical section as\r
-       if the interrupt has already removed the character the next interrupt\r
-       will simply turn off the Tx interrupt again. */\r
-       usart->ier = (1 << AVR32_USART_IER_TXRDY_OFFSET);\r
-\r
-       return pdPASS;\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-void vSerialClose( xComPortHandle xPort )\r
-{\r
-  /* Not supported as not required by the demo application. */\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-/*###########################################################*/\r
-\r
-/*\r
- * Create the rx and tx queues.\r
- */\r
-static void vprvSerialCreateQueues(  unsigned portBASE_TYPE uxQueueLength, xQueueHandle *pxRxedChars, xQueueHandle *pxCharsForTx )\r
-{\r
-       /* Create the queues used to hold Rx and Tx characters. */\r
-       xRxedChars = xQueueCreate( uxQueueLength, ( unsigned portBASE_TYPE ) sizeof( signed portCHAR ) );\r
-       xCharsForTx = xQueueCreate( uxQueueLength + 1, ( unsigned portBASE_TYPE ) sizeof( signed portCHAR ) );\r
-\r
-       /* Pass back a reference to the queues so the serial API file can\r
-       post/receive characters. */\r
-       *pxRxedChars = xRxedChars;\r
-       *pxCharsForTx = xCharsForTx;\r
-}\r
-/*-----------------------------------------------------------*/\r