From 0a59caa507fd9aed69345ba2c915dfa8f7c2395c Mon Sep 17 00:00:00 2001 From: gdisirio Date: Wed, 19 Aug 2009 12:00:55 +0000 Subject: git-svn-id: svn://svn.code.sf.net/p/chibios/svn/trunk@1081 35acf78f-673a-0410-8e92-d51de3d6d3f4 --- os/ports/GCC/ARMCM3/STM32F103/serial_lld.c | 290 +++++++++++++++++++++++++++ os/ports/GCC/ARMCM3/STM32F103/serial_lld.h | 206 +++++++++++++++++++ os/ports/GCC/ARMCM3/STM32F103/stm32_serial.c | 222 -------------------- os/ports/GCC/ARMCM3/STM32F103/stm32_serial.h | 122 ----------- 4 files changed, 496 insertions(+), 344 deletions(-) create mode 100644 os/ports/GCC/ARMCM3/STM32F103/serial_lld.c create mode 100644 os/ports/GCC/ARMCM3/STM32F103/serial_lld.h delete mode 100644 os/ports/GCC/ARMCM3/STM32F103/stm32_serial.c delete mode 100644 os/ports/GCC/ARMCM3/STM32F103/stm32_serial.h (limited to 'os') diff --git a/os/ports/GCC/ARMCM3/STM32F103/serial_lld.c b/os/ports/GCC/ARMCM3/STM32F103/serial_lld.c new file mode 100644 index 000000000..5e4bcce99 --- /dev/null +++ b/os/ports/GCC/ARMCM3/STM32F103/serial_lld.c @@ -0,0 +1,290 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file os/io/templates/serial_lld.c + * @brief Serial Driver subsystem low level driver source template + * @addtogroup SERIAL_LLD + * @{ + */ + +#include +#include + +#include "nvic.h" +#include "board.h" + +#if USE_STM32_USART1 || defined(__DOXYGEN__) +/** @brief USART1 serial driver identifier.*/ +SerialDriver COM1; +#endif + +#if USE_STM32_USART2 || defined(__DOXYGEN__) +/** @brief USART2 serial driver identifier.*/ +SerialDriver COM2; +#endif + +#if USE_STM32_USART3 || defined(__DOXYGEN__) +/** @brief USART3 serial driver identifier.*/ +SerialDriver COM3; +#endif + +/*===========================================================================*/ +/* Low Level Driver local functions. */ +/*===========================================================================*/ + +/** + * @brief USART initialization. + * @details This function must be invoked with interrupts disabled. + * + * @param[in] u pointer to an USART I/O block + * @param[in] config the architecture-dependent serial driver configuration + */ +static void usart_init(USART_TypeDef *u, const SerialDriverConfig* config) { + + /* + * Baud rate setting. + */ + if (u == USART1) + u->BRR = APB2CLK / config->baud_rate; + else + u->BRR = APB1CLK / config->baud_rate; + + /* + * Note that some bits are enforced. + */ + u->CR1 = config->cr1 | USART_CR1_UE | USART_CR1_PEIE | USART_CR1_RXNEIE | + USART_CR1_TE | USART_CR1_RE; + u->CR2 = config->cr2; + u->CR3 = config->cr3 | USART_CR3_EIE; +} + +/** + * @brief USART de-initialization. + * @details This function must be invoked with interrupts disabled. + * + * @param[in] u pointer to an USART I/O block + */ +static void usart_deinit(USART_TypeDef *u) { + + u->CR1 = 0; + u->CR2 = 0; + u->CR3 = 0; +} + +/** + * @brief Error handling routine. + * @param[in] sr USART SR register value + * @param[in] com communication channel associated to the USART + */ +static void set_error(uint16_t sr, SerialDriver *sdp) { + sdflags_t sts = 0; + + if (sr & USART_SR_ORE) + sts |= SD_OVERRUN_ERROR; + if (sr & USART_SR_PE) + sts |= SD_PARITY_ERROR; + if (sr & USART_SR_FE) + sts |= SD_FRAMING_ERROR; + if (sr & USART_SR_LBD) + sts |= SD_BREAK_DETECTED; + chSysLockFromIsr(); + sdAddFlagsI(sdp, sts); + chSysUnlockFromIsr(); +} + +/** + * @brief Common IRQ handler. + * @param[in] u pointer to an USART I/O block + * @param[in] com communication channel associated to the USART + */ +static void serve_interrupt(USART_TypeDef *u, SerialDriver *sdp) { + uint16_t sr = u->SR; + + if (sr & (USART_SR_ORE | USART_SR_FE | USART_SR_PE | USART_SR_LBD)) + set_error(sr, sdp); + if (sr & USART_SR_RXNE) { + chSysLockFromIsr(); + sdIncomingDataI(sdp, u->DR); + chSysUnlockFromIsr(); + } + if (sr & USART_SR_TXE) { + chSysLockFromIsr(); + msg_t b = sdRequestDataI(sdp); + chSysUnlockFromIsr(); + if (b < Q_OK) + u->CR1 &= ~USART_CR1_TXEIE; + else + u->DR = b; + } +} + +#if USE_STM32_USART1 || defined(__DOXYGEN__) +static void notify1(void) { + + USART1->CR1 |= USART_CR1_TXEIE; +} +#endif + +#if USE_STM32_USART2 || defined(__DOXYGEN__) +static void notify2(void) { + + USART2->CR1 |= USART_CR1_TXEIE; +} +#endif + +#if USE_STM32_USART3 || defined(__DOXYGEN__) +static void notify3(void) { + + USART3->CR1 |= USART_CR1_TXEIE; +} +#endif + +/*===========================================================================*/ +/* Low Level Driver interrupt handlers. */ +/*===========================================================================*/ + +#if USE_STM32_USART1 || defined(__DOXYGEN__) +CH_IRQ_HANDLER(VectorD4) { + + CH_IRQ_PROLOGUE(); + + serve_interrupt(USART1, &COM1); + + CH_IRQ_EPILOGUE(); +} +#endif + +#if USE_STM32_USART2 || defined(__DOXYGEN__) +CH_IRQ_HANDLER(VectorD8) { + + CH_IRQ_PROLOGUE(); + + serve_interrupt(USART2, &COM2); + + CH_IRQ_EPILOGUE(); +} +#endif + +#if USE_STM32_USART3 || defined(__DOXYGEN__) +CH_IRQ_HANDLER(VectorDC) { + + CH_IRQ_PROLOGUE(); + + serve_interrupt(USART3, &COM3); + + CH_IRQ_EPILOGUE(); +} +#endif + +/*===========================================================================*/ +/* Low Level Driver exported functions. */ +/*===========================================================================*/ + +/** + * Low level serial driver initialization. + */ +void sd_lld_init(void) { + +#if USE_STM32_USART1 + sdInit(&COM1, NULL, notify1); + GPIOA->CRH = (GPIOA->CRH & 0xFFFFF00F) | 0x000004B0; +#endif + +#if USE_STM32_USART2 + sdInit(&COM2, NULL, notify2); + GPIOA->CRL = (GPIOA->CRL & 0xFFFF00FF) | 0x00004B00; +#endif + +#if USE_STM32_USART3 + sdInit(&COM3, NULL, notify3); + GPIOB->CRH = (GPIOB->CRH & 0xFFFF00FF) | 0x00004B00; +#endif +} + +/** + * @brief Low level serial driver configuration and (re)start. + * + * @param[in] sdp pointer to a @p SerialDriver object + * @param[in] config the architecture-dependent serial driver configuration + */ +void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config) { + +#if USE_STM32_USART1 + if (&COM1 == sdp) { + RCC->APB2ENR |= RCC_APB2ENR_USART1EN; + usart_init(USART1, config); + NVICEnableVector(USART1_IRQn, STM32_USART1_PRIORITY); + return; + } +#endif +#if USE_STM32_USART2 + if (&COM2 == sdp) { + RCC->APB1ENR |= RCC_APB1ENR_USART2EN; + usart_init(USART2, config); + NVICEnableVector(USART2_IRQn, STM32_USART2_PRIORITY); + return; + } +#endif +#if USE_STM32_USART3 + if (&COM3 == sdp) { + RCC->APB1ENR |= RCC_APB1ENR_USART3EN; + usart_init(USART3, config); + NVICEnableVector(USART3_IRQn, STM32_USART3_PRIORITY); + return; + } +#endif +} + +/** + * @brief Low level serial driver stop. + * @details De-initializes the USART, stops the associated clock, resets the + * interrupt vector. + * + * @param[in] sd pointer to a @p SerialDriver object + */ +void sd_lld_stop(SerialDriver *sdp) { + +#if USE_STM32_USART1 + if (&COM1 == sdp) { + usart_deinit(USART1); + RCC->APB2ENR &= ~RCC_APB2ENR_USART1EN; + NVICDisableVector(USART1_IRQn); + return; + } +#endif +#if USE_STM32_USART2 + if (&COM2 == sdp) { + usart_deinit(USART2); + RCC->APB1ENR &= ~RCC_APB1ENR_USART2EN; + NVICDisableVector(USART2_IRQn); + return; + } +#endif +#if USE_STM32_USART3 + if (&COM3 == sdp) { + usart_deinit(USART3); + RCC->APB1ENR &= ~RCC_APB1ENR_USART3EN; + NVICDisableVector(USART3_IRQn); + return; + } +#endif +} + +/** @} */ diff --git a/os/ports/GCC/ARMCM3/STM32F103/serial_lld.h b/os/ports/GCC/ARMCM3/STM32F103/serial_lld.h new file mode 100644 index 000000000..280a44b2f --- /dev/null +++ b/os/ports/GCC/ARMCM3/STM32F103/serial_lld.h @@ -0,0 +1,206 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file os/io/templates/serial_lld.h + * @brief Serial Driver subsystem low level driver header template + * @addtogroup SERIAL_LLD + * @{ + */ + +#ifndef _SERIAL_LLD_H_ +#define _SERIAL_LLD_H_ + +/* + * Tricks required to make the TRUE/FALSE declaration inside the library + * compatible. + */ +#ifndef __STM32F10x_H +#undef FALSE +#undef TRUE +#include +#define FALSE 0 +#define TRUE (!FALSE) +#endif + +/*===========================================================================*/ +/* Driver pre-compile time settings. */ +/*===========================================================================*/ + +/** + * @brief Serial buffers size setting. + * @details Configuration parameter, you can change the depth of the queue + * buffers depending on the requirements of your application. + * @note The default is 128 bytes for both the transmission and receive buffers. + */ +#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__) +#define SERIAL_BUFFERS_SIZE 128 +#endif + +/** + * @brief USART1 driver enable switch. + * @details If set to @p TRUE the support for USART1 is included. + * @note The default is @p FALSE. + */ +#if !defined(USE_STM32_USART1) || defined(__DOXYGEN__) +#define USE_STM32_USART1 FALSE +#endif + +/** + * @brief USART2 driver enable switch. + * @details If set to @p TRUE the support for USART2 is included. + * @note The default is @p TRUE. + */ +#if !defined(USE_STM32_USART2) || defined(__DOXYGEN__) +#define USE_STM32_USART2 TRUE +#endif + +/** + * @brief USART3 driver enable switch. + * @details If set to @p TRUE the support for USART3 is included. + * @note The default is @p FALSE. + */ +#if !defined(USE_STM32_USART3) || defined(__DOXYGEN__) +#define USE_STM32_USART3 FALSE +#endif + +/** + * @brief USART1 interrupt priority level setting. + * @note @p BASEPRI_KERNEL >= @p STM32_USART1_PRIORITY > @p PRIORITY_PENDSV. + */ +#if !defined(STM32_USART1_PRIORITY) || defined(__DOXYGEN__) +#define STM32_USART1_PRIORITY 0xC0 +#endif + +/** + * @brief USART2 interrupt priority level setting. + * @note @p BASEPRI_KERNEL >= @p STM32_USART2_PRIORITY > @p PRIORITY_PENDSV. + */ +#if !defined(STM32_USART2_PRIORITY) || defined(__DOXYGEN__) +#define STM32_USART2_PRIORITY 0xC0 +#endif + +/** + * @brief USART3 interrupt priority level setting. + * @note @p BASEPRI_KERNEL >= @p STM32_USART3_PRIORITY > @p PRIORITY_PENDSV. + */ +#if !defined(STM32_USART3_PRIORITY) || defined(__DOXYGEN__) +#define STM32_USART3_PRIORITY 0xC0 +#endif + +/*===========================================================================*/ +/* Driver macros. */ +/*===========================================================================*/ + +/* + * Extra USARTs definitions here (missing from the ST header file). + */ +#define USART_CR2_STOP1_BITS (0 << 12) /**< @brief CR2 1 stop bit value.*/ +#define USART_CR2_STOP0P5_BITS (1 << 12) /**< @brief CR2 0.5 stop bit value.*/ +#define USART_CR2_STOP2_BITS (2 << 12) /**< @brief CR2 2 stop bit value.*/ +#define USART_CR2_STOP1P5_BITS (3 << 12) /**< @brief CR2 1.5 stop bit value.*/ + +/*===========================================================================*/ +/* Driver data structures. */ +/*===========================================================================*/ + +/** + * Serial Driver condition flags type. + */ +typedef uint32_t sdflags_t; + +/** + * @brief @p SerialDriver specific data. + */ +struct _serial_driver_data { + /** + * Input queue, incoming data can be read from this input queue by + * using the queues APIs. + */ + InputQueue iqueue; + /** + * Output queue, outgoing data can be written to this output queue by + * using the queues APIs. + */ + OutputQueue oqueue; + /** + * Status Change @p EventSource. This event is generated when one or more + * condition flags change. + */ + EventSource sevent; + /** + * I/O driver status flags. + */ + sdflags_t flags; + /** + * Input circular buffer. + */ + uint8_t ib[SERIAL_BUFFERS_SIZE]; + /** + * Output circular buffer. + */ + uint8_t ob[SERIAL_BUFFERS_SIZE]; +}; + +/** + * @brief Generic Serial Driver static initializer. + * @details An instance of this structure must be passed to @p sdStart() + * in order to configure and start a serial driver operations. + * + * @note This structure content is architecture dependent, each driver + * implementation defines its own version and the custom static + * initializers. + */ +typedef struct { + + uint32_t baud_rate; + uint16_t cr1; + uint16_t cr2; + uint16_t cr3; +} SerialDriverConfig; + +/*===========================================================================*/ +/* External declarations. */ +/*===========================================================================*/ + +/** @cond never*/ +#if USE_STM32_USART1 +extern SerialDriver COM1; +#endif +#if USE_STM32_USART2 +extern SerialDriver COM2; +#endif +#if USE_STM32_USART3 +extern SerialDriver COM3; +#endif +/** @endcond*/ + +#ifdef __cplusplus +extern "C" { +#endif + void sd_lld_init(void); + void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config); + void sd_lld_stop(SerialDriver *sdp); +#ifdef __cplusplus +} +#endif + +#endif /* _SERIAL_LLD_H_ */ + +/** @} */ diff --git a/os/ports/GCC/ARMCM3/STM32F103/stm32_serial.c b/os/ports/GCC/ARMCM3/STM32F103/stm32_serial.c deleted file mode 100644 index 4634d82a8..000000000 --- a/os/ports/GCC/ARMCM3/STM32F103/stm32_serial.c +++ /dev/null @@ -1,222 +0,0 @@ -/* - ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio. - - This file is part of ChibiOS/RT. - - ChibiOS/RT is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - ChibiOS/RT is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . -*/ - -/** - * @file ports/ARMCM3-STM32F103/stm32_serial.c - * @brief STM32F103 Serial driver code. - * @addtogroup STM32F103_SERIAL - * @{ - */ - -#include - -#include "board.h" -#include "nvic.h" -#include "stm32_serial.h" - -#if USE_STM32_USART1 || defined(__DOXYGEN__) -/** @brief USART1 serial driver identifier.*/ -FullDuplexDriver COM1; - -static uint8_t ib1[SERIAL_BUFFERS_SIZE]; -static uint8_t ob1[SERIAL_BUFFERS_SIZE]; -#endif - -#if USE_STM32_USART2 || defined(__DOXYGEN__) -/** @brief USART2 serial driver identifier.*/ -FullDuplexDriver COM2; - -static uint8_t ib2[SERIAL_BUFFERS_SIZE]; -static uint8_t ob2[SERIAL_BUFFERS_SIZE]; -#endif - -#if USE_STM32_USART3 || defined(__DOXYGEN__) -/** @brief USART3 serial driver identifier.*/ -FullDuplexDriver COM3; - -static uint8_t ib3[SERIAL_BUFFERS_SIZE]; -static uint8_t ob3[SERIAL_BUFFERS_SIZE]; -#endif - -/** - * @brief Error handling routine. - * @param[in] sr USART SR register value - * @param[in] com communication channel associated to the USART - */ -static void SetError(uint16_t sr, FullDuplexDriver *com) { - dflags_t sts = 0; - - if (sr & USART_SR_ORE) - sts |= SD_OVERRUN_ERROR; - if (sr & USART_SR_PE) - sts |= SD_PARITY_ERROR; - if (sr & USART_SR_FE) - sts |= SD_FRAMING_ERROR; - if (sr & USART_SR_LBD) - sts |= SD_BREAK_DETECTED; - chSysLockFromIsr(); - chFDDAddFlagsI(com, sts); - chSysUnlockFromIsr(); -} - -/** - * @brief Common IRQ handler. - * @param[in] u pointer to an USART I/O block - * @param[in] com communication channel associated to the USART - */ -static void ServeInterrupt(USART_TypeDef *u, FullDuplexDriver *com) { - uint16_t sr = u->SR; - - if (sr & (USART_SR_ORE | USART_SR_FE | USART_SR_PE | USART_SR_LBD)) - SetError(sr, com); - if (sr & USART_SR_RXNE) { - chSysLockFromIsr(); - chFDDIncomingDataI(com, u->DR); - chSysUnlockFromIsr(); - } - if (sr & USART_SR_TXE) { - chSysLockFromIsr(); - msg_t b = chFDDRequestDataI(com); - chSysUnlockFromIsr(); - if (b < Q_OK) - u->CR1 &= ~USART_CR1_TXEIE; - else - u->DR = b; - } -} - -#if USE_STM32_USART1 || defined(__DOXYGEN__) -CH_IRQ_HANDLER(VectorD4) { - - CH_IRQ_PROLOGUE(); - - ServeInterrupt(USART1, &COM1); - - CH_IRQ_EPILOGUE(); -} - -static void OutNotify1(void) { - - USART1->CR1 |= USART_CR1_TXEIE; -} -#endif - -#if USE_STM32_USART2 || defined(__DOXYGEN__) -CH_IRQ_HANDLER(VectorD8) { - - CH_IRQ_PROLOGUE(); - - ServeInterrupt(USART2, &COM2); - - CH_IRQ_EPILOGUE(); -} - -static void OutNotify2(void) { - - USART2->CR1 |= USART_CR1_TXEIE; -} -#endif - -#if USE_STM32_USART3 || defined(__DOXYGEN__) -CH_IRQ_HANDLER(VectorDC) { - - CH_IRQ_PROLOGUE(); - - ServeInterrupt(USART3, &COM3); - - CH_IRQ_EPILOGUE(); -} - -static void OutNotify3(void) { - - USART3->CR1 |= USART_CR1_TXEIE; -} -#endif - -/** - * @brief USART1 setup. - * @details This function must be invoked with interrupts disabled. - * @param[in] u pointer to an USART I/O block - * @param[in] speed serial port speed in bits per second - * @param[in] cr1 the value for the @p CR1 register - * @param[in] cr2 the value for the @p CR2 register - * @param[in] cr3 the value for the @p CR3 register - * @note Must be invoked with interrupts disabled. - * @note Does not reset the I/O queues. - */ -void usart_setup(USART_TypeDef *u, uint32_t speed, uint16_t cr1, - uint16_t cr2, uint16_t cr3) { - - /* - * Baud rate setting. - */ - if (u == USART1) - u->BRR = APB2CLK / speed; - else - u->BRR = APB1CLK / speed; - - /* - * Note that some bits are enforced. - */ - u->CR1 = cr1 | USART_CR1_UE | USART_CR1_PEIE | USART_CR1_RXNEIE | - USART_CR1_TE | USART_CR1_RE; - u->CR2 = cr2; - u->CR3 = cr3 | USART_CR3_EIE; -} - -/** - * @brief Serial driver initialization. - * @param[in] prio1 priority to be assigned to the USART1 IRQ - * @param[in] prio2 priority to be assigned to the USART2 IRQ - * @param[in] prio3 priority to be assigned to the USART3 IRQ - * @note Handshake pads are not enabled inside this function because they - * may have another use, enable them externally if needed. - * RX and TX pads are handled inside. - */ -void serial_init(uint32_t prio1, uint32_t prio2, uint32_t prio3) { - -#if USE_STM32_USART1 - chFDDInit(&COM1, ib1, sizeof ib1, NULL, ob1, sizeof ob1, OutNotify1); - RCC->APB2ENR |= RCC_APB2ENR_USART1EN; - usart_setup(USART1, DEFAULT_USART_BITRATE, 0, - USART_CR2_STOP1_BITS | USART_CR2_LINEN, 0); - GPIOA->CRH = (GPIOA->CRH & 0xFFFFF00F) | 0x000004B0; - NVICEnableVector(USART1_IRQn, prio1); -#endif - -#if USE_STM32_USART2 - chFDDInit(&COM2, ib2, sizeof ib2, NULL, ob2, sizeof ob2, OutNotify2); - RCC->APB1ENR |= RCC_APB1ENR_USART2EN; - usart_setup(USART2, DEFAULT_USART_BITRATE, 0, - USART_CR2_STOP1_BITS | USART_CR2_LINEN, 0); - GPIOA->CRL = (GPIOA->CRL & 0xFFFF00FF) | 0x00004B00; - NVICEnableVector(USART2_IRQn, prio2); -#endif - -#if USE_STM32_USART3 - chFDDInit(&COM3, ib3, sizeof ib3, NULL, ob3, sizeof ob3, OutNotify3); - RCC->APB1ENR |= RCC_APB1ENR_USART3EN; - usart_setup(USART3, DEFAULT_USART_BITRATE, 0, - USART_CR2_STOP1_BITS | USART_CR2_LINEN, 0); - GPIOB->CRH = (GPIOB->CRH & 0xFFFF00FF) | 0x00004B00; - NVICEnableVector(USART3_IRQn, prio3); -#endif -} - -/** @} */ diff --git a/os/ports/GCC/ARMCM3/STM32F103/stm32_serial.h b/os/ports/GCC/ARMCM3/STM32F103/stm32_serial.h deleted file mode 100644 index 421cf00fe..000000000 --- a/os/ports/GCC/ARMCM3/STM32F103/stm32_serial.h +++ /dev/null @@ -1,122 +0,0 @@ -/* - ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio. - - This file is part of ChibiOS/RT. - - ChibiOS/RT is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - ChibiOS/RT is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . -*/ - -/** - * @file ports/ARMCM3-STM32F103/stm32_serial.h - * @brief STM32F103 Serial driver macros and structures. - * @addtogroup STM32F103_SERIAL - * @{ - */ - -#ifndef _STM32_SERIAL_H_ -#define _STM32_SERIAL_H_ - -/* - * Tricks required to make the TRUE/FALSE declaration inside the library - * compatible. - */ -#ifndef __STM32F10x_H -#undef FALSE -#undef TRUE -#include -#define FALSE 0 -#define TRUE (!FALSE) -#endif - -/** - * @brief Serial buffers size. - * @details Configuration parameter, you can change the depth of the queue - * buffers depending on the requirements of your application. - * @note The default is 128 bytes for both the transmission and receive buffers. - */ -#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__) -#define SERIAL_BUFFERS_SIZE 128 -#endif - -/** - * @brief Default bit rate. - * @details Configuration parameter, at startup the USARTs are configured at - * this speed. - * @note It is possible to use @p SetUSART() in order to change the working - * parameters at runtime. - */ -#if !defined(DEFAULT_USART_BITRATE) || defined(__DOXYGEN__) -#define DEFAULT_USART_BITRATE 38400 -#endif - -/** - * @brief USART1 driver enable switch. - * @details If set to @p TRUE the support for USART1 is included. - * @note The default is @p FALSE. - */ -#if !defined(USE_STM32_USART1) || defined(__DOXYGEN__) -#define USE_STM32_USART1 FALSE -#endif - -/** - * @brief USART2 driver enable switch. - * @details If set to @p TRUE the support for USART2 is included. - * @note The default is @p TRUE. - */ -#if !defined(USE_STM32_USART2) || defined(__DOXYGEN__) -#define USE_STM32_USART2 TRUE -#endif - -/** - * @brief USART3 driver enable switch. - * @details If set to @p TRUE the support for USART3 is included. - * @note The default is @p FALSE. - */ -#if !defined(USE_STM32_USART3) || defined(__DOXYGEN__) -#define USE_STM32_USART3 FALSE -#endif - -/* - * Extra USARTs definitions here (missing from the ST header file). - */ -#define USART_CR2_STOP1_BITS (0 << 12) /**< @brief CR2 1 stop bit value.*/ -#define USART_CR2_STOP0P5_BITS (1 << 12) /**< @brief CR2 0.5 stop bit value.*/ -#define USART_CR2_STOP2_BITS (2 << 12) /**< @brief CR2 2 stop bit value.*/ -#define USART_CR2_STOP1P5_BITS (3 << 12) /**< @brief CR2 1.5 stop bit value.*/ - -/** @cond never*/ -#if USE_STM32_USART1 -extern FullDuplexDriver COM1; -#endif -#if USE_STM32_USART2 -extern FullDuplexDriver COM2; -#endif -#if USE_STM32_USART3 -extern FullDuplexDriver COM3; -#endif -/** @endcond*/ - -#ifdef __cplusplus -extern "C" { -#endif - void serial_init(uint32_t prio1, uint32_t prio2, uint32_t prio3); - void usart_setup(USART_TypeDef *u, uint32_t speed, uint16_t cr1, - uint16_t cr2, uint16_t cr3); -#ifdef __cplusplus -} -#endif - -#endif /* _STM32_SERIAL_H_ */ - -/** @} */ -- cgit v1.2.3