diff options
Diffstat (limited to 'os')
| -rw-r--r-- | os/hal/platforms/STM32/hal_lld_f103.h | 2 | ||||
| -rw-r--r-- | os/hal/platforms/STM32/hal_lld_f105_f107.h | 2 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/hal_lld.h | 20 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/hal_lld_stm8l_hd.h | 81 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/hal_lld_stm8l_md.h | 81 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/hal_lld_stm8l_mdp.h | 81 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/pal_lld.h | 20 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/platform.dox | 4 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/serial_lld.c | 61 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/serial_lld.h | 15 | ||||
| -rw-r--r-- | os/hal/platforms/STM8L/shared_isr.c | 2 | 
11 files changed, 314 insertions, 55 deletions
| diff --git a/os/hal/platforms/STM32/hal_lld_f103.h b/os/hal/platforms/STM32/hal_lld_f103.h index a459badf0..3364ade9e 100644 --- a/os/hal/platforms/STM32/hal_lld_f103.h +++ b/os/hal/platforms/STM32/hal_lld_f103.h @@ -19,7 +19,7 @@  /**
   * @defgroup STM32F103_HAL STM32F103 HAL Support
 - * @brief HAL support for STM32 LD, MD and HD families.
 + * @details HAL support for STM32 LD, MD and HD families.
   *
   * @ingroup HAL
   */
 diff --git a/os/hal/platforms/STM32/hal_lld_f105_f107.h b/os/hal/platforms/STM32/hal_lld_f105_f107.h index 7ffe895b3..4605ee78f 100644 --- a/os/hal/platforms/STM32/hal_lld_f105_f107.h +++ b/os/hal/platforms/STM32/hal_lld_f105_f107.h @@ -19,7 +19,7 @@  /**
   * @defgroup STM32F10X_CL_HAL STM32F105/F107 HAL Support
 - * @brief HAL support for STM32 CL (Connectivity Line) family.
 + * @details HAL support for STM32 CL (Connectivity Line) family.
   *
   * @ingroup HAL
   */
 diff --git a/os/hal/platforms/STM8L/hal_lld.h b/os/hal/platforms/STM8L/hal_lld.h index 8d658e6dc..45fcc29aa 100644 --- a/os/hal/platforms/STM8L/hal_lld.h +++ b/os/hal/platforms/STM8L/hal_lld.h @@ -16,6 +16,7 @@      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    STM8L/hal_lld.h
   * @brief   STM8L HAL subsystem low level driver source.
 @@ -26,6 +27,11 @@   *          - LSECLK (@p 0 if disabled or frequency in Hertz).
   *          - LSEBYPASS (@p TRUE if external oscillator rather than a crystal).
   *          .
 + *          One of the following macros must also be defined:
 + *          - STM8L15X_MD for Medium Density devices.
 + *          - STM8L15X_MDP for Medium Density Plus devices.
 + *          - STM8L15X_HD for High Density devices.
 + *          .
   *
   * @addtogroup HAL
   * @{
 @@ -37,15 +43,21 @@  #undef FALSE
  #undef TRUE
 -#if defined (STM8L15X_MD) || defined (STM8L15X_MDP) || defined (STM8L15X_HD)
  #include "stm8l15x.h"
 -#else
 -#error "unsupported or invalid STM8L platform"
 -#endif
  #define FALSE 0
  #define TRUE (!FALSE)
 +#if defined (STM8L15X_MD)
 +#include "hal_lld_stm8l_md.h"
 +#elif defined (STM8L15X_MDP)
 +#include "hal_lld_stm8l_mdp.h"
 +#elif defined (STM8L15X_HD)
 +#include "hal_lld_stm8l_hd.h"
 +#else
 +#error "unspecified, unsupported or invalid STM8L platform"
 +#endif
 +
  /*===========================================================================*/
  /* Driver constants.                                                         */
  /*===========================================================================*/
 diff --git a/os/hal/platforms/STM8L/hal_lld_stm8l_hd.h b/os/hal/platforms/STM8L/hal_lld_stm8l_hd.h new file mode 100644 index 000000000..9acad669b --- /dev/null +++ b/os/hal/platforms/STM8L/hal_lld_stm8l_hd.h @@ -0,0 +1,81 @@ +/*
 +    ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 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/>.
 +*/
 +
 +/**
 + * @defgroup STM8L_HD_HAL STM8L High Density sub-family
 + *
 + * @ingroup HAL
 + */
 +
 +/**
 + * @file    STM8L/hal_lld_stm8l_hd.h
 + * @brief   STM8L High Density sub-family capabilities descriptor.
 + *
 + * @addtogroup STM8L_HD_HAL
 + * @{
 + */
 +
 +#ifndef _HAL_LLD_STM8L_HD_H_
 +#define _HAL_LLD_STM8L_HD_H_
 +
 +/*===========================================================================*/
 +/* Sub-family capabilities.                                                  */
 +/*===========================================================================*/
 +
 +#define STM8L_HAS_ADC1              TRUE
 +
 +#define STM8L_HAS_BEEP              TRUE
 +
 +#define STM8L_HAS_COMP1             TRUE
 +#define STM8L_HAS_COMP2             TRUE
 +
 +#define STM8L_HAS_DAC1              TRUE
 +
 +#define STM8L_HAS_DMA1              TRUE
 +
 +#define STM8L_HAS_GPIOA             TRUE
 +#define STM8L_HAS_GPIOB             TRUE
 +#define STM8L_HAS_GPIOC             TRUE
 +#define STM8L_HAS_GPIOD             TRUE
 +#define STM8L_HAS_GPIOE             TRUE
 +#define STM8L_HAS_GPIOF             TRUE
 +#define STM8L_HAS_GPIOG             TRUE
 +#define STM8L_HAS_GPIOH             TRUE
 +#define STM8L_HAS_GPIOI             TRUE
 +
 +#define STM8L_HAS_I2C1              TRUE
 +
 +#define STM8L_HAS_LCD               TRUE
 +
 +#define STM8L_HAS_SPI1              TRUE
 +#define STM8L_HAS_SPI2              TRUE
 +
 +#define STM8L_HAS_TIM1              TRUE
 +#define STM8L_HAS_TIM2              TRUE
 +#define STM8L_HAS_TIM3              TRUE
 +#define STM8L_HAS_TIM4              TRUE
 +#define STM8L_HAS_TIM5              TRUE
 +
 +#define STM8L_HAS_USART1            TRUE
 +#define STM8L_HAS_USART2            TRUE
 +#define STM8L_HAS_USART3            TRUE
 +
 +#endif /* _HAL_LLD_STM8L_HD_H_ */
 +
 +/** @} */
 diff --git a/os/hal/platforms/STM8L/hal_lld_stm8l_md.h b/os/hal/platforms/STM8L/hal_lld_stm8l_md.h new file mode 100644 index 000000000..c32ec112f --- /dev/null +++ b/os/hal/platforms/STM8L/hal_lld_stm8l_md.h @@ -0,0 +1,81 @@ +/*
 +    ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 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/>.
 +*/
 +
 +/**
 + * @defgroup STM8L_MD_HAL STM8L Medium Density sub-family
 + *
 + * @ingroup HAL
 + */
 +
 +/**
 + * @file    STM8L/hal_lld_stm8l_md.h
 + * @brief   STM8L Medium Density sub-family capabilities descriptor.
 + *
 + * @addtogroup STM8L_MD_HAL
 + * @{
 + */
 +
 +#ifndef _HAL_LLD_STM8L_MD_H_
 +#define _HAL_LLD_STM8L_MD_H_
 +
 +/*===========================================================================*/
 +/* Sub-family capabilities.                                                  */
 +/*===========================================================================*/
 +
 +#define STM8L_HAS_ADC1              TRUE
 +
 +#define STM8L_HAS_BEEP              TRUE
 +
 +#define STM8L_HAS_COMP1             TRUE
 +#define STM8L_HAS_COMP2             TRUE
 +
 +#define STM8L_HAS_DAC1              TRUE
 +
 +#define STM8L_HAS_DMA1              TRUE
 +
 +#define STM8L_HAS_GPIOA             TRUE
 +#define STM8L_HAS_GPIOB             TRUE
 +#define STM8L_HAS_GPIOC             TRUE
 +#define STM8L_HAS_GPIOD             TRUE
 +#define STM8L_HAS_GPIOE             TRUE
 +#define STM8L_HAS_GPIOF             TRUE
 +#define STM8L_HAS_GPIOG             TRUE
 +#define STM8L_HAS_GPIOH             FALSE
 +#define STM8L_HAS_GPIOI             FALSE
 +
 +#define STM8L_HAS_I2C1              TRUE
 +
 +#define STM8L_HAS_LCD               TRUE
 +
 +#define STM8L_HAS_SPI1              TRUE
 +#define STM8L_HAS_SPI2              FALSE
 +
 +#define STM8L_HAS_TIM1              TRUE
 +#define STM8L_HAS_TIM2              TRUE
 +#define STM8L_HAS_TIM3              TRUE
 +#define STM8L_HAS_TIM4              TRUE
 +#define STM8L_HAS_TIM5              FALSE
 +
 +#define STM8L_HAS_USART1            TRUE
 +#define STM8L_HAS_USART2            FALSE
 +#define STM8L_HAS_USART3            FALSE
 +
 +#endif /* _HAL_LLD_STM8L_MD_H_ */
 +
 +/** @} */
 diff --git a/os/hal/platforms/STM8L/hal_lld_stm8l_mdp.h b/os/hal/platforms/STM8L/hal_lld_stm8l_mdp.h new file mode 100644 index 000000000..f01c18af9 --- /dev/null +++ b/os/hal/platforms/STM8L/hal_lld_stm8l_mdp.h @@ -0,0 +1,81 @@ +/*
 +    ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 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/>.
 +*/
 +
 +/**
 + * @defgroup STM8L_MDP_HAL STM8L Medium Density Plus sub-family
 + *
 + * @ingroup HAL
 + */
 +
 +/**
 + * @file    STM8L/hal_lld_stm8l_mdp.h
 + * @brief   STM8L Medium Density Plus sub-family capabilities descriptor.
 + *
 + * @addtogroup STM8L_MDP_HAL
 + * @{
 + */
 +
 +#ifndef _HAL_LLD_STM8L_MDP_H_
 +#define _HAL_LLD_STM8L_MDP_H_
 +
 +/*===========================================================================*/
 +/* Sub-family capabilities.                                                  */
 +/*===========================================================================*/
 +
 +#define STM8L_HAS_ADC1              TRUE
 +
 +#define STM8L_HAS_BEEP              TRUE
 +
 +#define STM8L_HAS_COMP1             TRUE
 +#define STM8L_HAS_COMP2             TRUE
 +
 +#define STM8L_HAS_DAC1              TRUE
 +
 +#define STM8L_HAS_DMA1              TRUE
 +
 +#define STM8L_HAS_GPIOA             TRUE
 +#define STM8L_HAS_GPIOB             TRUE
 +#define STM8L_HAS_GPIOC             TRUE
 +#define STM8L_HAS_GPIOD             TRUE
 +#define STM8L_HAS_GPIOE             TRUE
 +#define STM8L_HAS_GPIOF             TRUE
 +#define STM8L_HAS_GPIOG             TRUE
 +#define STM8L_HAS_GPIOH             TRUE
 +#define STM8L_HAS_GPIOI             TRUE
 +
 +#define STM8L_HAS_I2C1              TRUE
 +
 +#define STM8L_HAS_LCD               TRUE
 +
 +#define STM8L_HAS_SPI1              TRUE
 +#define STM8L_HAS_SPI2              TRUE
 +
 +#define STM8L_HAS_TIM1              TRUE
 +#define STM8L_HAS_TIM2              TRUE
 +#define STM8L_HAS_TIM3              TRUE
 +#define STM8L_HAS_TIM4              TRUE
 +#define STM8L_HAS_TIM5              TRUE
 +
 +#define STM8L_HAS_USART1            TRUE
 +#define STM8L_HAS_USART2            TRUE
 +#define STM8L_HAS_USART3            TRUE
 +
 +#endif /* _HAL_LLD_STM8L_MDP_H_ */
 +
 +/** @} */
 diff --git a/os/hal/platforms/STM8L/pal_lld.h b/os/hal/platforms/STM8L/pal_lld.h index 64650adaf..6cf2afb26 100644 --- a/os/hal/platforms/STM8L/pal_lld.h +++ b/os/hal/platforms/STM8L/pal_lld.h @@ -95,52 +95,68 @@ typedef GPIO_TypeDef *ioportid_t;   */
  #define IOPORTS         ((PALConfig *)0x5000)
 +#if STM8L_HAS_GPIOA || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port A identifier.
   */
  #define IOPORT1         GPIOA
 +#endif
 +#if STM8L_HAS_GPIOB || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port B identifier.
   */
  #define IOPORT2         GPIOB
 +#endif
 +#if STM8L_HAS_GPIOC || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port C identifier.
   */
  #define IOPORT3         GPIOC
 +#endif
 +#if STM8L_HAS_GPIOD || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port D identifier.
   */
  #define IOPORT4         GPIOD
 +#endif
 +#if STM8L_HAS_GPIOE || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port E identifier.
   */
  #define IOPORT5         GPIOE
 +#endif
 +#if STM8L_HAS_GPIOF || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port F identifier.
   */
  #define IOPORT6         GPIOF
 +#endif
 +#if STM8L_HAS_GPIOG || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port G identifier.
   */
  #define IOPORT7         GPIOG
 +#endif
 -#if defined(STM8L15X_MDP) || defined(STM8L15X_HD)
 +#if STM8L_HAS_GPIOH || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port H identifier.
   */
  #define IOPORT8         GPIOH
 +#endif
 +#if STM8L_HAS_GPIOI || defined(__DOXYGEN__)
  /**
   * @brief   GPIO port I identifier.
   */
  #define IOPORT9         GPIOI
 -#endif /* defined(STM8L15X_MDP) || defined(STM8L15X_HD) */
 +#endif
  /*===========================================================================*/
  /* Implementation, some of the following macros could be implemented as      */
 diff --git a/os/hal/platforms/STM8L/platform.dox b/os/hal/platforms/STM8L/platform.dox index 407855f97..8646b5978 100644 --- a/os/hal/platforms/STM8L/platform.dox +++ b/os/hal/platforms/STM8L/platform.dox @@ -92,8 +92,8 @@   * @section stm8l_serial_1 Supported HW resources
   * The serial driver can support any of the following hardware resources:
   * - USART1.
 - * - USART2.
 - * - USART3.
 + * - USART2 (where present).
 + * - USART3 (where present).
   * .
   * @section stm8l_serial_2 STM8L Serial driver implementation features
   * - Clock stop for reduced power usage when the driver is in stop state.
 diff --git a/os/hal/platforms/STM8L/serial_lld.c b/os/hal/platforms/STM8L/serial_lld.c index dcb99643a..57749f371 100644 --- a/os/hal/platforms/STM8L/serial_lld.c +++ b/os/hal/platforms/STM8L/serial_lld.c @@ -63,7 +63,7 @@ SerialDriver SD3;   * @brief   Driver default configuration.
   */
  static ROMCONST SerialConfig default_config = {
 -  BBR(SERIAL_DEFAULT_BITRATE),
 +  BRR(SERIAL_DEFAULT_BITRATE),
    SD_MODE_PARITY_NONE | SD_MODE_STOP_1
  };
 @@ -71,44 +71,6 @@ static ROMCONST SerialConfig default_config = {  /* Driver local functions.                                                   */
  /*===========================================================================*/
 -/**
 - * @brief   USART initialization.
 - *
 - * @param[in] config    architecture-dependent serial driver configuration
 - * @param[in] sdp       pointer to a @p SerialDriver object
 - */
 -static void usart_init(SerialDriver *sdp, const SerialConfig *config) {
 -  USART_TypeDef *u = sdp->usart;
 -
 -  u->BRR2 = (uint8_t)(((uint8_t)(config->sc_brr >> 8) & (uint8_t)0xF0) |
 -                      ((uint8_t)config->sc_brr & (uint8_t)0x0F));
 -  u->BRR1 = (uint8_t)(config->sc_brr >> 4);
 -  u->CR1  = (uint8_t)(config->sc_mode & SD_MODE_PARITY);
 -  u->CR2  = USART_CR2_RIEN | USART_CR2_TEN | USART_CR2_REN;
 -  u->CR3  = (uint8_t)(config->sc_mode & SD_MODE_STOP);
 -  u->CR4  = 0;
 -  u->CR5  = 0;
 -  u->PSCR = 1;
 -  (void)u->SR;
 -  (void)u->DR;
 -}
 -
 -/**
 - * @brief   USART de-initialization.
 - *
 - * @param[in] sdp       pointer to a @p SerialDriver object
 - */
 -static void usart_deinit(SerialDriver *sdp) {
 -  USART_TypeDef *u = sdp->usart;
 -
 -  u->CR1  = USART_CR1_USARTD;
 -  u->CR2  = 0;
 -  u->CR3  = 0;
 -  u->CR4  = 0;
 -  u->CR5  = 0;
 -  u->PSCR = 0;
 -}
 -
  #if STM8L_SERIAL_USE_USART1 || defined(__DOXYGEN__)
  static void notify1(void) {
 @@ -204,11 +166,22 @@ void sd_lld_init(void) {   * @notapi
   */
  void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) {
 +  USART_TypeDef *u = sdp->usart;
    if (config == NULL)
      config = &default_config;
 -  usart_init(sdp, config);
 +  u->BRR2 = (uint8_t)(((uint8_t)(config->sc_brr >> 8) & (uint8_t)0xF0) |
 +                      ((uint8_t)config->sc_brr & (uint8_t)0x0F));
 +  u->BRR1 = (uint8_t)(config->sc_brr >> 4);
 +  u->CR1  = (uint8_t)(config->sc_mode & SD_MODE_PARITY);
 +  u->CR2  = USART_CR2_RIEN | USART_CR2_TEN | USART_CR2_REN;
 +  u->CR3  = (uint8_t)(config->sc_mode & SD_MODE_STOP);
 +  u->CR4  = 0;
 +  u->CR5  = 0;
 +  u->PSCR = 1;
 +  (void)u->SR;
 +  (void)u->DR;
  }
  /**
 @@ -221,8 +194,14 @@ void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) {   * @notapi
   */
  void sd_lld_stop(SerialDriver *sdp) {
 +  USART_TypeDef *u = sdp->usart;
 -  usart_deinit(sdp);
 +  u->CR1  = USART_CR1_USARTD;
 +  u->CR2  = 0;
 +  u->CR3  = 0;
 +  u->CR4  = 0;
 +  u->CR5  = 0;
 +  u->PSCR = 0;
  }
  #endif /* HAL_USE_SERIAL */
 diff --git a/os/hal/platforms/STM8L/serial_lld.h b/os/hal/platforms/STM8L/serial_lld.h index ac829cf1e..b523f048f 100644 --- a/os/hal/platforms/STM8L/serial_lld.h +++ b/os/hal/platforms/STM8L/serial_lld.h @@ -79,9 +79,16 @@  /* Derived constants and error checks.                                       */
  /*===========================================================================*/
 -#if defined(STM8L15X_MD) &&                                                 \
 -    (STM8L_SERIAL_USE_USART2 || STM8L_SERIAL_USE_USART3)
 -#error "STM8L15X_MD devices do not have USART2 and USART3"
 +#if STM8L_SERIAL_USE_USART1 && !STM8L_HAS_USART1
 +#error "USART1 enabled but not present"
 +#endif
 +
 +#if STM8L_SERIAL_USE_USART2 && !STM8L_HAS_USART2
 +#error "USART2 enabled but not present"
 +#endif
 +
 +#if STM8L_SERIAL_USE_USART3 && !STM8L_HAS_USART3
 +#error "USART3 enabled but not present"
  #endif
  /*===========================================================================*/
 @@ -142,7 +149,7 @@ typedef struct {   * @brief   Macro for baud rate computation.
   * @note    Make sure the final baud rate is within tolerance.
   */
 -#define BBR(b) (SYSCLK / (b))
 +#define BRR(b) (SYSCLK / (b))
  #if STM8L_SERIAL_USE_USART1 || defined(__DOXYGEN__)
  /**
 diff --git a/os/hal/platforms/STM8L/shared_isr.c b/os/hal/platforms/STM8L/shared_isr.c index 279c74865..6709442c5 100644 --- a/os/hal/platforms/STM8L/shared_isr.c +++ b/os/hal/platforms/STM8L/shared_isr.c @@ -23,6 +23,8 @@   * @details The STM8L shares some interrupt handlers among several sources.
   *          This module includes all the interrupt handlers that are
   *          used by more than one peripheral.
 + * @note    Only the interrupt handlers that are used by the HAL are defined
 + *          in this module.
   *
   * @addtogroup HAL
   * @{
 | 
