diff options
Diffstat (limited to 'os')
| -rw-r--r-- | os/io/platforms/AT91SAM7X/serial_lld.h | 4 | ||||
| -rw-r--r-- | os/io/platforms/MSP430/pal_lld.c (renamed from os/ports/GCC/MSP430/pal_lld.c) | 0 | ||||
| -rw-r--r-- | os/io/platforms/MSP430/pal_lld.h (renamed from os/ports/GCC/MSP430/pal_lld.h) | 0 | ||||
| -rw-r--r-- | os/io/platforms/MSP430/platform.dox (renamed from os/ports/GCC/MSP430/port.dox) | 0 | ||||
| -rw-r--r-- | os/io/platforms/MSP430/serial_lld.c | 292 | ||||
| -rw-r--r-- | os/io/platforms/MSP430/serial_lld.h | 163 | ||||
| -rw-r--r-- | os/ports/GCC/MSP430/msp430_serial.c | 216 | ||||
| -rw-r--r-- | os/ports/GCC/MSP430/msp430_serial.h | 91 | 
8 files changed, 457 insertions, 309 deletions
| diff --git a/os/io/platforms/AT91SAM7X/serial_lld.h b/os/io/platforms/AT91SAM7X/serial_lld.h index 6156c3933..f6f704e95 100644 --- a/os/io/platforms/AT91SAM7X/serial_lld.h +++ b/os/io/platforms/AT91SAM7X/serial_lld.h @@ -138,10 +138,10 @@ typedef struct {  /*===========================================================================*/
  /** @cond never*/
 -#if defined(USE_SAM7X_USART0)
 +#if USE_SAM7X_USART0
  extern SerialDriver COM1;
  #endif
 -#if defined(USE_SAM7X_USART1)
 +#if USE_SAM7X_USART1
  extern SerialDriver COM2;
  #endif
 diff --git a/os/ports/GCC/MSP430/pal_lld.c b/os/io/platforms/MSP430/pal_lld.c index 885a58dbc..885a58dbc 100644 --- a/os/ports/GCC/MSP430/pal_lld.c +++ b/os/io/platforms/MSP430/pal_lld.c diff --git a/os/ports/GCC/MSP430/pal_lld.h b/os/io/platforms/MSP430/pal_lld.h index 94407a849..94407a849 100644 --- a/os/ports/GCC/MSP430/pal_lld.h +++ b/os/io/platforms/MSP430/pal_lld.h diff --git a/os/ports/GCC/MSP430/port.dox b/os/io/platforms/MSP430/platform.dox index 232053f06..232053f06 100644 --- a/os/ports/GCC/MSP430/port.dox +++ b/os/io/platforms/MSP430/platform.dox diff --git a/os/io/platforms/MSP430/serial_lld.c b/os/io/platforms/MSP430/serial_lld.c new file mode 100644 index 000000000..c1ac3035c --- /dev/null +++ b/os/io/platforms/MSP430/serial_lld.c @@ -0,0 +1,292 @@ +/*
 +    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 <http://www.gnu.org/licenses/>.
 +*/
 +
 +/**
 + * @file templates/serial_lld.c
 + * @brief Serial Driver subsystem low level driver source template
 + * @addtogroup SERIAL_LLD
 + * @{
 + */
 +
 +#include <ch.h>
 +#include <serial.h>
 +
 +#include <signal.h>
 +
 +#include "board.h"
 +
 +#if USE_MSP430_USART0 || defined(__DOXYGEN__)
 +/** @brief USART0 serial driver identifier.*/
 +SerialDriver COM1;
 +#endif
 +#if USE_MSP430_USART1 || defined(__DOXYGEN__)
 +/** @brief USART1 serial driver identifier.*/
 +SerialDriver COM2;
 +#endif
 +
 +/** @brief Driver default configuration.*/
 +static const SerialDriverConfig default_config = {
 +  UBR(DEFAULT_USART_BITRATE),
 +  0,
 +  CHAR
 +};
 +
 +/*===========================================================================*/
 +/* Low Level Driver local functions.                                         */
 +/*===========================================================================*/
 +
 +static void set_error(uint8_t urctl, SerialDriver *sdp) {
 +  sdflags_t sts = 0;
 +
 +  if (urctl & OE)
 +    sts |= SD_OVERRUN_ERROR;
 +  if (urctl & PE)
 +    sts |= SD_PARITY_ERROR;
 +  if (urctl & FE)
 +    sts |= SD_FRAMING_ERROR;
 +  if (urctl & BRK)
 +    sts |= SD_BREAK_DETECTED;
 +  chSysLockFromIsr();
 +  sdAddFlagsI(sdp, sts);
 +  chSysUnlockFromIsr();
 +}
 +
 +#if USE_MSP430_USART0 || defined(__DOXYGEN__)
 +static void notify1(void) {
 +
 +  if (!(U0IE & UTXIE0)) {
 +    chSysLockFromIsr();
 +    U0TXBUF = (uint8_t)sdRequestDataI(&COM1);
 +    chSysUnlockFromIsr();
 +    U0IE |= UTXIE0;
 +  }
 +}
 +
 +/**
 + * @brief USART0 initialization.
 + * @param[in] config the architecture-dependent serial driver configuration
 + */
 +void usart0_init(const SerialDriverConfig *config) {
 +
 +  U0CTL = SWRST;                /* Resets the USART, it should already be.*/
 +  /* USART init */
 +  U0TCTL = SSEL0 | SSEL1;       /* SMCLK as clock source.*/
 +  U0MCTL = config->mod;         /* Modulator.*/
 +  U0BR1 = (uint8_t)(config->div >> 8);  /* Divider high.*/
 +  U0BR0 = (uint8_t)(config->div >> 0);  /* Divider low.*/
 +  /* Clear USART status.*/
 +  (void)U0RXBUF;
 +  U0RCTL = 0;
 +  /* USART enable.*/
 +  U0ME |= UTXE0 + URXE0;        /* Enables the USART.*/
 +  U0CTL = config->ctl & ~SWRST; /* Various settings, clears reset state.*/
 +  U0IE |= URXIE0;               /* Enables RX interrupt.*/
 +}
 +
 +/**
 + * @brief USART0 de-initialization.
 + */
 +void usart0_deinit(void) {
 +
 +  U0IE &= ~URXIE0;
 +  U0CTL = SWRST;
 +}
 +#endif /* USE_MSP430_USART0 */
 +
 +#if USE_MSP430_USART1 || defined(__DOXYGEN__)
 +static void notify2(void) {
 +
 +  if (!(U1IE & UTXIE1)) {
 +    U1TXBUF = (uint8_t)sdRequestDataI(&COM2);
 +    U1IE |= UTXIE1;
 +  }
 +}
 +
 +/**
 + * @brief USART1 initialization.
 + * @param[in] config the architecture-dependent serial driver configuration
 + */
 +void usart1_init(const SerialDriverConfig *config) {
 +
 +  U1CTL = SWRST;                /* Resets the USART, it should already be.*/
 +  /* USART init.*/
 +  U1TCTL = SSEL0 | SSEL1;       /* SMCLK as clock source.*/
 +  U1MCTL = config->mod;         /* Modulator.*/
 +  U1BR1 = (uint8_t)(config->div >> 8);  /* Divider high.*/
 +  U1BR0 = (uint8_t)(config->div >> 0);  /* Divider low.*/
 +  /* Clear USART status.*/
 +  (void)U0RXBUF;
 +  U1RCTL = 0;
 +  /* USART enable.*/
 +  U1ME |= UTXE0 + URXE0;        /* Enables the USART.*/
 +  U1CTL = config->ctl & ~SWRST; /* Various settings, clears reset state.*/
 +  U1IE |= URXIE0;               /* Enables RX interrupt.*/
 +}
 +
 +/**
 + * @brief USART1 de-initialization.
 + */
 +void usart1_deinit(void) {
 +
 +  U1IE &= ~URXIE0;
 +  U1CTL = SWRST;
 +}
 +#endif /* USE_MSP430_USART1 */
 +
 +/*===========================================================================*/
 +/* Low Level Driver interrupt handlers.                                      */
 +/*===========================================================================*/
 +
 +#if USE_MSP430_USART0 || defined(__DOXYGEN__)
 +CH_IRQ_HANDLER(USART0TX_VECTOR) {
 +  msg_t b;
 +
 +  CH_IRQ_PROLOGUE();
 +
 +  chSysLockFromIsr();
 +  b = sdRequestDataI(&COM1);
 +  chSysUnlockFromIsr();
 +  if (b < Q_OK)
 +    U0IE &= ~UTXIE0;
 +  else
 +    U0TXBUF = b;
 +
 +  CH_IRQ_EPILOGUE();
 +}
 +
 +CH_IRQ_HANDLER(USART0RX_VECTOR) {
 +  uint8_t urctl;
 +
 +  CH_IRQ_PROLOGUE();
 +
 +  if ((urctl = U0RCTL) & RXERR)
 +    set_error(urctl, &COM1);
 +  chSysLockFromIsr();
 +  sdIncomingDataI(&COM1, U0RXBUF);
 +  chSysUnlockFromIsr();
 +
 +  CH_IRQ_EPILOGUE();
 +}
 +#endif /* USE_MSP430_USART0 */
 +
 +#if USE_MSP430_USART1 || defined(__DOXYGEN__)
 +CH_IRQ_HANDLER(USART1TX_VECTOR) {
 +  msg_t b;
 +
 +  CH_IRQ_PROLOGUE();
 +
 +  chSysLockFromIsr();
 +  b = sdRequestDataI(&COM2);
 +  chSysUnlockFromIsr();
 +  if (b < Q_OK)
 +    U1IE &= ~UTXIE1;
 +  else
 +    U1TXBUF = b;
 +
 +  CH_IRQ_EPILOGUE();
 +}
 +
 +CH_IRQ_HANDLER(USART1RX_VECTOR) {
 +  uint8_t urctl;
 +
 +  CH_IRQ_PROLOGUE();
 +
 +  if ((urctl = U1RCTL) & RXERR)
 +    set_error(urctl, &COM2);
 +  chSysLockFromIsr();
 +  sdIncomingDataI(&COM2, U1RXBUF);
 +  chSysUnlockFromIsr();
 +
 +  CH_IRQ_EPILOGUE();
 +}
 +#endif /* USE_MSP430_USART1 */
 +
 +/*===========================================================================*/
 +/* Low Level Driver exported functions.                                      */
 +/*===========================================================================*/
 +
 +/**
 + * Low level serial driver initialization. + */
 +void sd_lld_init(void) {
 +
 +#if USE_MSP430_USART0
 +  sdObjectInit(&COM1, NULL, notify1);
 +  /* I/O pins for USART0.*/
 +  P3SEL |= BV(4) + BV(5);
 +#endif
 +
 +#if USE_MSP430_USART1
 +  sdObjectInit(&COM2, NULL, notify2);
 +  /* I/O pins for USART1.*/
 +  P3SEL |= BV(6) + BV(7);
 +#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.
 + *                   If this parameter is set to @p NULL then a default
 + *                   configuration is used.
 + */
 +void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config) {
 +
 +  if (config == NULL)
 +    config = &default_config;
 +
 +#if USE_MSP430_USART0
 +  if (&COM1 == sdp) {
 +    usart0_init(config);
 +    return;
 +  }
 +#endif
 +#if USE_MSP430_USART1
 +  if (&COM2 == sdp) {
 +    usart1_init(config);
 +    return;
 +  }
 +#endif
 +}
 +
 +/**
 + * @brief Low level serial driver stop.
 + * @details De-initializes the USART, stops the associated clock, resets the
 + *          interrupt vector.
 + *
 + * @param[in] sdp pointer to a @p SerialDriver object
 + */
 +void sd_lld_stop(SerialDriver *sdp) {
 +
 +#if USE_MSP430_USART0
 +  if (&COM1 == sdp) {
 +    usart0_deinit();
 +    return;
 +  }
 +#endif
 +#if USE_MSP430_USART1
 +  if (&COM2 == sdp) {
 +    usart1_deinit();
 +    return;
 +  }
 +#endif
 +}
 +
 +/** @} */
 diff --git a/os/io/platforms/MSP430/serial_lld.h b/os/io/platforms/MSP430/serial_lld.h new file mode 100644 index 000000000..bef3d0367 --- /dev/null +++ b/os/io/platforms/MSP430/serial_lld.h @@ -0,0 +1,163 @@ +/*
 +    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 <http://www.gnu.org/licenses/>.
 +*/
 +
 +/**
 + * @file templates/serial_lld.h
 + * @brief Serial Driver subsystem low level driver header template
 + * @addtogroup SERIAL_LLD
 + * @{
 + */
 +
 +#ifndef _SERIAL_LLD_H_
 +#define _SERIAL_LLD_H_
 +
 +/*===========================================================================*/
 +/* Driver pre-compile time settings.                                         */
 +/*===========================================================================*/
 +
 +/**
 + * @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 32 bytes for both the transmission and receive buffers.
 + */
 +#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
 +#define SERIAL_BUFFERS_SIZE 32
 +#endif
 +
 +/**
 + * @brief Default bit rate.
 + * @details Configuration parameter, at startup the UARTs are configured at
 + * this speed.
 + */
 +#if !defined(DEFAULT_USART_BITRATE) || defined(__DOXYGEN__)
 +#define DEFAULT_USART_BITRATE 38400
 +#endif
 +
 +/**
 + * @brief USART0 driver enable switch.
 + * @details If set to @p TRUE the support for USART0 is included.
 + * @note The default is @p TRUE.
 + */
 +#if !defined(USE_MSP430_USART0) || defined(__DOXYGEN__)
 +#define USE_MSP430_USART0 TRUE
 +#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_MSP430_USART1) || defined(__DOXYGEN__)
 +#define USE_MSP430_USART1 FALSE
 +#endif
 +
 +/*===========================================================================*/
 +/* Unsupported event flags and custom events.                                */
 +/*===========================================================================*/
 +
 +/*===========================================================================*/
 +/* Driver data structures and types.                                         */
 +/*===========================================================================*/
 +
 +/**
 + * Serial Driver condition flags type.
 + */
 +typedef uint8_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 Macro for baud rate computation.
 + * @note Make sure the final baud rate is within tolerance.
 + */
 +#define UBR(b) (SMCLK / (b))
 +
 +/**
 + * @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 {
 +  uint16_t              div;
 +  uint8_t               mod;
 +  uint8_t               ctl;
 +} SerialDriverConfig;
 +
 +/*===========================================================================*/
 +/* External declarations.                                                    */
 +/*===========================================================================*/
 +
 +/** @cond never*/
 +#if USE_MSP430_USART0
 +extern SerialDriver COM1;
 +#endif
 +#if USE_MSP430_USART1
 +extern SerialDriver COM2;
 +#endif
 +
 +#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
 +/** @endcond*/
 +
 +#endif /* _SERIAL_LLD_H_ */
 +
 +/** @} */
 diff --git a/os/ports/GCC/MSP430/msp430_serial.c b/os/ports/GCC/MSP430/msp430_serial.c deleted file mode 100644 index a7da03c60..000000000 --- a/os/ports/GCC/MSP430/msp430_serial.c +++ /dev/null @@ -1,216 +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 <http://www.gnu.org/licenses/>.
 -*/
 -
 -/**
 - * @file MSP430/msp430_serial.c
 - * @brief MSP430 Serial driver code.
 - * @addtogroup MSP430_SERIAL
 - * @{
 - */
 -
 -#include <ch.h>
 -#include <signal.h>
 -
 -#include "board.h"
 -#include "msp430_serial.h"
 -
 -static void SetError(uint8_t urctl, FullDuplexDriver *com) {
 -  dflags_t sts = 0;
 -
 -  if (urctl & OE)
 -    sts |= SD_OVERRUN_ERROR;
 -  if (urctl & PE)
 -    sts |= SD_PARITY_ERROR;
 -  if (urctl & FE)
 -    sts |= SD_FRAMING_ERROR;
 -  if (urctl & BRK)
 -    sts |= SD_BREAK_DETECTED;
 -  chSysLockFromIsr();
 -  chFDDAddFlagsI(com, sts);
 -  chSysUnlockFromIsr();
 -}
 -
 -#if USE_MSP430_USART0 || defined(__DOXYGEN__)
 -
 -/** @brief USART0 serial driver identifier.*/
 -FullDuplexDriver COM1;
 -
 -static uint8_t ib1[SERIAL_BUFFERS_SIZE];
 -static uint8_t ob1[SERIAL_BUFFERS_SIZE];
 -
 -CH_IRQ_HANDLER(USART0TX_VECTOR) {
 -  msg_t b;
 -
 -  CH_IRQ_PROLOGUE();
 -
 -  chSysLockFromIsr();
 -  b = chFDDRequestDataI(&COM1);
 -  chSysUnlockFromIsr();
 -  if (b < Q_OK)
 -    U0IE &= ~UTXIE0;
 -  else
 -    U0TXBUF = b;
 -
 -  CH_IRQ_EPILOGUE();
 -}
 -
 -CH_IRQ_HANDLER(USART0RX_VECTOR) {
 -  uint8_t urctl;
 -
 -  CH_IRQ_PROLOGUE();
 -
 -  if ((urctl = U0RCTL) & RXERR)
 -    SetError(urctl, &COM1);
 -  chSysLockFromIsr();
 -  chFDDIncomingDataI(&COM1, U0RXBUF);
 -  chSysUnlockFromIsr();
 -
 -  CH_IRQ_EPILOGUE();
 -}
 -
 -static void OutNotify1(void) {
 -
 -  if (!(U0IE & UTXIE0)) {
 -    chSysLockFromIsr();
 -    U0TXBUF = (uint8_t)chFDDRequestDataI(&COM1);
 -    chSysUnlockFromIsr();
 -    U0IE |= UTXIE0;
 -  }
 -}
 -
 -/**
 - * @brief USART0 setup.
 - * @details This function must be invoked with interrupts disabled.
 - * @param div The divider value as calculated by the @p UBR() macro.
 - * @param mod The value for the @p U0MCTL register.
 - * @param ctl The value for the @p U0CTL register.
 - * @note Does not reset the I/O queues.
 - */
 -void usart0_setup(uint16_t div, uint8_t mod, uint8_t ctl) {
 -
 -  U0CTL = SWRST;                /* Resets the USART, it should already be */
 -  /* USART init */
 -  U0TCTL = SSEL0 | SSEL1;       /* SMCLK as clock source */
 -  U0MCTL = mod;                 /* Modulator */
 -  U0BR1 = (uint8_t)(div >> 8);  /* Divider high */
 -  U0BR0 = (uint8_t)(div >> 0);  /* Divider low */
 -  /* Clear USART status */
 -  (void)U0RXBUF;
 -  U0RCTL = 0;
 -  /* USART enable */
 -  P3SEL |= BV(4) + BV(5);       /* I/O pins for USART 0 */
 -  U0ME |= UTXE0 + URXE0;        /* Enables the USART */
 -  U0CTL = ctl & ~SWRST;         /* Various settings, clears reset state */
 -  U0IE |= URXIE0;               /* Enables RX interrupt */
 -}
 -#endif /* USE_MSP430_USART0 */
 -
 -#if USE_MSP430_USART1 || defined(__DOXYGEN__)
 -
 -/** @brief USART1 serial driver identifier.*/
 -FullDuplexDriver COM2;
 -
 -static uint8_t ib2[SERIAL_BUFFERS_SIZE];
 -static uint8_t ob2[SERIAL_BUFFERS_SIZE];
 -
 -CH_IRQ_HANDLER(USART1TX_VECTOR) {
 -  msg_t b;
 -
 -  CH_IRQ_PROLOGUE();
 -
 -  chSysLockFromIsr();
 -  b = chFDDRequestDataI(&COM2);
 -  chSysUnlockFromIsr();
 -  if (b < Q_OK)
 -    U1IE &= ~UTXIE1;
 -  else
 -    U1TXBUF = b;
 -
 -  CH_IRQ_EPILOGUE();
 -}
 -
 -CH_IRQ_HANDLER(USART1RX_VECTOR) {
 -  uint8_t urctl;
 -
 -  CH_IRQ_PROLOGUE();
 -
 -  if ((urctl = U1RCTL) & RXERR)
 -    SetError(urctl, &COM2);
 -  chSysLockFromIsr();
 -  chFDDIncomingDataI(&COM2, U1RXBUF);
 -  chSysUnlockFromIsr();
 -
 -  CH_IRQ_EPILOGUE();
 -}
 -
 -static void OutNotify2(void) {
 -
 -  if (!(U1IE & UTXIE1)) {
 -    U1TXBUF = (uint8_t)chFDDRequestDataI(&COM2);
 -    U1IE |= UTXIE1;
 -  }
 -}
 -
 -/**
 - * @brief USART1 setup.
 - * @details This function must be invoked with interrupts disabled.
 - * @param[in] div the divider value as calculated by the @p UBR() macro
 - * @param[in] mod the value for the @p U1MCTL register
 - * @param[in] ctl the value for the @p U1CTL register.
 - * @note Must be invoked with interrupts disabled.
 - * @note Does not reset the I/O queues.
 - */
 -void usart1_setup(uint16_t div, uint8_t mod, uint8_t ctl) {
 -
 -  U1CTL = SWRST;                /* Resets the USART, it should already be */
 -  /* USART init */
 -  U1TCTL = SSEL0 | SSEL1;       /* SMCLK as clock source */
 -  U1MCTL = mod;                 /* Modulator */
 -  U1BR1 = (uint8_t)(div >> 8);  /* Divider high */
 -  U1BR0 = (uint8_t)(div >> 0);  /* Divider low */
 -  /* Clear USART status */
 -  (void)U0RXBUF;
 -  U1RCTL = 0;
 -  /* USART enable */
 -  P3SEL |= BV(6) + BV(7);       /* I/O pins for USART 1 */
 -  U1ME |= UTXE0 + URXE0;        /* Enables the USART */
 -  U1CTL = ctl & ~SWRST;         /* Various settings, clears reset state */
 -  U1IE |= URXIE0;               /* Enables RX interrupt */
 -}
 -#endif
 -
 -/**
 - * @brief Serial driver initialization.
 - * @note The serial ports are initialized at @p 38400-8-N-1 by default. - */
 -void serial_init(void) {
 -
 -  /* I/O queues setup.*/
 -#if USE_MSP430_USART0
 -  chFDDInit(&COM1, ib1, sizeof ib1, NULL, ob1, sizeof ob1, OutNotify1);
 -  usart0_setup(UBR(DEFAULT_USART_BITRATE), 0, CHAR);
 -#endif
 -
 -#if USE_MSP430_USART1
 -  chFDDInit(&COM2, ib2, sizeof ib2, NULL, ob2, sizeof ob2, OutNotify2);
 -  usart1_setup(UBR(DEFAULT_USART_BITRATE), 0, CHAR);
 -#endif
 -}
 -
 -/** @} */
 diff --git a/os/ports/GCC/MSP430/msp430_serial.h b/os/ports/GCC/MSP430/msp430_serial.h deleted file mode 100644 index 487dc22ec..000000000 --- a/os/ports/GCC/MSP430/msp430_serial.h +++ /dev/null @@ -1,91 +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 <http://www.gnu.org/licenses/>.
 -*/
 -
 -/**
 - * @file MSP430/msp430_serial.h
 - * @brief MSP430 Serial driver macros and structures.
 - * @addtogroup MSP430_SERIAL
 - * @{
 - */
 -
 -#ifndef _MSP430_SERIAL_H_
 -#define _MSP430_SERIAL_H_
 -
 -/**
 - * @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 32 bytes for both the transmission and receive buffers.
 - */
 -#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
 -#define SERIAL_BUFFERS_SIZE 32
 -#endif
 -
 -/**
 - * @brief Default bit rate.
 - * @details Configuration parameter, at startup the UARTs are configured at
 - * this speed.
 - * @note It is possible to use @p SetUART() in order to change the working
 - *       parameters at runtime.
 - */
 -#if !defined(DEFAULT_USART_BITRATE) || defined(__DOXYGEN__)
 -#define DEFAULT_USART_BITRATE 38400
 -#endif
 -
 -/**
 - * @brief USART0 driver enable switch.
 - * @details If set to @p TRUE the support for USART0 is included.
 - * @note The default is @p TRUE. - */
 -#if !defined(USE_MSP430_USART0) || defined(__DOXYGEN__)
 -#define USE_MSP430_USART0 TRUE
 -#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_MSP430_USART1) || defined(__DOXYGEN__)
 -#define USE_MSP430_USART1 FALSE
 -#endif
 -
 -/**
 - * @brief Macro for baud rate computation.
 - * @note Make sure the final baud rate is within tolerance.
 - */
 -#define UBR(b) (SMCLK / (b))
 -
 -#ifdef __cplusplus
 -extern "C" {
 -#endif
 -  void serial_init(void);
 -  void usart0_setup(uint16_t div, uint8_t mod, uint8_t ctl);
 -  void usart1_setup(uint16_t div, uint8_t mod, uint8_t ctl);
 -#ifdef __cplusplus
 -}
 -#endif
 -
 -/** @cond never*/
 -extern FullDuplexDriver COM1, COM2;
 -/** @endcond*/
 -
 -#endif /* _MSP430_SERIAL_H_ */
 -
 -/** @} */
 | 
