diff options
Diffstat (limited to 'os/hal/platforms/STM32F0xx')
| -rw-r--r-- | os/hal/platforms/STM32F0xx/adc_lld.c | 292 | ||||
| -rw-r--r-- | os/hal/platforms/STM32F0xx/adc_lld.h | 293 | ||||
| -rw-r--r-- | os/hal/platforms/STM32F0xx/platform.mk | 1 | 
3 files changed, 586 insertions, 0 deletions
| diff --git a/os/hal/platforms/STM32F0xx/adc_lld.c b/os/hal/platforms/STM32F0xx/adc_lld.c new file mode 100644 index 000000000..751f15afd --- /dev/null +++ b/os/hal/platforms/STM32F0xx/adc_lld.c @@ -0,0 +1,292 @@ +/*
 +    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    STM32F0xx/adc_lld.c
 + * @brief   STM32F0xx ADC subsystem low level driver source.
 + *
 + * @addtogroup ADC
 + * @{
 + */
 +
 +#include "ch.h"
 +#include "hal.h"
 +
 +#if HAL_USE_ADC || defined(__DOXYGEN__)
 +
 +/*===========================================================================*/
 +/* Driver exported variables.                                                */
 +/*===========================================================================*/
 +
 +/** @brief ADC1 driver identifier.*/
 +#if STM32_ADC_USE_ADC1 || defined(__DOXYGEN__)
 +ADCDriver ADCD1;
 +#endif
 +
 +/*===========================================================================*/
 +/* Driver local variables.                                                   */
 +/*===========================================================================*/
 +
 +/*===========================================================================*/
 +/* Driver local functions.                                                   */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   Stops an ongoing conversion, if any.
 + *
 + * @param[in] adc       pointer to the ADC registers block
 + */
 +static void adc_lld_stop_adc(ADC_TypeDef *adc) {
 +
 +  if (adc->CR & ADC_CR_ADSTART) {
 +    adc->CR |= ADC_CR_ADSTP;
 +    while (adc->CR & ADC_CR_ADSTP)
 +      ;
 +  }
 +}
 +
 +/**
 + * @brief   ADC DMA ISR service routine.
 + *
 + * @param[in] adcp      pointer to the @p ADCDriver object
 + * @param[in] flags     pre-shifted content of the ISR register
 + */
 +static void adc_lld_serve_rx_interrupt(ADCDriver *adcp, uint32_t flags) {
 +
 +  /* DMA errors handling.*/
 +  if ((flags & (STM32_DMA_ISR_TEIF | STM32_DMA_ISR_DMEIF)) != 0) {
 +    /* DMA, this could help only if the DMA tries to access an unmapped
 +       address space or violates alignment rules.*/
 +    _adc_isr_error_code(adcp, ADC_ERR_DMAFAILURE);
 +  }
 +  else {
 +    /* It is possible that the conversion group has already be reset by the
 +       ADC error handler, in this case this interrupt is spurious.*/
 +    if (adcp->grpp != NULL) {
 +      if ((flags & STM32_DMA_ISR_HTIF) != 0) {
 +        /* Half transfer processing.*/
 +        _adc_isr_half_code(adcp);
 +      }
 +      if ((flags & STM32_DMA_ISR_TCIF) != 0) {
 +        /* Transfer complete processing.*/
 +        _adc_isr_full_code(adcp);
 +      }
 +    }
 +  }
 +}
 +
 +/*===========================================================================*/
 +/* Driver interrupt handlers.                                                */
 +/*===========================================================================*/
 +
 +#if STM32_ADC_USE_ADC1 || defined(__DOXYGEN__)
 +/**
 + * @brief   ADC interrupt handler.
 + *
 + * @isr
 + */
 +CH_IRQ_HANDLER(ADC1_IRQHandler) {
 +  uint32_t isr;
 +
 +  CH_IRQ_PROLOGUE();
 +
 +  isr = ADC1->ISR;
 +  ADC1->ISR = isr;
 +  /* Note, an overflow may occur after the conversion ended before the driver
 +     is able to stop the ADC, this is why the DMA channel is checked too.*/
 +  if ((isr & ADC_ISR_OVR) && (dmaStreamGetTransactionSize(ADCD1.dmastp) > 0)) {
 +    /* ADC overflow condition, this could happen only if the DMA is unable
 +       to read data fast enough.*/
 +    if (ADCD1.grpp != NULL)
 +      _adc_isr_error_code(&ADCD1, ADC_ERR_OVERFLOW);
 +  }
 +  /* TODO: Add here analog watchdog handling.*/
 +
 +  CH_IRQ_EPILOGUE();
 +}
 +#endif
 +
 +/*===========================================================================*/
 +/* Driver exported functions.                                                */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   Low level ADC driver initialization.
 + *
 + * @notapi
 + */
 +void adc_lld_init(void) {
 +
 +#if STM32_ADC_USE_ADC1
 +  /* Driver initialization.*/
 +  adcObjectInit(&ADCD1);
 +  ADCD1.adc = ADC1;
 +  ADCD1.dmastp  = STM32_DMA1_STREAM1;
 +  ADCD1.dmamode = STM32_DMA_CR_PL(STM32_ADC_ADC1_DMA_PRIORITY) |
 +                  STM32_DMA_CR_DIR_P2M |
 +                  STM32_DMA_CR_MSIZE_HWORD | STM32_DMA_CR_PSIZE_HWORD |
 +                  STM32_DMA_CR_MINC        | STM32_DMA_CR_TCIE        |
 +                  STM32_DMA_CR_DMEIE       | STM32_DMA_CR_TEIE        |
 +                  STM32_DMA_CR_EN;
 +#endif
 +
 +  /* The shared vector is initialized on driver initialization and never
 +     disabled.*/
 +  nvicEnableVector(ADC1_COMP_IRQn,
 +                   CORTEX_PRIORITY_MASK(STM32_ADC_IRQ_PRIORITY));
 +}
 +
 +/**
 + * @brief   Configures and activates the ADC peripheral.
 + *
 + * @param[in] adcp      pointer to the @p ADCDriver object
 + *
 + * @notapi
 + */
 +void adc_lld_start(ADCDriver *adcp) {
 +
 +  /* If in stopped state then enables the ADC and DMA clocks.*/
 +  if (adcp->state == ADC_STOP) {
 +#if STM32_ADC_USE_ADC1
 +    if (&ADCD1 == adcp) {
 +      bool_t b;
 +      b = dmaStreamAllocate(adcp->dmastp,
 +                            STM32_ADC_ADC1_DMA_IRQ_PRIORITY,
 +                            (stm32_dmaisr_t)adc_lld_serve_rx_interrupt,
 +                            (void *)adcp);
 +      chDbgAssert(!b, "adc_lld_start(), #1", "stream already allocated");
 +      dmaStreamSetPeripheral(adcp->dmastp, &ADC1->DR);
 +      rccEnableADC1(FALSE);
 +    }
 +#endif /* STM32_ADC_USE_ADC1 */
 +
 +    /* ADC initial setup, starting the analog part here in order to reduce
 +       the latency when starting a conversion.*/
 +    adcp->adc->CR = ADC_CR_ADEN;
 +    while (!(adcp->adc->ISR & ADC_ISR_ADRDY))
 +      ;
 +  }
 +}
 +
 +/**
 + * @brief   Deactivates the ADC peripheral.
 + *
 + * @param[in] adcp      pointer to the @p ADCDriver object
 + *
 + * @notapi
 + */
 +void adc_lld_stop(ADCDriver *adcp) {
 +
 +  /* If in ready state then disables the ADC clock and analog part.*/
 +  if (adcp->state == ADC_READY) {
 +
 +    dmaStreamRelease(adcp->dmastp);
 +
 +    /* Disabling ADC.*/
 +    if (adcp->adc->CR & ADC_CR_ADEN) {
 +      adc_lld_stop_adc(adcp->adc);
 +      adcp->adc->CR |= ADC_CR_ADDIS;
 +      while (adcp->adc->CR & ADC_CR_ADDIS)
 +        ;
 +    }
 +
 +#if STM32_ADC_USE_ADC1
 +    if (&ADCD1 == adcp)
 +      rccDisableADC1(FALSE);
 +#endif
 +  }
 +}
 +
 +/**
 + * @brief   Starts an ADC conversion.
 + *
 + * @param[in] adcp      pointer to the @p ADCDriver object
 + *
 + * @notapi
 + */
 +void adc_lld_start_conversion(ADCDriver *adcp) {
 +  uint32_t mode;
 +  const ADCConversionGroup *grpp = adcp->grpp;
 +
 +  /* DMA setup.*/
 +  mode = adcp->dmamode;
 +  if (grpp->circular) {
 +    mode |= STM32_DMA_CR_CIRC;
 +  }
 +  if (adcp->depth > 1) {
 +    /* If the buffer depth is greater than one then the half transfer interrupt
 +       interrupt is enabled in order to allows streaming processing.*/
 +    mode |= STM32_DMA_CR_HTIE;
 +  }
 +  dmaStreamSetMemory0(adcp->dmastp, adcp->samples);
 +  dmaStreamSetTransactionSize(adcp->dmastp, (uint32_t)grpp->num_channels *
 +                                            (uint32_t)adcp->depth);
 +  dmaStreamSetMode(adcp->dmastp, mode);
 +
 +  /* ADC setup.*/
 +  adcp->adc->ISR    = adcp->adc->ISR;
 +  adcp->adc->IER    = ADC_IER_OVRIE;
 +  adcp->adc->SMPR   = grpp->smpr;
 +  adcp->adc->CHSELR = grpp->chselr;
 +
 +  /* ADC configuration and start.*/
 +  adcp->adc->CFGR1  = grpp->cfgr1 | ADC_CFGR1_CONT  | ADC_CFGR1_DMACFG |
 +                                    ADC_CFGR1_DMAEN;
 +  adcp->adc->CR    |= ADC_CR_ADSTART;
 +}
 +
 +/**
 + * @brief   Stops an ongoing conversion.
 + *
 + * @param[in] adcp      pointer to the @p ADCDriver object
 + *
 + * @notapi
 + */
 +void adc_lld_stop_conversion(ADCDriver *adcp) {
 +
 +  dmaStreamDisable(adcp->dmastp);
 +  adc_lld_stop_adc(adcp->adc);
 +}
 +
 +/**
 + * @brief   Enables the TSVREFE bit.
 + * @details The TSVREFE bit is required in order to sample the internal
 + *          temperature sensor and internal reference voltage.
 + * @note    This is an STM32-only functionality.
 + */
 +void adcSTM32EnableTSVREFE(void) {
 +
 +  ADC->CCR |= ADC_CCR_VREFEN;
 +}
 +
 +/**
 + * @brief   Disables the TSVREFE bit.
 + * @details The TSVREFE bit is required in order to sample the internal
 + *          temperature sensor and internal reference voltage.
 + * @note    This is an STM32-only functionality.
 + */
 +void adcSTM32DisableTSVREFE(void) {
 +
 +  ADC->CCR &= ~ADC_CCR_VREFEN;
 +}
 +
 +#endif /* HAL_USE_ADC */
 +
 +/** @} */
 diff --git a/os/hal/platforms/STM32F0xx/adc_lld.h b/os/hal/platforms/STM32F0xx/adc_lld.h new file mode 100644 index 000000000..3be5a053c --- /dev/null +++ b/os/hal/platforms/STM32F0xx/adc_lld.h @@ -0,0 +1,293 @@ +/*
 +    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    STM32F0xx/adc_lld.h
 + * @brief   STM32F0xx ADC subsystem low level driver header.
 + *
 + * @addtogroup ADC
 + * @{
 + */
 +
 +#ifndef _ADC_LLD_H_
 +#define _ADC_LLD_H_
 +
 +#if HAL_USE_ADC || defined(__DOXYGEN__)
 +
 +/*===========================================================================*/
 +/* Driver constants.                                                         */
 +/*===========================================================================*/
 +
 +/**
 + * @name    Sampling rates
 + * @{
 + */
 +#define ADC_SAMPLE_1P5          0   /**< @brief 14 cycles conversion time   */
 +#define ADC_SAMPLE_7P5          1   /**< @brief 21 cycles conversion time.  */
 +#define ADC_SAMPLE_13P5         2   /**< @brief 28 cycles conversion time.  */
 +#define ADC_SAMPLE_28P5         3   /**< @brief 41 cycles conversion time.  */
 +#define ADC_SAMPLE_41P5         4   /**< @brief 54 cycles conversion time.  */
 +#define ADC_SAMPLE_55P5         5   /**< @brief 68 cycles conversion time.  */
 +#define ADC_SAMPLE_71P5         6   /**< @brief 84 cycles conversion time.  */
 +#define ADC_SAMPLE_239P5        7   /**< @brief 252 cycles conversion time. */
 +/** @} */
 +
 +/*===========================================================================*/
 +/* Driver pre-compile time settings.                                         */
 +/*===========================================================================*/
 +
 +/**
 + * @name    Configuration options
 + * @{
 + */
 +/**
 + * @brief   ADC1 driver enable switch.
 + * @details If set to @p TRUE the support for ADC1 is included.
 + * @note    The default is @p TRUE.
 + */
 +#if !defined(STM32_ADC_USE_ADC1) || defined(__DOXYGEN__)
 +#define STM32_ADC_USE_ADC1                  TRUE
 +#endif
 +
 +/**
 + * @brief   ADC1 DMA priority (0..3|lowest..highest).
 + */
 +#if !defined(STM32_ADC_ADC1_DMA_PRIORITY) || defined(__DOXYGEN__)
 +#define STM32_ADC_ADC1_DMA_PRIORITY         2
 +#endif
 +
 +/**
 + * @brief   ADC interrupt priority level setting.
 + */
 +#if !defined(STM32_ADC_IRQ_PRIORITY) || defined(__DOXYGEN__)
 +#define STM32_ADC_IRQ_PRIORITY              2
 +#endif
 +
 +/**
 + * @brief   ADC1 DMA interrupt priority level setting.
 + */
 +#if !defined(STM32_ADC_ADC1_DMA_IRQ_PRIORITY) || defined(__DOXYGEN__)
 +#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY     2
 +#endif
 +
 +/** @} */
 +
 +/*===========================================================================*/
 +/* Derived constants and error checks.                                       */
 +/*===========================================================================*/
 +
 +#if STM32_ADC_USE_ADC1 && !STM32_HAS_ADC1
 +#error "ADC1 not present in the selected device"
 +#endif
 +
 +#if !STM32_ADC_USE_ADC1
 +#error "ADC driver activated but no ADC peripheral assigned"
 +#endif
 +
 +#if !defined(STM32_DMA_REQUIRED)
 +#define STM32_DMA_REQUIRED
 +#endif
 +
 +/*===========================================================================*/
 +/* Driver data structures and types.                                         */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   ADC sample data type.
 + */
 +typedef uint16_t adcsample_t;
 +
 +/**
 + * @brief   Channels number in a conversion group.
 + */
 +typedef uint16_t adc_channels_num_t;
 +
 +/**
 + * @brief   Possible ADC failure causes.
 + * @note    Error codes are architecture dependent and should not relied
 + *          upon.
 + */
 +typedef enum {
 +  ADC_ERR_DMAFAILURE = 0,                   /**< DMA operations failure.    */
 +  ADC_ERR_OVERFLOW = 1                      /**< ADC overflow condition.    */
 +} adcerror_t;
 +
 +/**
 + * @brief   Type of a structure representing an ADC driver.
 + */
 +typedef struct ADCDriver ADCDriver;
 +
 +/**
 + * @brief   ADC notification callback type.
 + *
 + * @param[in] adcp      pointer to the @p ADCDriver object triggering the
 + *                      callback
 + * @param[in] buffer    pointer to the most recent samples data
 + * @param[in] n         number of buffer rows available starting from @p buffer
 + */
 +typedef void (*adccallback_t)(ADCDriver *adcp, adcsample_t *buffer, size_t n);
 +
 +/**
 + * @brief   ADC error callback type.
 + *
 + * @param[in] adcp      pointer to the @p ADCDriver object triggering the
 + *                      callback
 + */
 +typedef void (*adcerrorcallback_t)(ADCDriver *adcp, adcerror_t err);
 +
 +/**
 + * @brief   Conversion group configuration structure.
 + * @details This implementation-dependent structure describes a conversion
 + *          operation.
 + * @note    The use of this configuration structure requires knowledge of
 + *          STM32 ADC cell registers interface, please refer to the STM32
 + *          reference manual for details.
 + */
 +typedef struct {
 +  /**
 +   * @brief   Enables the circular buffer mode for the group.
 +   */
 +  bool_t                    circular;
 +  /**
 +   * @brief   Number of the analog channels belonging to the conversion group.
 +   */
 +  adc_channels_num_t        num_channels;
 +  /**
 +   * @brief   Callback function associated to the group or @p NULL.
 +   */
 +  adccallback_t             end_cb;
 +  /**
 +   * @brief   Error callback or @p NULL.
 +   */
 +  adcerrorcallback_t        error_cb;
 +  /* End of the mandatory fields.*/
 +  /**
 +   * @brief   ADC CFGR1 register initialization data.
 +   */
 +  uint32_t                  cfgr1;
 +  /**
 +   * @brief   ADC SMPR register initialization data.
 +   */
 +  uint32_t                  smpr;
 +  /**
 +   * @brief   ADC CHSELR register initialization data.
 +   * @details The number of bits at logic level one in this register must
 +   *          be equal to the number in the @p num_channels field.
 +   */
 +  uint32_t                  chselr;
 +} ADCConversionGroup;
 +
 +/**
 + * @brief   Driver configuration structure.
 + * @note    It could be empty on some architectures.
 + */
 +typedef struct {
 +  uint32_t                  dummy;
 +} ADCConfig;
 +
 +/**
 + * @brief   Structure representing an ADC driver.
 + */
 +struct ADCDriver {
 +  /**
 +   * @brief Driver state.
 +   */
 +  adcstate_t                state;
 +  /**
 +   * @brief Current configuration data.
 +   */
 +  const ADCConfig           *config;
 +  /**
 +   * @brief Current samples buffer pointer or @p NULL.
 +   */
 +  adcsample_t               *samples;
 +  /**
 +   * @brief Current samples buffer depth or @p 0.
 +   */
 +  size_t                    depth;
 +  /**
 +   * @brief Current conversion group pointer or @p NULL.
 +   */
 +  const ADCConversionGroup  *grpp;
 +#if ADC_USE_WAIT || defined(__DOXYGEN__)
 +  /**
 +   * @brief Waiting thread.
 +   */
 +  Thread                    *thread;
 +#endif
 +#if ADC_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__)
 +#if CH_USE_MUTEXES || defined(__DOXYGEN__)
 +  /**
 +   * @brief Mutex protecting the peripheral.
 +   */
 +  Mutex                     mutex;
 +#elif CH_USE_SEMAPHORES
 +  Semaphore                 semaphore;
 +#endif
 +#endif /* ADC_USE_MUTUAL_EXCLUSION */
 +#if defined(ADC_DRIVER_EXT_FIELDS)
 +  ADC_DRIVER_EXT_FIELDS
 +#endif
 +  /* End of the mandatory fields.*/
 +  /**
 +   * @brief Pointer to the ADCx registers block.
 +   */
 +  ADC_TypeDef               *adc;
 +  /**
 +   * @brief Pointer to associated SMA channel.
 +   */
 +  const stm32_dma_stream_t  *dmastp;
 +  /**
 +   * @brief DMA mode bit mask.
 +   */
 +  uint32_t                  dmamode;
 +};
 +
 +/*===========================================================================*/
 +/* Driver macros.                                                            */
 +/*===========================================================================*/
 +
 +/*===========================================================================*/
 +/* External declarations.                                                    */
 +/*===========================================================================*/
 +
 +#if STM32_ADC_USE_ADC1 && !defined(__DOXYGEN__)
 +extern ADCDriver ADCD1;
 +#endif
 +
 +#ifdef __cplusplus
 +extern "C" {
 +#endif
 +  void adc_lld_init(void);
 +  void adc_lld_start(ADCDriver *adcp);
 +  void adc_lld_stop(ADCDriver *adcp);
 +  void adc_lld_start_conversion(ADCDriver *adcp);
 +  void adc_lld_stop_conversion(ADCDriver *adcp);
 +  void adcSTM32EnableTSVREFE(void);
 +  void adcSTM32DisableTSVREFE(void);
 +#ifdef __cplusplus
 +}
 +#endif
 +
 +#endif /* HAL_USE_ADC */
 +
 +#endif /* _ADC_LLD_H_ */
 +
 +/** @} */
 diff --git a/os/hal/platforms/STM32F0xx/platform.mk b/os/hal/platforms/STM32F0xx/platform.mk index 9d13d064a..9c0e709df 100644 --- a/os/hal/platforms/STM32F0xx/platform.mk +++ b/os/hal/platforms/STM32F0xx/platform.mk @@ -1,5 +1,6 @@  # List of all the STM32F1xx platform files.
  PLATFORMSRC = ${CHIBIOS}/os/hal/platforms/STM32F0xx/stm32_dma.c \
 +              ${CHIBIOS}/os/hal/platforms/STM32F0xx/adc_lld.c \
                ${CHIBIOS}/os/hal/platforms/STM32F0xx/hal_lld.c \
                ${CHIBIOS}/os/hal/platforms/STM32/GPIOv2/pal_lld.c \
                ${CHIBIOS}/os/hal/platforms/STM32/serial_lld.c	\
 | 
