diff options
Diffstat (limited to 'os')
| -rw-r--r-- | os/hal/platforms/SPC563Mxx/platform.mk | 5 | ||||
| -rw-r--r-- | os/hal/platforms/SPC563Mxx/serial_lld.c | 294 | ||||
| -rw-r--r-- | os/hal/platforms/SPC563Mxx/serial_lld.h | 157 | ||||
| -rw-r--r-- | os/hal/platforms/SPC5xx/ESCI_v1/serial_lld.c | 2 | ||||
| -rw-r--r-- | os/ports/GCC/PPC/SPC563Mxx/ivor.s | 2 | ||||
| -rw-r--r-- | os/ports/GCC/PPC/chcore.c | 8 | 
6 files changed, 9 insertions, 459 deletions
| diff --git a/os/hal/platforms/SPC563Mxx/platform.mk b/os/hal/platforms/SPC563Mxx/platform.mk index e9a508857..a5ae689fe 100644 --- a/os/hal/platforms/SPC563Mxx/platform.mk +++ b/os/hal/platforms/SPC563Mxx/platform.mk @@ -1,6 +1,7 @@  # List of all the SPC56x platform files.
  PLATFORMSRC = ${CHIBIOS}/os/hal/platforms/SPC563Mxx/hal_lld.c \
 -              ${CHIBIOS}/os/hal/platforms/SPC5xx/ESCIv1/serial_lld.c
 +              ${CHIBIOS}/os/hal/platforms/SPC5xx/ESCI_v1/serial_lld.c
  # Required include directories
 -PLATFORMINC = ${CHIBIOS}/os/hal/platforms/SPC563Mxx
 +PLATFORMINC = ${CHIBIOS}/os/hal/platforms/SPC563Mxx \
 +              ${CHIBIOS}/os/hal/platforms/SPC5xx/ESCI_v1
 diff --git a/os/hal/platforms/SPC563Mxx/serial_lld.c b/os/hal/platforms/SPC563Mxx/serial_lld.c deleted file mode 100644 index e562b6c2d..000000000 --- a/os/hal/platforms/SPC563Mxx/serial_lld.c +++ /dev/null @@ -1,294 +0,0 @@ -/*
 -    ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
 -                 2011,2012 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    SPC56x/serial_lld.c
 - * @brief   SPC563 low level serial driver code.
 - *
 - * @addtogroup SERIAL
 - * @{
 - */
 -
 -#include "ch.h"
 -#include "hal.h"
 -
 -#if HAL_USE_SERIAL || defined(__DOXYGEN__)
 -
 -/*===========================================================================*/
 -/* Driver exported variables.                                                */
 -/*===========================================================================*/
 -
 -/**
 - * @brief   eSCI-A serial driver identifier.
 - */
 -#if USE_SPC563_ESCIA || defined(__DOXYGEN__)
 -SerialDriver SD1;
 -#endif
 -
 -/**
 - * @brief   eSCI-B serial driver identifier.
 - */
 -#if USE_SPC563_ESCIB || defined(__DOXYGEN__)
 -SerialDriver SD2;
 -#endif
 -
 -/*===========================================================================*/
 -/* Driver local variables.                                                   */
 -/*===========================================================================*/
 -
 -/**
 - * @brief   Driver default configuration.
 - */
 -static const SerialConfig default_config = {
 -  SERIAL_DEFAULT_BITRATE,
 -  SD_MODE_NORMAL | SD_MODE_PARITY_NONE
 -};
 -
 -/*===========================================================================*/
 -/* Driver local functions.                                                   */
 -/*===========================================================================*/
 -
 -/**
 - * @brief   eSCI initialization.
 - * @details This function must be invoked with interrupts disabled.
 - *
 - * @param[in] sdp       pointer to a @p SerialDriver object
 - * @param[in] config    the architecture-dependent serial driver configuration
 - */
 -static void esci_init(SerialDriver *sdp, const SerialConfig *config) {
 -  volatile struct ESCI_tag *escip = sdp->escip;
 -  uint8_t mode = config->sc_mode;
 -
 -  escip->CR2.R  = 0;                /* MDIS off.                            */
 -  escip->CR1.R  = 0;
 -  escip->LCR.R  = 0;
 -  escip->CR1.B.SBR = SPC563_SYSCLK / (16 * config->sc_speed);
 -  if (mode & SD_MODE_LOOPBACK)
 -    escip->CR1.B.LOOPS = 1;
 -  switch (mode & SD_MODE_PARITY) {
 -  case SD_MODE_PARITY_ODD:
 -    escip->CR1.B.PT = 1;
 -  case SD_MODE_PARITY_EVEN:
 -    escip->CR1.B.PE = 1;
 -    escip->CR1.B.M  = 1;            /* Makes it 8 bits data + 1 bit parity. */
 -  default:
 -    ;
 -  }
 -  escip->LPR.R  = 0;
 -  escip->CR1.R |= 0x0000002C;       /* RIE, TE, RE to 1.                    */
 -  escip->CR2.R |= 0x000F;           /* ORIE, NFIE, FEIE, PFIE to 1.         */
 -}
 -
 -/**
 - * @brief   eSCI de-initialization.
 - * @details This function must be invoked with interrupts disabled.
 - *
 - * @param[in] escip     pointer to an eSCI I/O block
 - */
 -static void esci_deinit(volatile struct ESCI_tag *escip) {
 -
 -  escip->LPR.R  = 0;
 -  escip->SR.R   = 0xFFFFFFFF;
 -  escip->CR1.R  = 0;
 -  escip->CR2.R  = 0x8000;           /* MDIS on.                             */
 -}
 -
 -/**
 - * @brief   Error handling routine.
 - *
 - * @param[in] sdp       pointer to a @p SerialDriver object
 - * @param[in] sr        eSCI SR register value
 - */
 -static void set_error(SerialDriver *sdp, uint32_t sr) {
 -  flagsmask_t sts = 0;
 -
 -  if (sr & 0x08000000)
 -    sts |= SD_OVERRUN_ERROR;
 -  if (sr & 0x04000000)
 -    sts |= SD_NOISE_ERROR;
 -  if (sr & 0x02000000)
 -    sts |= SD_FRAMING_ERROR;
 -  if (sr & 0x01000000)
 -    sts |= SD_PARITY_ERROR;
 -/*  if (sr & 0x00000000)
 -    sts |= SD_BREAK_DETECTED;*/
 -  chSysLockFromIsr();
 -  chnAddFlagsI(sdp, sts);
 -  chSysUnlockFromIsr();
 -}
 -
 -/**
 - * @brief   Common IRQ handler.
 - *
 - * @param[in] sdp       pointer to a @p SerialDriver object
 - */
 -static void serve_interrupt(SerialDriver *sdp) {
 -  volatile struct ESCI_tag *escip = sdp->escip;
 -
 -  uint32_t sr = escip->SR.R;
 -  escip->SR.R = 0x3FFFFFFF;                     /* Does not clear TDRE | TC.*/
 -  if (sr & 0x0F000000)                          /* OR | NF | FE | PF.       */
 -    set_error(sdp, sr);
 -  if (sr & 0x20000000) {                        /* RDRF.                    */
 -    chSysLockFromIsr();
 -    sdIncomingDataI(sdp, escip->DR.B.D);
 -    chSysUnlockFromIsr();
 -  }
 -  if (escip->CR1.B.TIE && (sr & 0x80000000)) {  /* TDRE.                    */
 -    msg_t b;
 -    chSysLockFromIsr();
 -    b = chOQGetI(&sdp->oqueue);
 -    if (b < Q_OK) {
 -      chnAddFlagsI(sdp, CHN_OUTPUT_EMPTY);
 -      escip->CR1.B.TIE = 0;
 -    }
 -    else {
 -      ESCI_A.SR.B.TDRE = 1;
 -      escip->DR.R = (uint16_t)b;
 -    }
 -    chSysUnlockFromIsr();
 -  }
 -}
 -
 -#if USE_SPC563_ESCIA || defined(__DOXYGEN__)
 -static void notify1(GenericQueue *qp) {
 -
 -  (void)qp;
 -  if (ESCI_A.SR.B.TDRE) {
 -    msg_t b = sdRequestDataI(&SD1);
 -    if (b != Q_EMPTY) {
 -      ESCI_A.SR.B.TDRE = 1;
 -      ESCI_A.CR1.B.TIE = 1;
 -      ESCI_A.DR.R = (uint16_t)b;
 -    }
 -  }
 -}
 -#endif
 -
 -#if USE_SPC563_ESCIB || defined(__DOXYGEN__)
 -static void notify2(GenericQueue *qp) {
 -
 -  (void)qp;
 -  if (ESCI_B.SR.B.TDRE) {
 -    msg_t b = sdRequestDataI(&SD2);
 -    if (b != Q_EMPTY) {
 -      ESCI_B.SR.B.TDRE = 1;
 -      ESCI_B.CR1.B.TIE = 1;
 -      ESCI_B.DR.R = (uint16_t)b;
 -    }
 -  }
 -}
 -#endif
 -
 -/*===========================================================================*/
 -/* Driver interrupt handlers.                                                */
 -/*===========================================================================*/
 -
 -#if USE_SPC563_ESCIA || defined(__DOXYGEN__)
 -/**
 - * @brief   eSCI-A interrupt handler.
 - *
 - * @isr
 - */
 -CH_IRQ_HANDLER(vector146) {
 -
 -  CH_IRQ_PROLOGUE();
 -
 -  serve_interrupt(&SD1);
 -
 -  CH_IRQ_EPILOGUE();
 -}
 -#endif
 -
 -#if USE_SPC563_ESCIB || defined(__DOXYGEN__)
 -/**
 - * @brief   eSCI-B interrupt handler.
 - *
 - * @isr
 - */
 -CH_IRQ_HANDLER(vector149) {
 -
 -  CH_IRQ_PROLOGUE();
 -
 -  serve_interrupt(&SD2);
 -
 -  CH_IRQ_EPILOGUE();
 -}
 -#endif
 -
 -/*===========================================================================*/
 -/* Driver exported functions.                                                */
 -/*===========================================================================*/
 -
 -/**
 - * @brief   Low level serial driver initialization.
 - *
 - * @notapi
 - */
 -void sd_lld_init(void) {
 -
 -#if USE_SPC563_ESCIA
 -  sdObjectInit(&SD1, NULL, notify1);
 -  SD1.escip       = &ESCI_A;
 -  ESCI_A.CR2.R    = 0x8000;                 /* MDIS ON.                     */
 -  INTC.PSR[146].R = SPC563_ESCIA_PRIORITY;
 -#endif
 -
 -#if USE_SPC563_ESCIB
 -  sdObjectInit(&SD2, NULL, notify2);
 -  SD2.escip       = &ESCI_B;
 -  ESCI_B.CR2.R    = 0x8000;                 /* MDIS ON.                     */
 -  INTC.PSR[149].R = SPC563_ESCIB_PRIORITY;
 -#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.
 - *
 - * @notapi
 - */
 -void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) {
 -
 -  if (config == NULL)
 -    config = &default_config;
 -  esci_init(sdp, config);
 -}
 -
 -/**
 - * @brief   Low level serial driver stop.
 - *
 - * @param[in] sdp       pointer to a @p SerialDriver object
 - *
 - * @notapi
 - */
 -void sd_lld_stop(SerialDriver *sdp) {
 -
 -  if (sdp->state == SD_READY)
 -    esci_deinit(sdp->escip);
 -}
 -
 -#endif /* HAL_USE_SERIAL */
 -
 -/** @} */
 diff --git a/os/hal/platforms/SPC563Mxx/serial_lld.h b/os/hal/platforms/SPC563Mxx/serial_lld.h deleted file mode 100644 index b02b160b1..000000000 --- a/os/hal/platforms/SPC563Mxx/serial_lld.h +++ /dev/null @@ -1,157 +0,0 @@ -/*
 -    ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
 -                 2011,2012 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    SPC56x/serial_lld.h
 - * @brief   SPC563 low level serial driver header.
 - *
 - * @addtogroup SERIAL
 - * @{
 - */
 -
 -#ifndef _SERIAL_LLD_H_
 -#define _SERIAL_LLD_H_
 -
 -#if HAL_USE_SERIAL || defined(__DOXYGEN__)
 -
 -/*===========================================================================*/
 -/* Driver constants.                                                         */
 -/*===========================================================================*/
 -
 -#define SD_MODE_PARITY_MASK     0x03        /**< @brief Parity field mask.  */
 -#define SD_MODE_PARITY_NONE     0x00        /**< @brief No parity.          */
 -#define SD_MODE_PARITY_EVEN     0x01        /**< @brief Even parity.        */
 -#define SD_MODE_PARITY_ODD      0x02        /**< @brief Odd parity.         */
 -
 -#define SD_MODE_NORMAL          0x00        /**< @brief Normal operations.  */
 -#define SD_MODE_LOOPBACK        0x80        /**< @brief Internal loopback.  */
 -
 -/*===========================================================================*/
 -/* Driver pre-compile time settings.                                         */
 -/*===========================================================================*/
 -
 -/**
 - * @brief   eSCI-A driver enable switch.
 - * @details If set to @p TRUE the support for eSCI-A is included.
 - * @note    The default is @p TRUE.
 - */
 -#if !defined(USE_SPC563_ESCIA) || defined(__DOXYGEN__)
 -#define USE_SPC563_ESCIA            TRUE
 -#endif
 -
 -/**
 - * @brief   eSCI-B driver enable switch.
 - * @details If set to @p TRUE the support for eSCI-B is included.
 - * @note    The default is @p TRUE.
 - */
 -#if !defined(USE_SPC563_ESCIB) || defined(__DOXYGEN__)
 -#define USE_SPC563_ESCIB            TRUE
 -#endif
 -
 -/**
 - * @brief   eSCI-A interrupt priority level setting.
 - */
 -#if !defined(SPC563_ESCIA_PRIORITY) || defined(__DOXYGEN__)
 -#define SPC563_ESCIA_PRIORITY       8
 -#endif
 -
 -/**
 - * @brief   eSCI-B interrupt priority level setting.
 - */
 -#if !defined(SPC563_ESCIB_PRIORITY) || defined(__DOXYGEN__)
 -#define SPC563_ESCIB_PRIORITY       8
 -#endif
 -
 -/*===========================================================================*/
 -/* Derived constants and error checks.                                       */
 -/*===========================================================================*/
 -
 -/*===========================================================================*/
 -/* Driver data structures and types.                                         */
 -/*===========================================================================*/
 -
 -/**
 - * @brief   Generic Serial Driver configuration structure.
 - * @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 {
 -  /**
 -   * @brief Bit rate.
 -   */
 -  uint32_t                  sc_speed;
 -  /**
 -   * @brief Mode flags.
 -   */
 -  uint8_t                   sc_mode;
 -} SerialConfig;
 -
 -/**
 - * @brief   @p SerialDriver specific data.
 - */
 -#define _serial_driver_data                                                 \
 -  _base_asynchronous_channel_data                                           \
 -  /* Driver state.*/                                                        \
 -  sdstate_t                 state;                                          \
 -  /* Input queue.*/                                                         \
 -  InputQueue                iqueue;                                         \
 -  /* Output queue.*/                                                        \
 -  OutputQueue               oqueue;                                         \
 -  /* Input circular buffer.*/                                               \
 -  uint8_t                   ib[SERIAL_BUFFERS_SIZE];                        \
 -  /* Output circular buffer.*/                                              \
 -  uint8_t                   ob[SERIAL_BUFFERS_SIZE];                        \
 -  /* End of the mandatory fields.*/                                         \
 -  /* Pointer to the volatile eSCI registers block.*/                        \
 -  volatile struct ESCI_tag  *escip;
 -
 -/*===========================================================================*/
 -/* Driver macros.                                                            */
 -/*===========================================================================*/
 -
 -/*===========================================================================*/
 -/* External declarations.                                                    */
 -/*===========================================================================*/
 -
 -#if USE_SPC563_ESCIA && !defined(__DOXYGEN__)
 -extern SerialDriver SD1;
 -#endif
 -#if USE_SPC563_ESCIB && !defined(__DOXYGEN__)
 -extern SerialDriver SD2;
 -#endif
 -
 -#ifdef __cplusplus
 -extern "C" {
 -#endif
 -  void sd_lld_init(void);
 -  void sd_lld_start(SerialDriver *sdp, const SerialConfig *config);
 -  void sd_lld_stop(SerialDriver *sdp);
 -#ifdef __cplusplus
 -}
 -#endif
 -
 -#endif /* HAL_USE_SERIAL */
 -
 -#endif /* _SERIAL_LLD_H_ */
 -
 -/** @} */
 diff --git a/os/hal/platforms/SPC5xx/ESCI_v1/serial_lld.c b/os/hal/platforms/SPC5xx/ESCI_v1/serial_lld.c index ca90d0d56..f73c31c9f 100644 --- a/os/hal/platforms/SPC5xx/ESCI_v1/serial_lld.c +++ b/os/hal/platforms/SPC5xx/ESCI_v1/serial_lld.c @@ -76,7 +76,7 @@ static void esci_init(SerialDriver *sdp, const SerialConfig *config) {    escip->CR1.B.SBR = SPC_SYSCLK / (16 * config->sc_speed);
    if (mode & SD_MODE_LOOPBACK)
      escip->CR1.B.LOOPS = 1;
 -  switch (mode & SD_MODE_PARITY) {
 +  switch (mode & SD_MODE_PARITY_MASK) {
    case SD_MODE_PARITY_ODD:
      escip->CR1.B.PT = 1;
    case SD_MODE_PARITY_EVEN:
 diff --git a/os/ports/GCC/PPC/SPC563Mxx/ivor.s b/os/ports/GCC/PPC/SPC563Mxx/ivor.s index 0eb362ed0..8e5909354 100644 --- a/os/ports/GCC/PPC/SPC563Mxx/ivor.s +++ b/os/ports/GCC/PPC/SPC563Mxx/ivor.s @@ -137,7 +137,7 @@ _IVOR10:  #endif
          bl          chSchIsPreemptionRequired
          cmpli       cr0, %r3, 0
 -        beq         cr0, .ctxrestore
 +        beq         cr0, _ivor_exit
          bl          chSchDoReschedule
          b           _ivor_exit
 diff --git a/os/ports/GCC/PPC/chcore.c b/os/ports/GCC/PPC/chcore.c index 5ad1195a4..b7525468f 100644 --- a/os/ports/GCC/PPC/chcore.c +++ b/os/ports/GCC/PPC/chcore.c @@ -36,10 +36,10 @@ void port_init(void) {  #if PPC_SUPPORTS_IVORS
      /* The CPU support IVOR registers, the kernel requires IVOR4 and IVOR10
         and the initialization is performed here.*/
 -    asm volatile ("li          %r3, _IVOR4@l        \t\n"
 -                  "mtIVOR4     %r3                  \t\n"
 -                  "li          %r3, _IVOR10@l       \t\n"
 -                  "mtIVOR10    %r3" : : : "memory");
 +    asm volatile ("li          %%r3, _IVOR4@l       \t\n"
 +                  "mtIVOR4     %%r3                 \t\n"
 +                  "li          %%r3, _IVOR10@l      \t\n"
 +                  "mtIVOR10    %%r3" : : : "memory");
  #endif
  }
 | 
