import ChibiOS 2.0.8

This commit is contained in:
NIIBE Yutaka
2010-11-30 13:54:43 +09:00
parent 27543cfeca
commit c560d0ad0c
1982 changed files with 5318 additions and 4046 deletions

View File

@@ -0,0 +1,252 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/adc_lld.c
* @brief STM32 ADC subsystem low level driver source.
* @addtogroup STM32_ADC
* @{
*/
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_ADC || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/** @brief ADC1 driver identifier.*/
#if USE_STM32_ADC1 || defined(__DOXYGEN__)
ADCDriver ADCD1;
#endif
/*===========================================================================*/
/* Driver local variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
#if USE_STM32_ADC1 || defined(__DOXYGEN__)
/**
* @brief ADC1 DMA interrupt handler (channel 1).
*/
CH_IRQ_HANDLER(Vector6C) {
uint32_t isr;
CH_IRQ_PROLOGUE();
isr = DMA1->ISR;
DMA1->IFCR |= DMA_IFCR_CGIF1 | DMA_IFCR_CTCIF1 |
DMA_IFCR_CHTIF1 | DMA_IFCR_CTEIF1;
if ((isr & DMA_ISR_HTIF1) != 0) {
/* Half transfer processing.*/
if (ADCD1.ad_callback != NULL) {
/* Invokes the callback passing the 1st half of the buffer.*/
ADCD1.ad_callback(ADCD1.ad_samples, ADCD1.ad_depth / 2);
}
}
if ((isr & DMA_ISR_TCIF1) != 0) {
/* Transfer complete processing.*/
if (!ADCD1.ad_grpp->acg_circular) {
/* End conversion.*/
adc_lld_stop_conversion(&ADCD1);
ADCD1.ad_grpp = NULL;
ADCD1.ad_state = ADC_COMPLETE;
chSysLockFromIsr();
chSemResetI(&ADCD1.ad_sem, 0);
chSysUnlockFromIsr();
}
/* Callback handling.*/
if (ADCD1.ad_callback != NULL) {
if (ADCD1.ad_depth > 1) {
/* Invokes the callback passing the 2nd half of the buffer.*/
size_t half = ADCD1.ad_depth / 2;
ADCD1.ad_callback(ADCD1.ad_samples + half, half);
}
else {
/* Invokes the callback passing the whole buffer.*/
ADCD1.ad_callback(ADCD1.ad_samples, ADCD1.ad_depth);
}
}
}
if ((isr & DMA_ISR_TEIF1) != 0) {
/* DMA error processing.*/
STM32_ADC1_DMA_ERROR_HOOK();
}
CH_IRQ_EPILOGUE();
}
#endif
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level ADC driver initialization.
*/
void adc_lld_init(void) {
#if USE_STM32_ADC1
/* ADC reset, ensures reset state in order to avoid trouble with JTAGs.*/
RCC->APB2RSTR = RCC_APB2RSTR_ADC1RST;
RCC->APB2RSTR = 0;
/* Driver initialization.*/
adcObjectInit(&ADCD1);
ADCD1.ad_adc = ADC1;
ADCD1.ad_dma = DMA1_Channel1;
ADCD1.ad_dmaprio = STM32_ADC1_DMA_PRIORITY << 12;
/* Temporary activation.*/
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN;
ADC1->CR1 = 0;
ADC1->CR2 = ADC_CR2_ADON;
/* Reset calibration just to be safe.*/
ADC1->CR2 = ADC_CR2_ADON | ADC_CR2_RSTCAL;
while ((ADC1->CR2 & ADC_CR2_RSTCAL) != 0)
;
/* Calibration.*/
ADC1->CR2 = ADC_CR2_ADON | ADC_CR2_CAL;
while ((ADC1->CR2 & ADC_CR2_CAL) != 0)
;
/* Return the ADC in low power mode.*/
ADC1->CR2 = 0;
RCC->APB2ENR &= ~RCC_APB2ENR_ADC1EN;
#endif
}
/**
* @brief Configures and activates the ADC peripheral.
*
* @param[in] adcp pointer to the @p ADCDriver object
*/
void adc_lld_start(ADCDriver *adcp) {
/* If in stopped state then enables the ADC and DMA clocks.*/
if (adcp->ad_state == ADC_STOP) {
#if USE_STM32_ADC1
if (&ADCD1 == adcp) {
dmaEnable(DMA1_ID); /* NOTE: Must be enabled before the IRQs.*/
NVICEnableVector(DMA1_Channel1_IRQn,
CORTEX_PRIORITY_MASK(STM32_ADC1_IRQ_PRIORITY));
DMA1_Channel1->CPAR = (uint32_t)&ADC1->DR;
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN;
}
#endif
/* ADC setup, the calibration procedure has already been performed
during initialization.*/
adcp->ad_adc->CR1 = ADC_CR1_SCAN;
adcp->ad_adc->CR2 = 0;
}
}
/**
* @brief Deactivates the ADC peripheral.
*
* @param[in] adcp pointer to the @p ADCDriver object
*/
void adc_lld_stop(ADCDriver *adcp) {
/* If in ready state then disables the ADC clock.*/
if (adcp->ad_state == ADC_READY) {
#if USE_STM32_ADC1
if (&ADCD1 == adcp) {
ADC1->CR1 = 0;
ADC1->CR2 = 0;
NVICDisableVector(DMA1_Channel1_IRQn);
dmaDisable(DMA1_ID);
RCC->APB2ENR &= ~RCC_APB2ENR_ADC1EN;
}
#endif
}
}
/**
* @brief Starts an ADC conversion.
*
* @param[in] adcp pointer to the @p ADCDriver object
*/
void adc_lld_start_conversion(ADCDriver *adcp) {
uint32_t ccr, n;
const ADCConversionGroup *grpp = adcp->ad_grpp;
/* DMA setup.*/
adcp->ad_dma->CMAR = (uint32_t)adcp->ad_samples;
ccr = adcp->ad_dmaprio | DMA_CCR1_EN | DMA_CCR1_MSIZE_0 | DMA_CCR1_PSIZE_0 |
DMA_CCR1_MINC | DMA_CCR1_TCIE | DMA_CCR1_TEIE;
if (grpp->acg_circular)
ccr |= DMA_CCR1_CIRC;
if (adcp->ad_depth > 1) {
/* If the buffer depth is greater than one then the half transfer interrupt
interrupt is enabled in order to allows streaming processing.*/
ccr |= DMA_CCR1_HTIE;
n = (uint32_t)grpp->acg_num_channels * (uint32_t)adcp->ad_depth;
}
else
n = (uint32_t)grpp->acg_num_channels;
adcp->ad_dma->CNDTR = n;
adcp->ad_dma->CCR = ccr;
/* ADC setup.*/
adcp->ad_adc->SMPR1 = grpp->acg_smpr1;
adcp->ad_adc->SMPR2 = grpp->acg_smpr2;
adcp->ad_adc->SQR1 = grpp->acg_sqr1;
adcp->ad_adc->SQR2 = grpp->acg_sqr2;
adcp->ad_adc->SQR3 = grpp->acg_sqr3;
adcp->ad_adc->CR1 = grpp->acg_cr1 | ADC_CR1_SCAN;
adcp->ad_adc->CR2 = grpp->acg_cr2 | ADC_CR2_DMA | ADC_CR2_ADON;
/* ADC start.*/
adcp->ad_adc->CR2 |= ADC_CR2_SWSTART | ADC_CR2_EXTTRIG;
}
/**
* @brief Stops an ongoing conversion.
*
* @param[in] adcp pointer to the @p ADCDriver object
*/
void adc_lld_stop_conversion(ADCDriver *adcp) {
adcp->ad_dma->CCR = 0;
adcp->ad_adc->CR2 = 0;
}
#endif /* CH_HAL_USE_ADC */
/** @} */

View File

@@ -0,0 +1,286 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/adc_lld.h
* @brief STM32 ADC subsystem low level driver header.
* @addtogroup STM32_ADC
* @{
*/
#ifndef _ADC_LLD_H_
#define _ADC_LLD_H_
#if CH_HAL_USE_ADC || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
#define ADC_CR2_EXTSEL_SRC(n) ((n) << 17) /**< @brief Trigger source. */
#define ADC_CR2_EXTSEL_SWSTART (7 << 17) /**< @brief Software trigger. */
#define ADC_CHANNEL_IN0 0 /**< @brief External analog input 0. */
#define ADC_CHANNEL_IN1 1 /**< @brief External analog input 1. */
#define ADC_CHANNEL_IN2 2 /**< @brief External analog input 2. */
#define ADC_CHANNEL_IN3 3 /**< @brief External analog input 3. */
#define ADC_CHANNEL_IN4 4 /**< @brief External analog input 4. */
#define ADC_CHANNEL_IN5 5 /**< @brief External analog input 5. */
#define ADC_CHANNEL_IN6 6 /**< @brief External analog input 6. */
#define ADC_CHANNEL_IN7 7 /**< @brief External analog input 7. */
#define ADC_CHANNEL_IN8 8 /**< @brief External analog input 8. */
#define ADC_CHANNEL_IN9 9 /**< @brief External analog input 9. */
#define ADC_CHANNEL_IN10 10 /**< @brief External analog input 10. */
#define ADC_CHANNEL_IN11 11 /**< @brief External analog input 11. */
#define ADC_CHANNEL_IN12 12 /**< @brief External analog input 12. */
#define ADC_CHANNEL_IN13 13 /**< @brief External analog input 13. */
#define ADC_CHANNEL_IN14 14 /**< @brief External analog input 14. */
#define ADC_CHANNEL_IN15 15 /**< @brief External analog input 15. */
#define ADC_CHANNEL_SENSOR 16 /**< @brief Internal temperature sensor.*/
#define ADC_CHANNEL_VREFINT 17 /**< @brief Internal reference. */
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @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(USE_STM32_ADC1) || defined(__DOXYGEN__)
#define USE_STM32_ADC1 TRUE
#endif
/**
* @brief ADC1 DMA priority (0..3|lowest..highest).
*/
#if !defined(STM32_ADC1_DMA_PRIORITY) || defined(__DOXYGEN__)
#define STM32_ADC1_DMA_PRIORITY 3
#endif
/**
* @brief ADC1 interrupt priority level setting.
*/
#if !defined(STM32_ADC1_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_ADC1_IRQ_PRIORITY 5
#endif
/**
* @brief ADC1 DMA error hook.
* @note The default action for DMA errors is a system halt because DMA error
* can only happen because programming errors.
*/
#if !defined(STM32_ADC1_DMA_ERROR_HOOK) || defined(__DOXYGEN__)
#define STM32_ADC1_DMA_ERROR_HOOK() chSysHalt()
#endif
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
/*===========================================================================*/
/* 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 ADC notification callback type.
* @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)(adcsample_t *buffer, size_t n);
/**
* @brief Conversion group configuration structure.
* @details This implementation-dependent structure describes a conversion
* operation.
*/
typedef struct {
/**
* @brief Enables the circular buffer mode for the group.
*/
bool_t acg_circular;
/**
* @brief Number of the analog channels belonging to the conversion group.
*/
adc_channels_num_t acg_num_channels;
/* End of the mandatory fields.*/
/**
* @brief ADC CR1 register initialization data.
* @note All the required bits must be defined into this field except
* @p ADC_CR1_SCAN that is enforced inside the driver.
*/
uint32_t acg_cr1;
/**
* @brief ADC CR2 register initialization data.
* @note All the required bits must be defined into this field except
* @p ADC_CR2_DMA and @p ADC_CR2_ADON that are enforced inside the
* driver.
*/
uint32_t acg_cr2;
/**
* @brief ADC SMPR1 register initialization data.
*/
uint32_t acg_smpr1;
/**
* @brief ADC SMPR2 register initialization data.
*/
uint32_t acg_smpr2;
/**
* @brief ADC SQR1 register initialization data.
*/
uint32_t acg_sqr1;
/**
* @brief ADC SQR2 register initialization data.
*/
uint32_t acg_sqr2;
/**
* @brief ADC SQR3 register initialization data.
*/
uint32_t acg_sqr3;
} ADCConversionGroup;
/**
* @brief Driver configuration structure.
* @note It could be empty on some architectures.
*/
typedef struct {
/* * <----------
* @brief ADC prescaler setting.
* @note This field can assume one of the following values:
* @p RCC_CFGR_ADCPRE_DIV2, @p RCC_CFGR_ADCPRE_DIV4,
* @p RCC_CFGR_ADCPRE_DIV6, @p RCC_CFGR_ADCPRE_DIV8.
*/
/* uint32_t ac_prescaler;*/
} ADCConfig;
/**
* @brief Structure representing an ADC driver.
*/
typedef struct {
/**
* @brief Driver state.
*/
adcstate_t ad_state;
/**
* @brief Current configuration data.
*/
const ADCConfig *ad_config;
/**
* @brief Synchronization semaphore.
*/
Semaphore ad_sem;
/**
* @brief Current callback function or @p NULL.
*/
adccallback_t ad_callback;
/**
* @brief Current samples buffer pointer or @p NULL.
*/
adcsample_t *ad_samples;
/**
* @brief Current samples buffer depth or @p 0.
*/
size_t ad_depth;
/**
* @brief Current conversion group pointer or @p NULL.
*/
const ADCConversionGroup *ad_grpp;
/* End of the mandatory fields.*/
/**
* @brief Pointer to the ADCx registers block.
*/
ADC_TypeDef *ad_adc;
/**
* @brief Pointer to the DMA channel registers block.
*/
DMA_Channel_TypeDef *ad_dma;
/**
* @brief DMA priority bit mask.
*/
uint32_t ad_dmaprio;
} ADCDriver;
/*===========================================================================*/
/* Driver macros. */
/*===========================================================================*/
#define ADC_SQR1_NUM_CH(n) (((n) - 1) << 20)
#define ADC_SQR3_SQ0_N(n) ((n) << 0)
#define ADC_SQR3_SQ1_N(n) ((n) << 5)
#define ADC_SQR3_SQ2_N(n) ((n) << 10)
#define ADC_SQR3_SQ3_N(n) ((n) << 15)
#define ADC_SQR3_SQ4_N(n) ((n) << 20)
#define ADC_SQR3_SQ5_N(n) ((n) << 25)
#define ADC_SQR2_SQ6_N(n) ((n) << 0)
#define ADC_SQR2_SQ7_N(n) ((n) << 5)
#define ADC_SQR2_SQ8_N(n) ((n) << 10)
#define ADC_SQR2_SQ9_N(n) ((n) << 15)
#define ADC_SQR2_SQ10_N(n) ((n) << 20)
#define ADC_SQR2_SQ11_N(n) ((n) << 25)
#define ADC_SQR1_SQ13_N(n) ((n) << 0)
#define ADC_SQR1_SQ14_N(n) ((n) << 5)
#define ADC_SQR1_SQ15_N(n) ((n) << 10)
#define ADC_SQR1_SQ16_N(n) ((n) << 15)
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#if USE_STM32_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);
#ifdef __cplusplus
}
#endif
#endif /* CH_HAL_USE_ADC */
#endif /* _ADC_LLD_H_ */
/** @} */

View File

@@ -0,0 +1,391 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/can_lld.c
* @brief STM32 CAN subsystem low level driver source.
* @addtogroup STM32_CAN
* @{
*/
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_CAN || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/** @brief ADC1 driver identifier.*/
#if USE_STM32_CAN1 || defined(__DOXYGEN__)
CANDriver CAND1;
#endif
/*===========================================================================*/
/* Driver local variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
/*
* CAN1 TX interrupt handler.
*/
CH_IRQ_HANDLER(Vector8C) {
CH_IRQ_PROLOGUE();
/* No more events until a message is transmitted.*/
CAN1->TSR = CAN_TSR_RQCP0 | CAN_TSR_RQCP1 | CAN_TSR_RQCP2;
chSysLockFromIsr();
while (chSemGetCounterI(&CAND1.cd_txsem) < 0)
chSemSignalI(&CAND1.cd_txsem);
chEvtBroadcastI(&CAND1.cd_txempty_event);
chSysUnlockFromIsr();
CH_IRQ_EPILOGUE();
}
/*
* CAN1 RX0 interrupt handler.
*/
CH_IRQ_HANDLER(Vector90) {
uint32_t rf0r;
CH_IRQ_PROLOGUE();
rf0r = CAN1->RF0R;
if ((rf0r & CAN_RF0R_FMP0) > 0) {
/* No more receive events until the queue 0 has been emptied.*/
CAN1->IER &= ~CAN_IER_FMPIE0;
chSysLockFromIsr();
while (chSemGetCounterI(&CAND1.cd_rxsem) < 0)
chSemSignalI(&CAND1.cd_rxsem);
chEvtBroadcastI(&CAND1.cd_rxfull_event);
chSysUnlockFromIsr();
}
if ((rf0r & CAN_RF0R_FOVR0) > 0) {
/* Overflow events handling.*/
CAN1->RF0R = CAN_RF0R_FOVR0;
canAddFlagsI(&CAND1, CAN_OVERFLOW_ERROR);
chSysLockFromIsr();
chEvtBroadcastI(&CAND1.cd_error_event);
chSysUnlockFromIsr();
}
CH_IRQ_EPILOGUE();
}
/*
* CAN1 RX1 interrupt handler.
*/
CH_IRQ_HANDLER(Vector94) {
CH_IRQ_PROLOGUE();
chSysHalt(); /* Not supported (yet).*/
CH_IRQ_EPILOGUE();
}
/*
* CAN1 SCE interrupt handler.
*/
CH_IRQ_HANDLER(Vector98) {
uint32_t msr;
CH_IRQ_PROLOGUE();
msr = CAN1->MSR;
CAN1->MSR = CAN_MSR_ERRI | CAN_MSR_WKUI | CAN_MSR_SLAKI;
/* Wakeup event.*/
if (msr & CAN_MSR_WKUI) {
chSysLockFromIsr();
chEvtBroadcastI(&CAND1.cd_wakeup_event);
chSysUnlockFromIsr();
}
/* Error event.*/
if (msr & CAN_MSR_ERRI) {
canstatus_t flags;
uint32_t esr = CAN1->ESR;
CAN1->ESR &= ~CAN_ESR_LEC;
flags = (canstatus_t)(esr & 7);
if ((esr & CAN_ESR_LEC) > 0)
flags |= CAN_FRAMING_ERROR;
chSysLockFromIsr();
canAddFlagsI(&CAND1, flags);
chEvtBroadcastI(&CAND1.cd_error_event);
chSysUnlockFromIsr();
}
CH_IRQ_EPILOGUE();
}
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level CAN driver initialization.
*/
void can_lld_init(void) {
#if USE_STM32_CAN1
/* CAN reset, ensures reset state in order to avoid trouble with JTAGs.*/
RCC->APB1RSTR = RCC_APB1RSTR_CAN1RST;
RCC->APB1RSTR = 0;
/* Driver initialization.*/
canObjectInit(&CAND1);
CAND1.cd_can = CAN1;
#endif
}
/**
* @brief Configures and activates the CAN peripheral.
*
* @param[in] canp pointer to the @p CANDriver object
*/
void can_lld_start(CANDriver *canp) {
/* Clock activation.*/
#if USE_STM32_CAN1
if (&CAND1 == canp) {
NVICEnableVector(USB_HP_CAN1_TX_IRQn,
CORTEX_PRIORITY_MASK(STM32_CAN1_IRQ_PRIORITY));
NVICEnableVector(USB_LP_CAN1_RX0_IRQn,
CORTEX_PRIORITY_MASK(STM32_CAN1_IRQ_PRIORITY));
NVICEnableVector(CAN1_RX1_IRQn,
CORTEX_PRIORITY_MASK(STM32_CAN1_IRQ_PRIORITY));
NVICEnableVector(CAN1_SCE_IRQn,
CORTEX_PRIORITY_MASK(STM32_CAN1_IRQ_PRIORITY));
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
}
#endif
/* Entering initialization mode. */
canp->cd_state = CAN_STARTING;
canp->cd_can->MCR = CAN_MCR_INRQ;
while ((canp->cd_can->MSR & CAN_MSR_INAK) == 0)
chThdSleepS(1);
/* BTR initialization.*/
canp->cd_can->BTR = canp->cd_config->cc_btr;
/* MCR initialization.*/
canp->cd_can->MCR = canp->cd_config->cc_mcr;
/* Filters initialization.*/
canp->cd_can->FMR |= CAN_FMR_FINIT;
if (canp->cd_config->cc_num > 0) {
uint32_t i, fmask;
CAN_FilterRegister_TypeDef *cfp;
canp->cd_can->FA1R = 0;
canp->cd_can->FM1R = 0;
canp->cd_can->FS1R = 0;
canp->cd_can->FFA1R = 0;
cfp = canp->cd_can->sFilterRegister;
fmask = 1;
for (i = 0; i < CAN_MAX_FILTERS; i++) {
if (i < canp->cd_config->cc_num) {
if (canp->cd_config->cc_filters[i].cf_mode)
canp->cd_can->FM1R |= fmask;
if (canp->cd_config->cc_filters[i].cf_scale)
canp->cd_can->FS1R |= fmask;
if (canp->cd_config->cc_filters[i].cf_assignment)
canp->cd_can->FFA1R |= fmask;
cfp->FR1 = canp->cd_config->cc_filters[i].cf_register1;
cfp->FR2 = canp->cd_config->cc_filters[i].cf_register2;
canp->cd_can->FA1R |= fmask;
}
else {
cfp->FR1 = 0;
cfp->FR2 = 0;
}
cfp++;
fmask <<= 1;
/* Gives a chance for preemption since this is a rather long loop.*/
chSysUnlock();
chThdYield();
chSysLock();
}
}
else {
/* Setup a default filter.*/
canp->cd_can->sFilterRegister[0].FR1 = 0;
canp->cd_can->sFilterRegister[0].FR2 = 0;
canp->cd_can->FM1R = 0;
canp->cd_can->FFA1R = 0;
canp->cd_can->FS1R = 1;
canp->cd_can->FA1R = 1;
}
canp->cd_can->FMR &= ~CAN_FMR_FINIT;
/* Interrupt sources initialization.*/
canp->cd_can->IER = CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_FMPIE1 |
CAN_IER_WKUIE | CAN_IER_ERRIE | CAN_IER_LECIE |
CAN_IER_BOFIE | CAN_IER_EPVIE | CAN_IER_EWGIE |
CAN_IER_FOVIE0 | CAN_IER_FOVIE1;
}
/**
* @brief Deactivates the CAN peripheral.
*
* @param[in] canp pointer to the @p CANDriver object
*/
void can_lld_stop(CANDriver *canp) {
/* If in ready state then disables the CAN peripheral.*/
if (canp->cd_state == CAN_READY) {
#if USE_STM32_CAN1
if (&CAND1 == canp) {
CAN1->MCR = 0x00010002; /* Register reset value. */
CAN1->IER = 0x00000000; /* All sources disabled. */
NVICDisableVector(USB_HP_CAN1_TX_IRQn);
NVICDisableVector(USB_LP_CAN1_RX0_IRQn);
NVICDisableVector(CAN1_RX1_IRQn);
NVICDisableVector(CAN1_SCE_IRQn);
RCC->APB1ENR &= ~RCC_APB1ENR_CAN1EN;
}
#endif
}
}
/**
* @brief Determines whether a frame can be transmitted.
*
* @param[in] canp pointer to the @p CANDriver object
*
* @return The queue space availability.
* @retval FALSE no space in the transmit queue.
* @retval TRUE transmit slot available.
*/
bool_t can_lld_can_transmit(CANDriver *canp) {
return (canp->cd_can->TSR & CAN_TSR_TME) != 0;
}
/**
* @brief Inserts a frame into the transmit queue.
*
* @param[in] canp pointer to the @p CANDriver object
* @param[in] ctfp pointer to the CAN frame to be transmitted
*/
void can_lld_transmit(CANDriver *canp, const CANTxFrame *ctfp) {
uint32_t tir;
CAN_TxMailBox_TypeDef *tmbp;
/* Pointer to a free transmission mailbox.*/
tmbp = &canp->cd_can->sTxMailBox[(canp->cd_can->TSR & CAN_TSR_CODE) >> 24];
/* Preparing the message.*/
if (ctfp->cf_IDE)
tir = ((uint32_t)ctfp->cf_EID << 3) | ((uint32_t)ctfp->cf_RTR << 1) |
CAN_TI0R_IDE;
else
tir = ((uint32_t)ctfp->cf_SID << 21) | ((uint32_t)ctfp->cf_RTR << 1);
tmbp->TDTR = ctfp->cf_DLC;
tmbp->TDLR = ctfp->cf_data32[0];
tmbp->TDHR = ctfp->cf_data32[1];
tmbp->TIR = tir | CAN_TI0R_TXRQ;
}
/**
* @brief Determines whether a frame has been received.
*
* @param[in] canp pointer to the @p CANDriver object
*
* @return The queue space availability.
* @retval FALSE no space in the transmit queue.
* @retval TRUE transmit slot available.
*/
bool_t can_lld_can_receive(CANDriver *canp) {
return (canp->cd_can->RF0R & CAN_RF0R_FMP0) > 0;
}
/**
* @brief Receives a frame from the input queue.
*
* @param[in] canp pointer to the @p CANDriver object
* @param[out] crfp pointer to the buffer where the CAN frame is copied
*/
void can_lld_receive(CANDriver *canp, CANRxFrame *crfp) {
uint32_t r;
/* Fetches the message.*/
r = canp->cd_can->sFIFOMailBox[0].RIR;
crfp->cf_RTR = (r & CAN_RI0R_RTR) >> 1;
crfp->cf_IDE = (r & CAN_RI0R_IDE) >> 2;
if (crfp->cf_IDE)
crfp->cf_EID = r >> 3;
else
crfp->cf_SID = r >> 21;
r = canp->cd_can->sFIFOMailBox[0].RDTR;
crfp->cf_DLC = r & CAN_RDT0R_DLC;
crfp->cf_FMI = (uint8_t)(r >> 8);
crfp->cf_TIME = (uint16_t)(r >> 16);
crfp->cf_data32[0] = canp->cd_can->sFIFOMailBox[0].RDLR;
crfp->cf_data32[1] = canp->cd_can->sFIFOMailBox[0].RDHR;
/* Releases the mailbox.*/
canp->cd_can->RF0R = CAN_RF0R_RFOM0;
/* If the queue is empty re-enables the interrupt in order to generate
events again.*/
if ((canp->cd_can->RF0R & CAN_RF0R_FMP0) == 0)
canp->cd_can->IER |= CAN_IER_FMPIE0;
}
#if CAN_USE_SLEEP_MODE || defined(__DOXYGEN__)
/**
* @brief Enters the sleep mode.
*
* @param[in] canp pointer to the @p CANDriver object
*/
void can_lld_sleep(CANDriver *canp) {
canp->cd_can->MCR |= CAN_MCR_SLEEP;
}
/**
* @brief Enforces leaving the sleep mode.
*
* @param[in] canp pointer to the @p CANDriver object
*/
void can_lld_wakeup(CANDriver *canp) {
canp->cd_can->MCR &= ~CAN_MCR_SLEEP;
}
#endif /* CAN_USE_SLEEP_MODE */
#endif /* CH_HAL_USE_CAN */
/** @} */

View File

@@ -0,0 +1,327 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/can_lld.h
* @brief STM32 CAN subsystem low level driver header.
* @addtogroup STM32_CAN
* @{
*/
#ifndef _CAN_LLD_H_
#define _CAN_LLD_H_
#if CH_HAL_USE_CAN || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
/*
* The following macros from the ST header file are replaced with better
* equivalents.
*/
#undef CAN_BTR_BRP
#undef CAN_BTR_TS1
#undef CAN_BTR_TS2
#undef CAN_BTR_SJW
/**
* @brief This switch defines whether the driver implementation supports
* a low power switch mode with automatic an wakeup feature.
*/
#define CAN_SUPPORTS_SLEEP TRUE
/**
* @brief Minimum number of CAN filters.
*/
#if defined(STM32F10X_CL) || defined(__DOXYGEN__)
#define CAN_MAX_FILTERS 28
#else
#define CAN_MAX_FILTERS 14
#endif
#define CAN_BTR_BRP(n) (n) /**< @brief BRP field macro.*/
#define CAN_BTR_TS1(n) ((n) << 16) /**< @brief TS1 field macro.*/
#define CAN_BTR_TS2(n) ((n) << 20) /**< @brief TS2 field macro.*/
#define CAN_BTR_SJW(n) ((n) << 24) /**< @brief SJW field macro.*/
#define CAN_IDE_STD 0 /**< @brief Standard id. */
#define CAN_IDE_EXT 1 /**< @brief Extended id. */
#define CAN_RTR_DATA 0 /**< @brief Data frame. */
#define CAN_RTR_REMOTE 1 /**< @brief Remote frame. */
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @brief CAN1 driver enable switch.
* @details If set to @p TRUE the support for ADC1 is included.
* @note The default is @p TRUE.
*/
#if !defined(USE_STM32_CAN1) || defined(__DOXYGEN__)
#define USE_STM32_CAN1 TRUE
#endif
/**
* @brief CAN1 interrupt priority level setting.
*/
#if !defined(STM32_CAN1_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_CAN1_IRQ_PRIORITY 11
#endif
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
#if CAN_USE_SLEEP_MODE && !CAN_SUPPORTS_SLEEP
#error "CAN sleep mode not supported in this architecture"
#endif
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
/**
* @brief CAN status flags.
*/
typedef uint32_t canstatus_t;
/**
* @brief CAN transmission frame.
* @note Accessing the frame data as word16 or word32 is not portable because
* machine data endianness, it can be still useful for a quick filling.
*/
typedef struct {
struct {
uint8_t cf_DLC:4; /**< @brief Data length. */
uint8_t cf_RTR:1; /**< @brief Frame type. */
uint8_t cf_IDE:1; /**< @brief Identifier type. */
};
union {
struct {
uint32_t cf_SID:11; /**< @brief Standard identifier.*/
};
struct {
uint32_t cf_EID:29; /**< @brief Extended identifier.*/
};
};
union {
uint8_t cf_data8[8]; /**< @brief Frame data. */
uint16_t cf_data16[4]; /**< @brief Frame data. */
uint32_t cf_data32[2]; /**< @brief Frame data. */
};
} CANTxFrame;
/**
* @brief CAN received frame.
* @note Accessing the frame data as word16 or word32 is not portable because
* machine data endianness, it can be still useful for a quick filling.
*/
typedef struct {
struct {
uint8_t cf_FMI; /**< @brief Filter id. */
uint16_t cf_TIME; /**< @brief Time stamp. */
};
struct {
uint8_t cf_DLC:4; /**< @brief Data length. */
uint8_t cf_RTR:1; /**< @brief Frame type. */
uint8_t cf_IDE:1; /**< @brief Identifier type. */
};
union {
struct {
uint32_t cf_SID:11; /**< @brief Standard identifier.*/
};
struct {
uint32_t cf_EID:29; /**< @brief Extended identifier.*/
};
};
union {
uint8_t cf_data8[8]; /**< @brief Frame data. */
uint16_t cf_data16[4]; /**< @brief Frame data. */
uint32_t cf_data32[2]; /**< @brief Frame data. */
};
} CANRxFrame;
/**
* @brief CAN filter.
* @note Refer to the STM32 reference manual for info about filters.
*/
typedef struct {
/**
* @brief Filter mode.
* @note This bit represent the CAN_FM1R register bit associated to this
* filter (0=mask mode, 1=list mode).
*/
uint32_t cf_mode:1;
/**
* @brief Filter sclae.
* @note This bit represent the CAN_FS1R register bit associated to this
* filter (0=16 bits mode, 1=32 bits mode).
*/
uint32_t cf_scale:1;
/**
* @brief Filter mode.
* @note This bit represent the CAN_FFA1R register bit associated to this
* filter, must be set to zero in this version of the driver.
*/
uint32_t cf_assignment:1;
/**
* @brief Filter register 1 (identifier).
*/
uint32_t cf_register1;
/**
* @brief Filter register 2 (mask/identifier depending on cf_mode=0/1).
*/
uint32_t cf_register2;
} CANFilter;
/**
* @brief Driver configuration structure.
*/
typedef struct {
/**
* @brief CAN MCR register initialization data.
* @note Some bits in this register are enforced by the driver regardless
* their status in this field.
*/
uint32_t cc_mcr;
/**
* @brief CAN BTR register initialization data.
* @note Some bits in this register are enforced by the driver regardless
* their status in this field.
*/
uint32_t cc_btr;
/**
* @brief Number of elements into the filters array.
* @note By setting this field to zero a default filter is enabled that
* allows all frames, this should be adequate for simple applications.
*/
uint32_t cc_num;
/**
* @brief Pointer to an array of @p CANFilter structures.
* @note This field can be set to @p NULL if the field @p cc_num is set to
* zero.
*/
const CANFilter *cc_filters;
} CANConfig;
/**
* @brief Structure representing an CAN driver.
*/
typedef struct {
/**
* @brief Driver state.
*/
canstate_t cd_state;
/**
* @brief Current configuration data.
*/
const CANConfig *cd_config;
/**
* @brief Transmission queue semaphore.
*/
Semaphore cd_txsem;
/**
* @brief Receive queue semaphore.
*/
Semaphore cd_rxsem;
/**
* @brief One or more frames become available.
* @note After broadcasting this event it will not be broadcasted again
* until the received frames queue has been completely emptied. It
* is <b>not</b> broadcasted for each received frame. It is
* responsibility of the application to empty the queue by repeatedly
* invoking @p chReceive() when listening to this event. This behavior
* minimizes the interrupt served by the system because CAN traffic.
*/
EventSource cd_rxfull_event;
/**
* @brief One or more transmission slots become available.
*/
EventSource cd_txempty_event;
/**
* @brief A CAN bus error happened.
*/
EventSource cd_error_event;
/**
* @brief Error flags set when an error event is broadcasted.
*/
canstatus_t cd_status;
#if CAN_USE_SLEEP_MODE || defined (__DOXYGEN__)
/**
* @brief Entering sleep state event.
*/
EventSource cd_sleep_event;
/**
* @brief Exiting sleep state event.
*/
EventSource cd_wakeup_event;
#endif /* CAN_USE_SLEEP_MODE */
/* End of the mandatory fields.*/
/**
* @brief Pointer to the CAN registers.
*/
CAN_TypeDef *cd_can;
} CANDriver;
/*===========================================================================*/
/* Driver macros. */
/*===========================================================================*/
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#if USE_STM32_CAN1 && !defined(__DOXYGEN__)
extern CANDriver CAND1;
#endif
#ifdef __cplusplus
extern "C" {
#endif
void can_lld_init(void);
void can_lld_start(CANDriver *canp);
void can_lld_stop(CANDriver *canp);
bool_t can_lld_can_transmit(CANDriver *canp);
void can_lld_transmit(CANDriver *canp, const CANTxFrame *crfp);
bool_t can_lld_can_receive(CANDriver *canp);
void can_lld_receive(CANDriver *canp, CANRxFrame *ctfp);
#if CAN_USE_SLEEP_MODE
void can_lld_sleep(CANDriver *canp);
void can_lld_wakeup(CANDriver *canp);
#endif /* CAN_USE_SLEEP_MODE */
#ifdef __cplusplus
}
#endif
#endif /* CH_HAL_USE_CAN */
#endif /* _CAN_LLD_H_ */
/** @} */

View File

@@ -0,0 +1,212 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/hal_lld.c
* @brief STM32 HAL subsystem low level driver source.
*
* @addtogroup STM32_HAL
* @{
*/
#include "ch.h"
#include "hal.h"
#define AIRCR_VECTKEY 0x05FA0000
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver local variables. */
/*===========================================================================*/
/**
* @brief PAL setup.
* @details Digital I/O ports static configuration as defined in @p board.h.
*/
const PALConfig pal_default_config =
{
{VAL_GPIOAODR, VAL_GPIOACRL, VAL_GPIOACRH},
{VAL_GPIOBODR, VAL_GPIOBCRL, VAL_GPIOBCRH},
{VAL_GPIOCODR, VAL_GPIOCCRL, VAL_GPIOCCRH},
{VAL_GPIODODR, VAL_GPIODCRL, VAL_GPIODCRH},
#if !defined(STM32F10X_LD) && !defined(CPU_WITH_NO_GPIOE)
{VAL_GPIOEODR, VAL_GPIOECRL, VAL_GPIOECRH},
#endif
#if defined(STM32F10X_HD)
{VAL_GPIOFODR, VAL_GPIOFCRL, VAL_GPIOFCRH},
{VAL_GPIOGODR, VAL_GPIOGCRL, VAL_GPIOGCRH},
#endif
};
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level HAL driver initialization.
*/
void hal_lld_init(void) {
/* SysTick initialization using the system clock.*/
SysTick->LOAD = STM32_HCLK / CH_FREQUENCY - 1;
SysTick->VAL = 0;
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
SysTick_CTRL_ENABLE_Msk |
SysTick_CTRL_TICKINT_Msk;
#if CH_HAL_USE_ADC || CH_HAL_USE_SPI
dmaInit();
#endif
}
/**
* @brief STM32 clocks and PLL initialization.
* @note All the involved constants come from the file @p board.h.
*/
#if defined(STM32F10X_LD) || defined(STM32F10X_MD) || \
defined(STM32F10X_HD) || defined(__DOXYGEN__)
/*
* Clocks initialization for the LD, MD and HD sub-families.
*/
void stm32_clock_init(void) {
/* HSI setup, it enforces the reset situation in order to handle possible
problems with JTAG probes and re-initializations.*/
RCC->CR |= RCC_CR_HSION; /* Make sure HSI is ON. */
while (!(RCC->CR & RCC_CR_HSIRDY))
; /* Wait until HSI is stable. */
RCC->CR &= RCC_CR_HSITRIM | RCC_CR_HSION; /* CR Reset value. */
RCC->CFGR = 0; /* CFGR reset value. */
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
; /* Wait until HSI is the source.*/
/* HSE setup, it is only performed if the HSE clock is selected as source
of the system clock (directly or through the PLL).*/
#if (STM32_SW == STM32_SW_HSE) || \
((STM32_SW == STM32_SW_PLL) && (STM32_PLLSRC == STM32_PLLSRC_HSE))
RCC->CR |= RCC_CR_HSEON;
while (!(RCC->CR & RCC_CR_HSERDY))
; /* Waits until HSE is stable. */
#endif
/* PLL setup, it is only performed if the PLL is the selected source of
the system clock else it is left disabled.*/
#if STM32_SW == STM32_SW_PLL
RCC->CFGR |= STM32_PLLMUL | STM32_PLLXTPRE | STM32_PLLSRC;
RCC->CR |= RCC_CR_PLLON;
while (!(RCC->CR & RCC_CR_PLLRDY))
; /* Waits until PLL is stable. */
#endif
/* Clock settings.*/
RCC->CFGR = STM32_MCO | STM32_PLLMUL | STM32_PLLXTPRE | STM32_PLLSRC |
STM32_ADCPRE | STM32_PPRE2 | STM32_PPRE1 | STM32_HPRE;
/* Flash setup and final clock selection. */
FLASH->ACR = STM32_FLASHBITS; /* Flash wait states depending on clock. */
/* Switching on the configured clock source if it is different from HSI.*/
#if (STM32_SW != STM32_SW_HSI)
RCC->CFGR |= STM32_SW; /* Switches on the selected clock source. */
while ((RCC->CFGR & RCC_CFGR_SWS) != (STM32_SW << 2))
;
#endif
}
#elif defined(STM32F10X_CL)
/*
* Clocks initialization for the CL sub-family.
*/
void stm32_clock_init(void) {
/* HSI setup, it enforces the reset situation in order to handle possible
problems with JTAG probes and re-initializations.*/
RCC->CR |= RCC_CR_HSION; /* Make sure HSI is ON. */
while (!(RCC->CR & RCC_CR_HSIRDY))
; /* Wait until HSI is stable. */
RCC->CR &= RCC_CR_HSITRIM | RCC_CR_HSION; /* CR Reset value. */
RCC->CFGR = 0; /* CFGR reset value. */
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
; /* Wait until HSI is the source.*/
RCC->CFGR2 = 0;
/* HSE setup, it is only performed if the HSE clock is selected as source
of the system clock (directly or through the PLLs).*/
#if (STM32_SW == STM32_SW_HSE) || \
((STM32_SW == STM32_SW_PLL) && (STM32_PLLSRC == STM32_PLLSRC_PREDIV1))
RCC->CR |= RCC_CR_HSEON;
while (!(RCC->CR & RCC_CR_HSERDY))
; /* Waits until HSE is stable. */
#endif
/* PLL2 setup, it is only performed if the PLL2 clock is selected as source
for the PLL clock else it is left disabled.*/
#if STM32_SW == STM32_SW_PLL
#if STM32_PREDIV1SRC == STM32_PREDIV1SRC_PLL2
RCC->CFGR2 |= STM32_PREDIV2 | STM32_PLL2MUL;
RCC->CR |= RCC_CR_PLL2ON;
while (!(RCC->CR & RCC_CR_PLL2RDY))
; /* Waits until PLL is stable. */
#endif
/* PLL setup, it is only performed if the PLL is the selected source of
the system clock else it is left disabled.*/
RCC->CFGR2 |= STM32_PREDIV1 | STM32_PREDIV1SRC;
RCC->CFGR |= STM32_PLLMUL | STM32_PLLSRC;
RCC->CR |= RCC_CR_PLLON;
while (!(RCC->CR & RCC_CR_PLLRDY))
; /* Waits until PLL2 is stable. */
#endif
/* Clock settings.*/
RCC->CFGR = STM32_MCO | STM32_PLLMUL | STM32_PLLSRC |
STM32_ADCPRE | STM32_PPRE2 | STM32_PPRE1 | STM32_HPRE;
/* Flash setup and final clock selection. */
FLASH->ACR = STM32_FLASHBITS; /* Flash wait states depending on clock. */
/* Switching on the configured clock source if it is different from HSI.*/
#if (STM32_SW != STM32_SW_HSI)
RCC->CFGR |= STM32_SW; /* Switches on the selected clock source. */
while ((RCC->CFGR & RCC_CFGR_SWS) != (STM32_SW << 2))
;
#endif
}
#else
void stm32_clock_init(void) {}
#endif
/** @} */

View File

@@ -0,0 +1,83 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/hal_lld.h
* @brief STM32 HAL subsystem low level driver header.
*
* @addtogroup STM32_HAL
* @{
*/
#ifndef _HAL_LLD_H_
#define _HAL_LLD_H_
/* Tricks required to make the TRUE/FALSE declaration inside the library
compatible.*/
#undef FALSE
#undef TRUE
#include "stm32f10x.h"
#define FALSE 0
#define TRUE (!FALSE)
#include "nvic.h"
#include "stm32_dma.h"
/**
* @brief Platform name.
*/
#if defined(STM32F10X_MD) || defined(__DOXYGEN__)
#define PLATFORM_NAME "STM32 MD"
#include "hal_lld_f103.h"
#elif defined(STM32F10X_LD)
#define PLATFORM_NAME "STM32 LD"
#include "hal_lld_f103.h"
#elif defined(STM32F10X_HD)
#define PLATFORM_NAME "STM32 HD"
#include "hal_lld_f103.h"
#elif defined(STM32F10X_CL)
#define PLATFORM_NAME "STM32 CL"
#include "hal_lld_f105_f107.h"
#else
#error "STM32 platform unknown or not specified"
#endif
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#ifdef __cplusplus
extern "C" {
#endif
void hal_lld_init(void);
void stm32_clock_init(void);
#ifdef __cplusplus
}
#endif
#endif /* _HAL_LLD_H_ */
/** @} */

View File

@@ -0,0 +1,445 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/hal_lld_f103.h
* @brief STM32F103 HAL subsystem low level driver header.
*
* @addtogroup STM32F103_HAL
* @{
*/
#ifndef _HAL_LLD_F103_H_
#define _HAL_LLD_F103_H_
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
#define STM32_HSICLK 8000000 /**< High speed internal clock. */
#define STM32_LSICLK 40000 /**< Low speed internal clock. */
/* RCC_CFGR register bits definitions.*/
#define STM32_SW_HSI (0 << 0) /**< SYSCLK source is HSI. */
#define STM32_SW_HSE (1 << 0) /**< SYSCLK source is HSE. */
#define STM32_SW_PLL (2 << 0) /**< SYSCLK source is PLL. */
#define STM32_HPRE_DIV1 (0 << 4) /**< SYSCLK divided by 1. */
#define STM32_HPRE_DIV2 (8 << 4) /**< SYSCLK divided by 2. */
#define STM32_HPRE_DIV4 (9 << 4) /**< SYSCLK divided by 4. */
#define STM32_HPRE_DIV8 (10 << 4) /**< SYSCLK divided by 8. */
#define STM32_HPRE_DIV16 (11 << 4) /**< SYSCLK divided by 16. */
#define STM32_HPRE_DIV64 (12 << 4) /**< SYSCLK divided by 64. */
#define STM32_HPRE_DIV128 (13 << 4) /**< SYSCLK divided by 128. */
#define STM32_HPRE_DIV256 (14 << 4) /**< SYSCLK divided by 256. */
#define STM32_HPRE_DIV512 (15 << 4) /**< SYSCLK divided by 512. */
#define STM32_PPRE1_DIV1 (0 << 8) /**< HCLK divided by 1. */
#define STM32_PPRE1_DIV2 (4 << 8) /**< HCLK divided by 2. */
#define STM32_PPRE1_DIV4 (5 << 8) /**< HCLK divided by 4. */
#define STM32_PPRE1_DIV8 (6 << 8) /**< HCLK divided by 8. */
#define STM32_PPRE1_DIV16 (7 << 8) /**< HCLK divided by 16. */
#define STM32_PPRE2_DIV1 (0 << 11) /**< HCLK divided by 1. */
#define STM32_PPRE2_DIV2 (4 << 11) /**< HCLK divided by 2. */
#define STM32_PPRE2_DIV4 (5 << 11) /**< HCLK divided by 4. */
#define STM32_PPRE2_DIV8 (6 << 11) /**< HCLK divided by 8. */
#define STM32_PPRE2_DIV16 (7 << 11) /**< HCLK divided by 16. */
#define STM32_ADCPRE_DIV2 (0 << 14) /**< HCLK divided by 2. */
#define STM32_ADCPRE_DIV4 (1 << 14) /**< HCLK divided by 4. */
#define STM32_ADCPRE_DIV6 (2 << 14) /**< HCLK divided by 6. */
#define STM32_ADCPRE_DIV8 (3 << 14) /**< HCLK divided by 8. */
#define STM32_PLLSRC_HSI (0 << 16) /**< PLL clock source is HSI. */
#define STM32_PLLSRC_HSE (1 << 16) /**< PLL clock source is HSE. */
#define STM32_PLLXTPRE_DIV1 (0 << 17) /**< HSE divided by 1. */
#define STM32_PLLXTPRE_DIV2 (1 << 17) /**< HSE divided by 2. */
#define STM32_MCO_NOCLOCK (0 << 24) /**< No clock on MCO pin. */
#define STM32_MCO_SYSCLK (4 << 24) /**< SYSCLK on MCO pin. */
#define STM32_MCO_HSI (5 << 24) /**< HSI clock on MCO pin. */
#define STM32_MCO_HSE (6 << 24) /**< HSE clock on MCO pin. */
#define STM32_MCO_PLLDIV2 (7 << 24) /**< PLL/2 clock on MCO pin. */
/*===========================================================================*/
/* Platform specific friendly IRQ names. */
/*===========================================================================*/
#define WWDG_IRQHandler Vector40 /**< Window Watchdog. */
#define PVD_IRQHandler Vector44 /**< PVD through EXTI Line
detect. */
#define TAMPER_IRQHandler Vector48 /**< Tamper. */
#define RTC_IRQHandler Vector4C /**< RTC. */
#define FLASH_IRQHandler Vector50 /**< Flash. */
#define RCC_IRQHandler Vector54 /**< RCC. */
#define EXTI0_IRQHandler Vector58 /**< EXTI Line 0. */
#define EXTI1_IRQHandler Vector5C /**< EXTI Line 1. */
#define EXTI2_IRQHandler Vector60 /**< EXTI Line 2. */
#define EXTI3_IRQHandler Vector64 /**< EXTI Line 3. */
#define EXTI4_IRQHandler Vector68 /**< EXTI Line 4. */
#define DMA1_Ch1_IRQHandler Vector6C /**< DMA1 Channel 1. */
#define DMA1_Ch2_IRQHandler Vector70 /**< DMA1 Channel 2. */
#define DMA1_Ch3_IRQHandler Vector74 /**< DMA1 Channel 3. */
#define DMA1_Ch4_IRQHandler Vector78 /**< DMA1 Channel 4. */
#define DMA1_Ch5_IRQHandler Vector7C /**< DMA1 Channel 5. */
#define DMA1_Ch6_IRQHandler Vector80 /**< DMA1 Channel 6. */
#define DMA1_Ch7_IRQHandler Vector84 /**< DMA1 Channel 7. */
#define ADC1_2_IRQHandler Vector88 /**< ADC1_2. */
#define CAN1_TX_IRQHandler Vector8C /**< CAN1 TX. */
#define USB_HP_IRQHandler Vector8C /**< USB High Priority, CAN1 TX.*/
#define CAN1_RX0_IRQHandler Vector90 /**< CAN1 RX0. */
#define USB_LP_IRQHandler Vector90 /**< USB Low Priority, CAN1 RX0.*/
#define CAN1_RX1_IRQHandler Vector94 /**< CAN1 RX1. */
#define CAN1_SCE_IRQHandler Vector98 /**< CAN1 SCE. */
#define EXTI9_5_IRQHandler Vector9C /**< EXTI Line 9..5. */
#define TIM1_BRK_IRQHandler VectorA0 /**< TIM1 Break. */
#define TIM1_UP_IRQHandler VectorA4 /**< TIM1 Update. */
#define TIM1_TRG_COM_IRQHandler VectorA8 /**< TIM1 Trigger and
Commutation. */
#define TIM1_CC_IRQHandler VectorAC /**< TIM1 Capture Compare. */
#define TIM2_IRQHandler VectorB0 /**< TIM2. */
#define TIM3_IRQHandler VectorB4 /**< TIM3. */
#if defined(STM32F10X_MD) || defined(STM32F10X_HD) || defined(__DOXYGEN__)
#define TIM4_IRQHandler VectorB8 /**< TIM4. */
#endif
#define I2C1_EV_IRQHandler VectorBC /**< I2C1 Event. */
#define I2C1_ER_IRQHandler VectorC0 /**< I2C1 Error. */
#if defined(STM32F10X_MD) || defined(STM32F10X_HD) || defined(__DOXYGEN__)
#define I2C2_EV_IRQHandler VectorC4 /**< I2C2 Event. */
#define I2C2_ER_IRQHandler VectorC8 /**< I2C2 Error. */
#endif
#define SPI1_IRQHandler VectorCC /**< SPI1. */
#if defined(STM32F10X_MD) || defined(STM32F10X_HD) || defined(__DOXYGEN__)
#define SPI2_IRQHandler VectorD0 /**< SPI2. */
#endif
#define USART1_IRQHandler VectorD4 /**< USART1. */
#define USART2_IRQHandler VectorD8 /**< USART2. */
#if defined(STM32F10X_MD) || defined(STM32F10X_HD) || defined(__DOXYGEN__)
#define USART3_IRQHandler VectorDC /**< USART3. */
#endif
#define EXTI15_10_IRQHandler VectorE0 /**< EXTI Line 15..10. */
#define RTCAlarm_IRQHandler VectorE4 /**< RTC Alarm through EXTI. */
#define USBWakeUp_IRQHandler VectorE8 /**< USB Wakeup from suspend. */
#if defined(STM32F10X_HD) || defined(__DOXYGEN__)
#define TIM8_BRK_IRQHandler VectorEC /**< TIM8 Break. */
#define TIM8_UP_IRQHandler VectorF0 /**< TIM8 Update. */
#define TIM8_TRG_COM_IRQHandler VectorF4 /**< TIM8 Trigger and
Commutation. */
#define TIM8_CC_IRQHandler VectorF8 /**< TIM8 Capture Compare. */
#define ADC3_IRQHandler VectorFC /**< ADC3. */
#define FSMC_IRQHandler Vector100 /**< FSMC. */
#define SDIO_IRQHandler Vector104 /**< SDIO. */
#define TIM5_IRQHandler Vector108 /**< TIM5. */
#define SPI3_IRQHandler Vector10C /**< SPI3. */
#define UART4_IRQHandler Vector110 /**< UART4. */
#define UART5_IRQHandler Vector114 /**< UART5. */
#define TIM6_IRQHandler Vector118 /**< TIM6. */
#define TIM7_IRQHandler Vector11C /**< TIM7. */
#define DMA2_Ch1_IRQHandler Vector120 /**< DMA2 Channel1. */
#define DMA2_Ch2_IRQHandler Vector124 /**< DMA2 Channel2. */
#define DMA2_Ch3_IRQHandler Vector128 /**< DMA2 Channel3. */
#define DMA2_Ch4_5_IRQHandler Vector12C /**< DMA2 Channel4 & Channel5. */
#endif
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @brief Main clock source selection.
* @note If the selected clock source is not the PLL then the PLL is not
* initialized and started.
* @note The default value is calculated for a 72MHz system clock from
* a 8MHz crystal using the PLL.
*/
#if !defined(STM32_SW) || defined(__DOXYGEN__)
#define STM32_SW STM32_SW_PLL
#endif
/**
* @brief Clock source for the PLL.
* @note This setting has only effect if the PLL is selected as the
* system clock source.
* @note The default value is calculated for a 72MHz system clock from
* a 8MHz crystal using the PLL.
*/
#if !defined(STM32_PLLSRC) || defined(__DOXYGEN__)
#define STM32_PLLSRC STM32_PLLSRC_HSE
#endif
/**
* @brief Crystal PLL pre-divider.
* @note This setting has only effect if the PLL is selected as the
* system clock source.
* @note The default value is calculated for a 72MHz system clock from
* a 8MHz crystal using the PLL.
*/
#if !defined(STM32_PLLXTPRE) || defined(__DOXYGEN__)
#define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1
#endif
/**
* @brief PLL multiplier value.
* @note The allowed range is 2...16.
* @note The default value is calculated for a 72MHz system clock from
* a 8MHz crystal using the PLL.
*/
#if !defined(STM32_PLLMUL_VALUE) || defined(__DOXYGEN__)
#define STM32_PLLMUL_VALUE 9
#endif
/**
* @brief AHB prescaler value.
* @note The default value is calculated for a 72MHz system clock from
* a 8MHz crystal using the PLL.
*/
#if !defined(STM32_HPRE) || defined(__DOXYGEN__)
#define STM32_HPRE STM32_HPRE_DIV1
#endif
/**
* @brief APB1 prescaler value.
*/
#if !defined(STM32_PPRE1) || defined(__DOXYGEN__)
#define STM32_PPRE1 STM32_PPRE1_DIV2
#endif
/**
* @brief APB2 prescaler value.
*/
#if !defined(STM32_PPRE2) || defined(__DOXYGEN__)
#define STM32_PPRE2 STM32_PPRE2_DIV2
#endif
/**
* @brief ADC prescaler value.
*/
#if !defined(STM32_ADCPRE) || defined(__DOXYGEN__)
#define STM32_ADCPRE STM32_ADCPRE_DIV4
#endif
/**
* @brief MCO pin setting.
*/
#if !defined(STM32_MCO) || defined(__DOXYGEN__)
#define STM32_MCO STM32_MCO_NOCLOCK
#endif
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
/* HSE prescaler setting check.*/
#if (STM32_PLLXTPRE != STM32_PLLXTPRE_DIV1) && \
(STM32_PLLXTPRE != STM32_PLLXTPRE_DIV2)
#error "invalid STM32_PLLXTPRE value specified"
#endif
/**
* @brief PLLMUL field.
*/
#if ((STM32_PLLMUL_VALUE >= 2) && (STM32_PLLMUL_VALUE <= 16)) || \
defined(__DOXYGEN__)
#define STM32_PLLMUL ((STM32_PLLMUL_VALUE - 2) << 18)
#else
#error "invalid STM32_PLLMUL_VALUE value specified"
#endif
/**
* @brief PLL input clock frequency.
*/
#if (STM32_PLLSRC == STM32_PLLSRC_HSE) || defined(__DOXYGEN__)
#if STM32_PLLXTPRE == STM32_PLLXTPRE_DIV1
#define STM32_PLLCLKIN (STM32_HSECLK / 1)
#else
#define STM32_PLLCLKIN (STM32_HSECLK / 2)
#endif
#elif STM32_PLLSRC == STM32_PLLSRC_HSI
#define STM32_PLLCLKIN (STM32_HSICLK / 2)
#else
#error "invalid STM32_PLLSRC value specified"
#endif
/* PLL input frequency range check.*/
#if (STM32_PLLCLKIN < 3000000) || (STM32_PLLCLKIN > 12000000)
#error "STM32_PLLCLKIN outside acceptable range (3...12MHz)"
#endif
/**
* @brief PLL output clock frequency.
*/
#define STM32_PLLCLKOUT (STM32_PLLCLKIN * STM32_PLLMUL_VALUE)
/* PLL output frequency range check.*/
#if (STM32_PLLCLKOUT < 16000000) || (STM32_PLLCLKOUT > 72000000)
#error "STM32_PLLCLKOUT outside acceptable range (16...72MHz)"
#endif
/**
* @brief System clock source.
*/
#if (STM32_SW == STM32_SW_PLL) || defined(__DOXYGEN__)
#define STM32_SYSCLK STM32_PLLCLKOUT
#elif (STM32_SW == STM32_SW_HSI)
#define STM32_SYSCLK STM32_HSICLK
#elif (STM32_SW == STM32_SW_HSE)
#define STM32_SYSCLK STM32_HSECLK
#else
#error "invalid STM32_SYSCLK_SW value specified"
#endif
/* Check on the system clock.*/
#if STM32_SYSCLK > 72000000
#error "STM32_SYSCLK above maximum rated frequency (72MHz)"
#endif
/**
* @brief AHB frequency.
*/
#if (STM32_HPRE == STM32_HPRE_DIV1) || defined(__DOXYGEN__)
#define STM32_HCLK (STM32_SYSCLK / 1)
#elif STM32_HPRE == STM32_HPRE_DIV2
#define STM32_HCLK (STM32_SYSCLK / 2)
#elif STM32_HPRE == STM32_HPRE_DIV4
#define STM32_HCLK (STM32_SYSCLK / 4)
#elif STM32_HPRE == STM32_HPRE_DIV8
#define STM32_HCLK (STM32_SYSCLK / 8)
#elif STM32_HPRE == STM32_HPRE_DIV16
#define STM32_HCLK (STM32_SYSCLK / 16)
#elif STM32_HPRE == STM32_HPRE_DIV64
#define STM32_HCLK (STM32_SYSCLK / 64)
#elif STM32_HPRE == STM32_HPRE_DIV128
#define STM32_HCLK (STM32_SYSCLK / 128)
#elif STM32_HPRE == STM32_HPRE_DIV256
#define STM32_HCLK (STM32_SYSCLK / 256)
#elif STM32_HPRE == STM32_HPRE_DIV512
#define STM32_HCLK (STM32_SYSCLK / 512)
#else
#error "invalid STM32_HPRE value specified"
#endif
/* AHB frequency check.*/
#if STM32_HCLK > 72000000
#error "STM32_HCLK exceeding maximum frequency (72MHz)"
#endif
/**
* @brief APB1 frequency.
*/
#if (STM32_PPRE1 == STM32_PPRE1_DIV1) || defined(__DOXYGEN__)
#define STM32_PCLK1 (STM32_HCLK / 1)
#elif STM32_PPRE1 == STM32_PPRE1_DIV2
#define STM32_PCLK1 (STM32_HCLK / 2)
#elif STM32_PPRE1 == STM32_PPRE1_DIV4
#define STM32_PCLK1 (STM32_HCLK / 4)
#elif STM32_PPRE1 == STM32_PPRE1_DIV8
#define STM32_PCLK1 (STM32_HCLK / 8)
#elif STM32_PPRE1 == STM32_PPRE1_DIV16
#define STM32_PCLK1 (STM32_HCLK / 16)
#else
#error "invalid STM32_PPRE1 value specified"
#endif
/* APB1 frequency check.*/
#if STM32_PCLK2 > 36000000
#error "STM32_PCLK1 exceeding maximum frequency (36MHz)"
#endif
/**
* @brief APB2 frequency.
*/
#if (STM32_PPRE2 == STM32_PPRE2_DIV1) || defined(__DOXYGEN__)
#define STM32_PCLK2 (STM32_HCLK / 1)
#elif STM32_PPRE2 == STM32_PPRE2_DIV2
#define STM32_PCLK2 (STM32_HCLK / 2)
#elif STM32_PPRE2 == STM32_PPRE2_DIV4
#define STM32_PCLK2 (STM32_HCLK / 4)
#elif STM32_PPRE2 == STM32_PPRE2_DIV8
#define STM32_PCLK2 (STM32_HCLK / 8)
#elif STM32_PPRE2 == STM32_PPRE2_DIV16
#define STM32_PCLK2 (STM32_HCLK / 16)
#else
#error "invalid STM32_PPRE2 value specified"
#endif
/* APB2 frequency check.*/
#if STM32_PCLK2 > 72000000
#error "STM32_PCLK2 exceeding maximum frequency (72MHz)"
#endif
/**
* @brief ADC frequency.
*/
#if (STM32_ADCPRE == STM32_ADCPRE_DIV2) || defined(__DOXYGEN__)
#define STM32_ADCCLK (STM32_PCLK2 / 2)
#elif STM32_ADCPRE == STM32_ADCPRE_DIV4
#define STM32_ADCCLK (STM32_PCLK2 / 4)
#elif STM32_ADCPRE == STM32_ADCPRE_DIV6
#define STM32_ADCCLK (STM32_PCLK2 / 6)
#elif STM32_ADCPRE == STM32_ADCPRE_DIV8
#define STM32_ADCCLK (STM32_PCLK2 / 8)
#else
#error "invalid STM32_ADCPRE value specified"
#endif
/* ADC frequency check.*/
#if STM32_ADCCLK > 14000000
#error "STM32_ADCCLK exceeding maximum frequency (14MHz)"
#endif
/**
* @brief Timers 2, 3, 4, 5, 6, 7, 12, 13, 14 clock.
*/
#if (STM32_PPRE1 == STM32_PPRE1_DIV1) || defined(__DOXYGEN__)
#define STM32_TIMCLK1 (STM32_PCLK1 * 1)
#else
#define STM32_TIMCLK1 (STM32_PCLK1 * 2)
#endif
/**
* @brief Timers 1, 8, 9, 10 and 11 clock.
*/
#if (STM32_PPRE2 == STM32_PPRE2_DIV1) || defined(__DOXYGEN__)
#define STM32_TIMCLK2 (STM32_PCLK2 * 1)
#else
#define STM32_TIMCLK2 (STM32_PCLK2 * 2)
#endif
/**
* @brief Flash settings.
*/
#if (STM32_HCLK <= 24000000) || defined(__DOXYGEN__)
#define STM32_FLASHBITS 0x00000010
#elif STM32_HCLK <= 48000000
#define STM32_FLASHBITS 0x00000011
#else
#define STM32_FLASHBITS 0x00000012
#endif
#endif /* _HAL_LLD_F103_H_ */
/** @} */

View File

@@ -0,0 +1,538 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/hal_lld_f105_f107.h
* @brief STM32F10x Connectivity Line HAL subsystem low level driver header.
*
* @addtogroup STM32F10X_CL_HAL
* @{
*/
#ifndef _HAL_LLD_F105_F107_H_
#define _HAL_LLD_F105_F107_H_
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
#define STM32_HSICLK 8000000 /**< High speed internal clock. */
#define STM32_LSICLK 40000 /**< Low speed internal clock. */
/* RCC_CFGR register bits definitions.*/
#define STM32_SW_HSI (0 << 0) /**< SYSCLK source is HSI. */
#define STM32_SW_HSE (1 << 0) /**< SYSCLK source is HSE. */
#define STM32_SW_PLL (2 << 0) /**< SYSCLK source is PLL. */
#define STM32_HPRE_DIV1 (0 << 4) /**< SYSCLK divided by 1. */
#define STM32_HPRE_DIV2 (8 << 4) /**< SYSCLK divided by 2. */
#define STM32_HPRE_DIV4 (9 << 4) /**< SYSCLK divided by 4. */
#define STM32_HPRE_DIV8 (10 << 4) /**< SYSCLK divided by 8. */
#define STM32_HPRE_DIV16 (11 << 4) /**< SYSCLK divided by 16. */
#define STM32_HPRE_DIV64 (12 << 4) /**< SYSCLK divided by 64. */
#define STM32_HPRE_DIV128 (13 << 4) /**< SYSCLK divided by 128. */
#define STM32_HPRE_DIV256 (14 << 4) /**< SYSCLK divided by 256. */
#define STM32_HPRE_DIV512 (15 << 4) /**< SYSCLK divided by 512. */
#define STM32_PPRE1_DIV1 (0 << 8) /**< HCLK divided by 1. */
#define STM32_PPRE1_DIV2 (4 << 8) /**< HCLK divided by 2. */
#define STM32_PPRE1_DIV4 (5 << 8) /**< HCLK divided by 4. */
#define STM32_PPRE1_DIV8 (6 << 8) /**< HCLK divided by 8. */
#define STM32_PPRE1_DIV16 (7 << 8) /**< HCLK divided by 16. */
#define STM32_PPRE2_DIV1 (0 << 11) /**< HCLK divided by 1. */
#define STM32_PPRE2_DIV2 (4 << 11) /**< HCLK divided by 2. */
#define STM32_PPRE2_DIV4 (5 << 11) /**< HCLK divided by 4. */
#define STM32_PPRE2_DIV8 (6 << 11) /**< HCLK divided by 8. */
#define STM32_PPRE2_DIV16 (7 << 11) /**< HCLK divided by 16. */
#define STM32_ADCPRE_DIV2 (0 << 14) /**< HCLK divided by 2. */
#define STM32_ADCPRE_DIV4 (1 << 14) /**< HCLK divided by 4. */
#define STM32_ADCPRE_DIV6 (2 << 14) /**< HCLK divided by 6. */
#define STM32_ADCPRE_DIV8 (3 << 14) /**< HCLK divided by 8. */
#define STM32_PLLSRC_HSI (0 << 16) /**< PLL clock source is HSI. */
#define STM32_PLLSRC_PREDIV1 (1 << 16) /**< PLL clock source is
PREDIV1. */
#define STM32_OTGFSPRE_DIV2 (1 << 22) /**< HCLK*2 divided by 2. */
#define STM32_OTGFSPRE_DIV3 (0 << 22) /**< HCLK*2 divided by 3. */
#define STM32_MCO_NOCLOCK (0 << 24) /**< No clock on MCO pin. */
#define STM32_MCO_SYSCLK (4 << 24) /**< SYSCLK on MCO pin. */
#define STM32_MCO_HSI (5 << 24) /**< HSI clock on MCO pin. */
#define STM32_MCO_HSE (6 << 24) /**< HSE clock on MCO pin. */
#define STM32_MCO_PLLDIV2 (7 << 24) /**< PLL/2 clock on MCO pin. */
#define STM32_MCO_PLL2 (8 << 24) /**< PLL2 clock on MCO pin. */
#define STM32_MCO_PLL3DIV2 (9 << 24) /**< PLL3/2 clock on MCO pin. */
#define STM32_MCO_XT1 (10 << 24) /**< XT1 clock on MCO pin. */
#define STM32_MCO_PLL3 (11 << 24) /**< PLL3 clock on MCO pin. */
/* RCC_CFGR2 register bits definitions.*/
#define STM32_PREDIV1SRC_HSE (0 << 16) /**< PREDIV1 source is HSE. */
#define STM32_PREDIV1SRC_PLL2 (1 << 16) /**< PREDIV1 source is PLL2. */
/*===========================================================================*/
/* Platform specific friendly IRQ names. */
/*===========================================================================*/
#define WWDG_IRQHandler Vector40 /**< Window Watchdog. */
#define PVD_IRQHandler Vector44 /**< PVD through EXTI Line
detect. */
#define TAMPER_IRQHandler Vector48 /**< Tamper. */
#define RTC_IRQHandler Vector4C /**< RTC. */
#define FLASH_IRQHandler Vector50 /**< Flash. */
#define RCC_IRQHandler Vector54 /**< RCC. */
#define EXTI0_IRQHandler Vector58 /**< EXTI Line 0. */
#define EXTI1_IRQHandler Vector5C /**< EXTI Line 1. */
#define EXTI2_IRQHandler Vector60 /**< EXTI Line 2. */
#define EXTI3_IRQHandler Vector64 /**< EXTI Line 3. */
#define EXTI4_IRQHandler Vector68 /**< EXTI Line 4. */
#define DMA1_Ch1_IRQHandler Vector6C /**< DMA1 Channel 1. */
#define DMA1_Ch2_IRQHandler Vector70 /**< DMA1 Channel 2. */
#define DMA1_Ch3_IRQHandler Vector74 /**< DMA1 Channel 3. */
#define DMA1_Ch4_IRQHandler Vector78 /**< DMA1 Channel 4. */
#define DMA1_Ch5_IRQHandler Vector7C /**< DMA1 Channel 5. */
#define DMA1_Ch6_IRQHandler Vector80 /**< DMA1 Channel 6. */
#define DMA1_Ch7_IRQHandler Vector84 /**< DMA1 Channel 7. */
#define ADC1_2_IRQHandler Vector88 /**< ADC1 and ADC2. */
#define CAN1_TX_IRQHandler Vector8C /**< CAN1 TX. */
#define CAN1_RX0_IRQHandler Vector90 /**< CAN1 RX0. */
#define CAN1_RX1_IRQHandler Vector94 /**< CAN1 RX1. */
#define CAN1_SCE_IRQHandler Vector98 /**< CAN1 SCE. */
#define EXTI9_5_IRQHandler Vector9C /**< EXTI Line 9..5. */
#define TIM1_BRK_IRQHandler VectorA0 /**< TIM1 Break. */
#define TIM1_UP_IRQHandler VectorA4 /**< TIM1 Update. */
#define TIM1_TRG_COM_IRQHandler VectorA8 /**< TIM1 Trigger and
Commutation. */
#define TIM1_CC_IRQHandler VectorAC /**< TIM1 Capture Compare. */
#define TIM2_IRQHandler VectorB0 /**< TIM2. */
#define TIM3_IRQHandler VectorB4 /**< TIM3. */
#define TIM4_IRQHandler VectorB8 /**< TIM4. */
#define I2C1_EV_IRQHandler VectorBC /**< I2C1 Event. */
#define I2C1_ER_IRQHandler VectorC0 /**< I2C1 Error. */
#define I2C2_EV_IRQHandler VectorC4 /**< I2C2 Event. */
#define I2C2_ER_IRQHandler VectorC8 /**< I2C1 Error. */
#define SPI1_IRQHandler VectorCC /**< SPI1. */
#define SPI2_IRQHandler VectorD0 /**< SPI2. */
#define USART1_IRQHandler VectorD4 /**< USART1. */
#define USART2_IRQHandler VectorD8 /**< USART2. */
#define USART3_IRQHandler VectorDC /**< USART3. */
#define EXTI15_10_IRQHandler VectorE0 /**< EXTI Line 15..10. */
#define RTCAlarm_IRQHandler VectorE4 /**< RTC alarm through EXTI
line. */
#define OTG_FS_WKUP_IRQHandler VectorE8 /**< USB OTG FS Wakeup through
EXTI line. */
#define TIM5_IRQHandler Vector108 /**< TIM5. */
#define SPI3_IRQHandler Vector10C /**< SPI3. */
#define UART4_IRQHandler Vector110 /**< UART4. */
#define UART5_IRQHandler Vector114 /**< UART5. */
#define TIM6_IRQHandler Vector118 /**< TIM6. */
#define TIM7_IRQHandler Vector11C /**< TIM7. */
#define DMA2_Ch1_IRQHandler Vector120 /**< DMA2 Channel1. */
#define DMA2_Ch2_IRQHandler Vector124 /**< DMA2 Channel2. */
#define DMA2_Ch3_IRQHandler Vector128 /**< DMA2 Channel3. */
#define DMA2_Ch4_IRQHandler Vector12C /**< DMA2 Channel4. */
#define DMA2_Ch5_IRQHandler Vector130 /**< DMA2 Channel5. */
#define ETH_IRQHandler Vector134 /**< Ethernet. */
#define ETH_WKUP_IRQHandler Vector138 /**< Ethernet Wakeup through
EXTI line. */
#define CAN2_TX_IRQHandler Vector13C /**< CAN2 TX. */
#define CAN2_RX0_IRQHandler Vector140 /**< CAN2 RX0. */
#define CAN2_RX1_IRQHandler Vector144 /**< CAN2 RX1. */
#define CAN2_SCE_IRQHandler Vector148 /**< CAN2 SCE. */
#define OTG_FS_IRQHandler Vector14C /**< USB OTG FS. */
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @brief Main clock source selection.
* @note If the selected clock source is not the PLL then the PLL is not
* initialized and started.
* @note The default value is calculated for a 72MHz system clock from
* a 25MHz crystal using both PLL and PLL2.
*/
#if !defined(STM32_SW) || defined(__DOXYGEN__)
#define STM32_SW STM32_SW_PLL
#endif
/**
* @brief Clock source for the PLL.
* @note This setting has only effect if the PLL is selected as the
* system clock source.
* @note The default value is calculated for a 72MHz system clock from
* a 25MHz crystal using both PLL and PLL2.
*/
#if !defined(STM32_PLLSRC) || defined(__DOXYGEN__)
#define STM32_PLLSRC STM32_PLLSRC_PREDIV1
#endif
/**
* @brief PREDIV1 clock source.
* @note This setting has only effect if the PLL is selected as the
* system clock source.
* @note The default value is calculated for a 72MHz system clock from
* a 25MHz crystal using both PLL and PLL2.
*/
#if !defined(STM32_PREDIV1SRC) || defined(__DOXYGEN__)
#define STM32_PREDIV1SRC STM32_PREDIV1SRC_PLL2
#endif
/**
* @brief PREDIV1 division factor.
* @note This setting has only effect if the PLL is selected as the
* system clock source.
* @note The allowed range is 1...16.
* @note The default value is calculated for a 72MHz system clock from
* a 25MHz crystal using both PLL and PLL2.
*/
#if !defined(STM32_PREDIV1_VALUE) || defined(__DOXYGEN__)
#define STM32_PREDIV1_VALUE 5
#endif
/**
* @brief PLL multiplier value.
* @note The allowed range is 4...9.
* @note The default value is calculated for a 72MHz system clock from
* a 25MHz crystal using both PLL and PLL2.
*/
#if !defined(STM32_PLLMUL_VALUE) || defined(__DOXYGEN__)
#define STM32_PLLMUL_VALUE 9
#endif
/**
* @brief PREDIV2 division factor.
* @note This setting has only effect if the PLL2 is selected as the
* clock source for the PLL.
* @note The allowed range is 1...16.
* @note The default value is calculated for a 72MHz system clock from
* a 25MHz crystal using both PLL and PLL2.
*/
#if !defined(STM32_PREDIV2_VALUE) || defined(__DOXYGEN__)
#define STM32_PREDIV2_VALUE 5
#endif
/**
* @brief PLL2 multiplier value.
* @note The default value is calculated for a 72MHz system clock from
* a 25MHz crystal using both PLL and PLL2.
*/
#if !defined(STM32_PLL2MUL_VALUE) || defined(__DOXYGEN__)
#define STM32_PLL2MUL_VALUE 8
#endif
/**
* @brief AHB prescaler value.
* @note The default value is calculated for a 72MHz system clock from
* a 25MHz crystal using both PLL and PLL2.
*/
#if !defined(STM32_HPRE) || defined(__DOXYGEN__)
#define STM32_HPRE STM32_HPRE_DIV1
#endif
/**
* @brief APB1 prescaler value.
*/
#if !defined(STM32_PPRE1) || defined(__DOXYGEN__)
#define STM32_PPRE1 STM32_PPRE1_DIV2
#endif
/**
* @brief APB2 prescaler value.
*/
#if !defined(STM32_PPRE2) || defined(__DOXYGEN__)
#define STM32_PPRE2 STM32_PPRE2_DIV2
#endif
/**
* @brief ADC prescaler value.
*/
#if !defined(STM32_ADCPRE) || defined(__DOXYGEN__)
#define STM32_ADCPRE STM32_ADCPRE_DIV4
#endif
/**
* @brief MCO pin setting.
*/
#if !defined(STM32_MCO) || defined(__DOXYGEN__)
#define STM32_MCO STM32_MCO_NOCLOCK
#endif
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
/**
* @brief PREDIV1 field.
*/
#if (STM32_PREDIV1_VALUE >= 1) && (STM32_PREDIV1_VALUE <= 16) || \
defined(__DOXYGEN__)
#define STM32_PREDIV1 ((STM32_PREDIV1_VALUE - 1) << 0)
#else
#error "invalid STM32_PREDIV1_VALUE value specified"
#endif
/**
* @brief PREDIV2 field.
*/
#if (STM32_PREDIV2_VALUE >= 1) && (STM32_PREDIV2_VALUE <= 16) || \
defined(__DOXYGEN__)
#define STM32_PREDIV2 ((STM32_PREDIV2_VALUE - 1) << 4)
#else
#error "invalid STM32_PREDIV2_VALUE value specified"
#endif
/**
* @brief PLLMUL field.
*/
#if ((STM32_PLLMUL_VALUE >= 4) && (STM32_PLLMUL_VALUE <= 9)) || \
defined(__DOXYGEN__)
#define STM32_PLLMUL ((STM32_PLLMUL_VALUE - 2) << 18)
#else
#error "invalid STM32_PLLMUL_VALUE value specified"
#endif
/**
* @brief PLL2MUL field.
*/
#if ((STM32_PLL2MUL_VALUE >= 8) && (STM32_PLL2MUL_VALUE <= 14)) || \
defined(__DOXYGEN__)
#define STM32_PLL2MUL ((STM32_PLL2MUL_VALUE - 2) << 8)
#elif (STM32_PLL2MUL_VALUE == 16)
#define STM32_PLL2MUL (14 << 8)
#elif (STM32_PLL2MUL_VALUE == 20)
#define STM32_PLL2MUL (15 << 8)
#else
#error "invalid STM32_PLL2MUL_VALUE value specified"
#endif
/* The following values are only used if PLL2 clock is selected as source
for the PLL clock */
#if (STM32_PREDIV1SRC == STM32_PREDIV1SRC_PLL2) || defined(__DOXYGEN__)
/**
* @brief PLL2 input frequency.
*/
#define STM32_PLL2CLKIN (STM32_HSECLK / STM32_PREDIV2_VALUE)
/* PLL2 input frequency range check.*/
#if (STM32_PLL2CLKIN < 3000000) || (STM32_PLL2CLKIN > 5000000)
#error "STM32_PLL2CLKIN outside acceptable range (3...5MHz)"
#endif
/**
* @brief PLL2 output clock frequency.
*/
#define STM32_PLL2CLKOUT (STM32_PLL2CLKIN * STM32_PLL2MUL_VALUE)
/* PLL2 output frequency range check.*/
#if (STM32_PLL2CLKOUT < 40000000) || (STM32_PLL2CLKOUT > 74000000)
#error "STM32_PLL2CLKOUT outside acceptable range (40...74MHz)"
#endif
#endif /* STM32_PREDIV1SRC == STM32_PREDIV1SRC_PLL2 */
/**
* @brief PREDIV1 input frequency.
*/
#if (STM32_PREDIV1SRC == STM32_PREDIV1SRC_PLL2) || defined(__DOXYGEN__)
#define STM32_PREDIV1CLK STM32_PLL2CLKOUT
#elif STM32_PREDIV1SRC == STM32_PREDIV1SRC_HSE
#define STM32_PREDIV1CLK STM32_HSECLK
#else
#error "invalid STM32_PREDIV1SRC value specified"
#endif
/**
* @brief PLL input clock frequency.
*/
#if (STM32_PLLSRC == STM32_PLLSRC_PREDIV1) || defined(__DOXYGEN__)
#define STM32_PLLCLKIN (STM32_PREDIV1CLK / STM32_PREDIV1_VALUE)
#elif STM32_PLLSRC == STM32_PLLSRC_HSI
#define STM32_PLLCLKIN (STM32_HSICLK / 2)
#else
#error "invalid STM32_PLLSRC value specified"
#endif
/* PLL input frequency range check.*/
#if (STM32_PLLCLKIN < 3000000) || (STM32_PLLCLKIN > 12000000)
#error "STM32_PLLCLKIN outside acceptable range (3...12MHz)"
#endif
/**
* @brief PLL output clock frequency.
*/
#define STM32_PLLCLKOUT (STM32_PLLCLKIN * STM32_PLLMUL_VALUE)
/* PLL output frequency range check.*/
#if (STM32_PLLCLKOUT < 18000000) || (STM32_PLLCLKOUT > 72000000)
#error "STM32_PLLCLKOUT outside acceptable range (18...72MHz)"
#endif
/**
* @brief System clock source.
*/
#if (STM32_SW == STM32_SW_PLL) || defined(__DOXYGEN__)
#define STM32_SYSCLK STM32_PLLCLKOUT
#elif (STM32_SW == STM32_SW_HSI)
#define STM32_SYSCLK STM32_HSICLK
#elif (STM32_SW == STM32_SW_HSE)
#define STM32_SYSCLK STM32_HSECLK
#else
#error "invalid STM32_SYSCLK_SW value specified"
#endif
/* Check on the system clock.*/
#if STM32_SYSCLK > 72000000
#error "STM32_SYSCLK above maximum rated frequency (72MHz)"
#endif
/**
* @brief AHB frequency.
*/
#if (STM32_HPRE == STM32_HPRE_DIV1) || defined(__DOXYGEN__)
#define STM32_HCLK (STM32_SYSCLK / 1)
#elif STM32_HPRE == STM32_HPRE_DIV2
#define STM32_HCLK (STM32_SYSCLK / 2)
#elif STM32_HPRE == STM32_HPRE_DIV4
#define STM32_HCLK (STM32_SYSCLK / 4)
#elif STM32_HPRE == STM32_HPRE_DIV8
#define STM32_HCLK (STM32_SYSCLK / 8)
#elif STM32_HPRE == STM32_HPRE_DIV16
#define STM32_HCLK (STM32_SYSCLK / 16)
#elif STM32_HPRE == STM32_HPRE_DIV64
#define STM32_HCLK (STM32_SYSCLK / 64)
#elif STM32_HPRE == STM32_HPRE_DIV128
#define STM32_HCLK (STM32_SYSCLK / 128)
#elif STM32_HPRE == STM32_HPRE_DIV256
#define STM32_HCLK (STM32_SYSCLK / 256)
#elif STM32_HPRE == STM32_HPRE_DIV512
#define STM32_HCLK (STM32_SYSCLK / 512)
#else
#error "invalid STM32_HPRE value specified"
#endif
/* AHB frequency check.*/
#if STM32_HCLK > 72000000
#error "STM32_HCLK exceeding maximum frequency (72MHz)"
#endif
/**
* @brief APB1 frequency.
*/
#if (STM32_PPRE1 == STM32_PPRE1_DIV1) || defined(__DOXYGEN__)
#define STM32_PCLK1 (STM32_HCLK / 1)
#elif STM32_PPRE1 == STM32_PPRE1_DIV2
#define STM32_PCLK1 (STM32_HCLK / 2)
#elif STM32_PPRE1 == STM32_PPRE1_DIV4
#define STM32_PCLK1 (STM32_HCLK / 4)
#elif STM32_PPRE1 == STM32_PPRE1_DIV8
#define STM32_PCLK1 (STM32_HCLK / 8)
#elif STM32_PPRE1 == STM32_PPRE1_DIV16
#define STM32_PCLK1 (STM32_HCLK / 16)
#else
#error "invalid STM32_PPRE1 value specified"
#endif
/* APB1 frequency check.*/
#if STM32_PCLK1 > 36000000
#error "STM32_PCLK1 exceeding maximum frequency (36MHz)"
#endif
/**
* @brief APB2 frequency.
*/
#if (STM32_PPRE2 == STM32_PPRE2_DIV1) || defined(__DOXYGEN__)
#define STM32_PCLK2 (STM32_HCLK / 1)
#elif STM32_PPRE2 == STM32_PPRE2_DIV2
#define STM32_PCLK2 (STM32_HCLK / 2)
#elif STM32_PPRE2 == STM32_PPRE2_DIV4
#define STM32_PCLK2 (STM32_HCLK / 4)
#elif STM32_PPRE2 == STM32_PPRE2_DIV8
#define STM32_PCLK2 (STM32_HCLK / 8)
#elif STM32_PPRE2 == STM32_PPRE2_DIV16
#define STM32_PCLK2 (STM32_HCLK / 16)
#else
#error "invalid STM32_PPRE2 value specified"
#endif
/* APB2 frequency check.*/
#if STM32_PCLK2 > 72000000
#error "STM32_PCLK2 exceeding maximum frequency (72MHz)"
#endif
/**
* @brief ADC frequency.
*/
#if (STM32_ADCPRE == STM32_ADCPRE_DIV2) || defined(__DOXYGEN__)
#define STM32_ADCCLK (STM32_PCLK2 / 2)
#elif STM32_ADCPRE == STM32_ADCPRE_DIV4
#define STM32_ADCCLK (STM32_PCLK2 / 4)
#elif STM32_ADCPRE == STM32_ADCPRE_DIV6
#define STM32_ADCCLK (STM32_PCLK2 / 6)
#elif STM32_ADCPRE == STM32_ADCPRE_DIV8
#define STM32_ADCCLK (STM32_PCLK2 / 8)
#else
#error "invalid STM32_ADCPRE value specified"
#endif
/* ADC frequency check.*/
#if STM32_ADCCLK > 14000000
#error "STM32_ADCCLK exceeding maximum frequency (14MHz)"
#endif
/**
* @brief Timers 2, 3, 4, 5, 6, 7 clock.
*/
#if (STM32_PPRE1 == STM32_PPRE1_DIV1) || defined(__DOXYGEN__)
#define STM32_TIMCLK1 (STM32_PCLK1 * 1)
#else
#define STM32_TIMCLK1 (STM32_PCLK1 * 2)
#endif
/**
* @brief Timer 1 clock.
*/
#if (STM32_PPRE2 == STM32_PPRE2_DIV1) || defined(__DOXYGEN__)
#define STM32_TIMCLK2 (STM32_PCLK2 * 1)
#else
#define STM32_TIMCLK2 (STM32_PCLK2 * 2)
#endif
/**
* @brief Flash settings.
*/
#if (STM32_HCLK <= 24000000) || defined(__DOXYGEN__)
#define STM32_FLASHBITS 0x00000010
#elif STM32_HCLK <= 48000000
#define STM32_FLASHBITS 0x00000011
#else
#define STM32_FLASHBITS 0x00000012
#endif
#endif /* _HAL_LLD_F105_F107_H_ */
/** @} */

View File

@@ -0,0 +1,200 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/pal_lld.c
* @brief STM32 GPIO low level driver code.
*
* @addtogroup STM32_PAL
* @{
*/
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_PAL || defined(__DOXYGEN__)
#if defined(STM32F10X_LD)
#define APB2_RST_MASK (RCC_APB2RSTR_IOPARST | RCC_APB2RSTR_IOPBRST | \
RCC_APB2RSTR_IOPCRST | RCC_APB2RSTR_IOPDRST | \
RCC_APB2RSTR_AFIORST)
#define APB2_EN_MASK (RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN | \
RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | \
RCC_APB2ENR_AFIOEN)
#elif defined(STM32F10X_HD)
#define APB2_RST_MASK (RCC_APB2RSTR_IOPARST | RCC_APB2RSTR_IOPBRST | \
RCC_APB2RSTR_IOPCRST | RCC_APB2RSTR_IOPDRST | \
RCC_APB2RSTR_IOPERST | RCC_APB2RSTR_IOPFRST | \
RCC_APB2RSTR_IOPGRST | RCC_APB2RSTR_AFIORST);
#define APB2_EN_MASK (RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN | \
RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | \
RCC_APB2ENR_IOPEEN | RCC_APB2ENR_IOPFEN | \
RCC_APB2ENR_IOPGEN | RCC_APB2ENR_AFIOEN)
#else
/* Defaults on Medium Density and Connection Line devices.*/
#define APB2_RST_MASK (RCC_APB2RSTR_IOPARST | RCC_APB2RSTR_IOPBRST | \
RCC_APB2RSTR_IOPCRST | RCC_APB2RSTR_IOPDRST | \
RCC_APB2RSTR_IOPERST | RCC_APB2RSTR_AFIORST);
#define APB2_EN_MASK (RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN | \
RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | \
RCC_APB2ENR_IOPEEN | RCC_APB2ENR_AFIOEN)
#endif
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver local variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief STM32 I/O ports configuration.
* @details Ports A-D(E, F, G) clocks enabled, AFIO clock enabled.
*
* @param[in] config the STM32 ports configuration
*/
void _pal_lld_init(const PALConfig *config) {
/*
* Enables the GPIO related clocks.
*/
RCC->APB2ENR |= APB2_EN_MASK;
/*
* Resets the GPIO ports and AFIO.
*/
RCC->APB2RSTR = APB2_RST_MASK;
RCC->APB2RSTR = 0;
IOPORT1->ODR = config->PAData.odr;
IOPORT1->CRH = config->PAData.crh;
IOPORT1->CRL = config->PAData.crl;
IOPORT2->ODR = config->PBData.odr;
IOPORT2->CRH = config->PBData.crh;
IOPORT2->CRL = config->PBData.crl;
IOPORT3->ODR = config->PCData.odr;
IOPORT3->CRH = config->PCData.crh;
IOPORT3->CRL = config->PCData.crl;
IOPORT4->ODR = config->PDData.odr;
IOPORT4->CRH = config->PDData.crh;
IOPORT4->CRL = config->PDData.crl;
#if !(defined(STM32F10X_LD) || defined(CPU_WITH_NO_GPIOE)) || defined(__DOXYGEN__)
IOPORT5->ODR = config->PEData.odr;
IOPORT5->CRH = config->PEData.crh;
IOPORT5->CRL = config->PEData.crl;
#endif
#if defined(STM32F10X_HD) || defined(__DOXYGEN__)
IOPORT6->ODR = config->PFData.odr;
IOPORT6->CRH = config->PFData.crh;
IOPORT6->CRL = config->PFData.crl;
IOPORT7->ODR = config->PGData.odr;
IOPORT7->CRH = config->PGData.crh;
IOPORT7->CRL = config->PGData.crl;
#endif
}
/**
* @brief Pads mode setup.
* @details This function programs a pads group belonging to the same port
* with the specified mode.
* @note This function is not meant to be invoked directly by the
* application code.
* @note @p PAL_MODE_UNCONNECTED is implemented as push pull output at 2MHz.
* @note Writing on pads programmed as pull-up or pull-down has the side
* effect to modify the resistor setting because the output latched
* data is used for the resistor selection.
*
* @param[in] port the port identifier
* @param[in] mask the group mask
* @param[in] mode the mode
*/
void _pal_lld_setgroupmode(ioportid_t port,
ioportmask_t mask,
uint_fast8_t mode) {
static const uint8_t cfgtab[] = {
4, /* PAL_MODE_RESET, implemented as input.*/
2, /* PAL_MODE_UNCONNECTED, implemented as push pull output 2MHz.*/
4, /* PAL_MODE_INPUT */
8, /* PAL_MODE_INPUT_PULLUP */
8, /* PAL_MODE_INPUT_PULLDOWN */
0, /* PAL_MODE_INPUT_ANALOG */
3, /* PAL_MODE_OUTPUT_PUSHPULL, 50MHz.*/
7, /* PAL_MODE_OUTPUT_OPENDRAIN, 50MHz.*/
8, /* Reserved.*/
8, /* Reserved.*/
8, /* Reserved.*/
8, /* Reserved.*/
8, /* Reserved.*/
8, /* Reserved.*/
8, /* Reserved.*/
8, /* Reserved.*/
0xB, /* PAL_MODE_STM32_ALTERNATE_PUSHPULL, 50MHz.*/
0xF, /* PAL_MODE_STM32_ALTERNATE_OPENDRAIN, 50MHz.*/
};
uint32_t mh, ml, crh, crl, cfg;
unsigned i;
if (mode == PAL_MODE_INPUT_PULLUP)
port->BSRR = mask;
else if (mode == PAL_MODE_INPUT_PULLDOWN)
port->BRR = mask;
cfg = cfgtab[mode];
mh = ml = crh = crl = 0;
for (i = 0; i < 8; i++) {
ml <<= 4;
mh <<= 4;
crl <<= 4;
crh <<= 4;
if ((mask & 0x0080) == 0)
ml |= 0xf;
else
crl |= cfg;
if ((mask & 0x8000) == 0)
mh |= 0xf;
else
crh |= cfg;
mask <<= 1;
}
port->CRH = (port->CRH & mh) | crh;
port->CRL = (port->CRL & ml) | crl;
}
#endif /* CH_HAL_USE_PAL */
/** @} */

View File

@@ -0,0 +1,316 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/pal_lld.h
* @brief STM32 GPIO low level driver header.
*
* @addtogroup STM32_PAL
* @{
*/
#ifndef _PAL_LLD_H_
#define _PAL_LLD_H_
#if CH_HAL_USE_PAL || defined(__DOXYGEN__)
/*===========================================================================*/
/* Unsupported modes and specific modes */
/*===========================================================================*/
/**
* @brief STM32 specific alternate push-pull output mode.
*/
#define PAL_MODE_STM32_ALTERNATE_PUSHPULL 16
/**
* @brief STM32 specific alternate open-drain output mode.
*/
#define PAL_MODE_STM32_ALTERNATE_OPENDRAIN 17
/*===========================================================================*/
/* I/O Ports Types and constants. */
/*===========================================================================*/
/**
* @brief GPIO port setup info.
*/
typedef struct {
/** Initial value for ODR register.*/
uint32_t odr;
/** Initial value for CRL register.*/
uint32_t crl;
/** Initial value for CRH register.*/
uint32_t crh;
} stm32_gpio_setup_t;
/**
* @brief STM32 GPIO static initializer.
* @details An instance of this structure must be passed to @p palInit() at
* system startup time in order to initialize the digital I/O
* subsystem. This represents only the initial setup, specific pads
* or whole ports can be reprogrammed at later time.
*/
typedef struct {
/** @brief Port A setup data.*/
stm32_gpio_setup_t PAData;
/** @brief Port B setup data.*/
stm32_gpio_setup_t PBData;
/** @brief Port C setup data.*/
stm32_gpio_setup_t PCData;
/** @brief Port D setup data.*/
stm32_gpio_setup_t PDData;
#if !(defined(STM32F10X_LD) || defined(CPU_WITH_NO_GPIOE)) || defined(__DOXYGEN__)
/** @brief Port E setup data.*/
stm32_gpio_setup_t PEData;
#endif
#if defined(STM32F10X_HD) || defined(__DOXYGEN__)
/** @brief Port F setup data.*/
stm32_gpio_setup_t PFData;
/** @brief Port G setup data.*/
stm32_gpio_setup_t PGData;
#endif
} PALConfig;
/**
* @brief Width, in bits, of an I/O port.
*/
#define PAL_IOPORTS_WIDTH 16
/**
* @brief Whole port mask.
* @brief This macro specifies all the valid bits into a port.
*/
#define PAL_WHOLE_PORT ((ioportmask_t)0xFFFF)
/**
* @brief Digital I/O port sized unsigned type.
*/
typedef uint32_t ioportmask_t;
/**
* @brief Port Identifier.
* @details This type can be a scalar or some kind of pointer, do not make
* any assumption about it, use the provided macros when populating
* variables of this type.
*/
typedef GPIO_TypeDef * ioportid_t;
/*===========================================================================*/
/* I/O Ports Identifiers. */
/* The low level driver wraps the definitions already present in the STM32 */
/* firmware library. */
/*===========================================================================*/
/**
* @brief GPIO port A identifier.
*/
#define IOPORT1 GPIOA
/**
* @brief GPIO port B identifier.
*/
#define IOPORT2 GPIOB
/**
* @brief GPIO port C identifier.
*/
#define IOPORT3 GPIOC
/**
* @brief GPIO port D identifier.
*/
#define IOPORT4 GPIOD
/**
* @brief GPIO port E identifier.
*/
#if !defined(STM32F10X_LD) || defined(__DOXYGEN__)
#define IOPORT5 GPIOE
#endif
/**
* @brief GPIO port F identifier.
*/
#if defined(STM32F10X_HD) || defined(__DOXYGEN__)
#define IOPORT6 GPIOF
/**
* @brief GPIO port G identifier.
*/
#define IOPORT7 GPIOG
#endif
/*===========================================================================*/
/* Implementation, some of the following macros could be implemented as */
/* functions, please put them in a file named ioports_lld.c if so. */
/*===========================================================================*/
/**
* @brief GPIO ports subsystem initialization.
*/
#define pal_lld_init(config) _pal_lld_init(config)
/**
* @brief Reads an I/O port.
* @details This function is implemented by reading the GPIO IDR register, the
* implementation has no side effects.
* @note This function is not meant to be invoked directly by the application
* code.
*
* @param[in] port the port identifier
* @return The port bits.
*/
#define pal_lld_readport(port) ((port)->IDR)
/**
* @brief Reads the output latch.
* @details This function is implemented by reading the GPIO ODR register, the
* implementation has no side effects.
* @note This function is not meant to be invoked directly by the application
* code.
*
* @param[in] port the port identifier
* @return The latched logical states.
*/
#define pal_lld_readlatch(port) ((port)->ODR)
/**
* @brief Writes on a I/O port.
* @details This function is implemented by writing the GPIO ODR register, the
* implementation has no side effects.
* @note This function is not meant to be invoked directly by the
* application code.
* @note Writing on pads programmed as pull-up or pull-down has the side
* effect to modify the resistor setting because the output latched
* data is used for the resistor selection.
*
* @param[in] port the port identifier
* @param[in] bits the bits to be written on the specified port
*/
#define pal_lld_writeport(port, bits) ((port)->ODR = (bits))
/**
* @brief Sets a bits mask on a I/O port.
* @details This function is implemented by writing the GPIO BSRR register, the
* implementation has no side effects.
* @note This function is not meant to be invoked directly by the
* application code.
* @note Writing on pads programmed as pull-up or pull-down has the side
* effect to modify the resistor setting because the output latched
* data is used for the resistor selection.
*
* @param[in] port the port identifier
* @param[in] bits the bits to be ORed on the specified port
*/
#define pal_lld_setport(port, bits) ((port)->BSRR = (bits))
/**
* @brief Clears a bits mask on a I/O port.
* @details This function is implemented by writing the GPIO BRR register, the
* implementation has no side effects.
* @note This function is not meant to be invoked directly by the
* application code.
* @note Writing on pads programmed as pull-up or pull-down has the side
* effect to modify the resistor setting because the output latched
* data is used for the resistor selection.
*
* @param[in] port the port identifier
* @param[in] bits the bits to be cleared on the specified port
*/
#define pal_lld_clearport(port, bits) ((port)->BRR = (bits))
/**
* @brief Writes a group of bits.
* @details This function is implemented by writing the GPIO BSRR register, the
* implementation has no side effects.
* @note This function is not meant to be invoked directly by the
* application code.
* @note Writing on pads programmed as pull-up or pull-down has the side
* effect to modify the resistor setting because the output latched
* data is used for the resistor selection.
*
* @param[in] port the port identifier
* @param[in] mask the group mask
* @param[in] offset the group bit offset within the port
* @param[in] bits the bits to be written. Values exceeding the group
* width are masked.
*/
#define pal_lld_writegroup(port, mask, offset, bits) { \
(port)->BSRR = ((~(bits) & (mask)) << (16 + (offset))) | \
(((bits) & (mask)) << (offset)); \
}
/**
* @brief Pads group mode setup.
* @details This function programs a pads group belonging to the same port
* with the specified mode.
* @note This function is not meant to be invoked directly by the
* application code.
* @note Writing on pads programmed as pull-up or pull-down has the side
* effect to modify the resistor setting because the output latched
* data is used for the resistor selection.
*
* @param[in] port the port identifier
* @param[in] mask the group mask
* @param[in] mode the mode
*/
#define pal_lld_setgroupmode(port, mask, mode) \
_pal_lld_setgroupmode(port, mask, mode)
/**
* @brief Writes a logical state on an output pad.
* @note This function is not meant to be invoked directly by the
* application code.
* @note Writing on pads programmed as pull-up or pull-down has the side
* effect to modify the resistor setting because the output latched
* data is used for the resistor selection.
*
* @param[in] port the port identifier
* @param[in] pad the pad number within the port
* @param[in] bit logical value, the value must be @p PAL_LOW or
* @p PAL_HIGH
*/
#define pal_lld_writepad(port, pad, bit) pal_lld_writegroup(port, 1, pad, bit)
extern const PALConfig pal_default_config;
#ifdef __cplusplus
extern "C" {
#endif
void _pal_lld_init(const PALConfig *config);
void _pal_lld_setgroupmode(ioportid_t port,
ioportmask_t mask,
uint_fast8_t mode);
#ifdef __cplusplus
}
#endif
#endif /* CH_HAL_USE_PAL */
#endif /* _PAL_LLD_H_ */
/** @} */

View File

@@ -0,0 +1,150 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @defgroup STM32 STM32 Support
* @brief STM32 specific support.
* @details The STM32 support includes:
* - I/O ports driver.
* - Buffered, interrupt driven, serial driver.
* - Interrupt driver CAN driver.
* - DMA capable, high performance, ADC driver.
* - DMA capable, high performance, SPI driver.
* - PWM driver.
* - A demo supporting the kernel test suite.
* - A demo that demonstrate the FatFs use with the MMC driver.
* .
* @ingroup ARMCMx
*/
/**
* @defgroup STM32_HAL STM32 HAL Support
* @brief HAL support.
*
* @ingroup STM32
*/
/**
* @defgroup STM32F103_HAL STM32F103 HAL Support
* @brief HAL support for STM32 LD, MD and HD families.
*
* @ingroup STM32_HAL
*/
/**
* @defgroup STM32F10X_CL_HAL STM32F105/F107 HAL Support
* @brief HAL support for STM32 CL (Connectivity Line) family.
*
* @ingroup STM32_HAL
*/
/**
* @defgroup STM32_PAL STM32 I/O Ports Support
* @brief I/O Ports peripherals support.
* @details This module supports the STM3 GPIO controller. The controller
* supports the following features (see @ref PAL):
* - 16 bits wide ports.
* - Atomic set/reset functions.
* - Atomic set+reset function (atomic bus operations).
* - Output latched regardless of the pad setting.
* - Direct read of input pads regardless of the pad setting.
* .
* <h2>Supported Setup Modes</h2>
* - @p PAL_MODE_RESET.
* - @p PAL_MODE_UNCONNECTED.
* - @p PAL_MODE_INPUT.
* - @p PAL_MODE_INPUT_PULLUP.
* - @p PAL_MODE_INPUT_PULLDOWN.
* - @p PAL_MODE_INPUT_ANALOG.
* - @p PAL_MODE_OUTPUT_PUSHPULL.
* - @p PAL_MODE_OUTPUT_OPENDRAIN.
* .
* Any attempt to setup an invalid mode is ignored.
*
* <h2>Suboptimal Behavior</h2>
* Some GPIO features are less than optimal:
* - Pad/port toggling operations are not atomic.
* - Pad/group mode setup is not atomic.
* - Writing on pads/groups/ports programmed as input with pull-up/down
* resistor can change the resistor setting because the output latch is
* used for resistor selection.
* .
* @ingroup STM32
*/
/**
* @defgroup STM32_SERIAL STM32 USART Support
* @brief USART peripherals support.
* @details The serial driver supports the STM32 USARTs in asynchronous
* mode.
*
* @ingroup STM32
*/
/**
* @defgroup STM32_DMA STM32 DMA Support
* @brief DMA support.
* @details The DMA helper driver allows to stop the DMA clock when no other
* driver requires its services.
*
* @ingroup STM32
*/
/**
* @defgroup STM32_ADC STM32 ADC Support
* @brief ADC peripherals support.
* @details The ADC driver supports the STM32 ADCs using DMA channels for
* improved performance.
*
* @ingroup STM32
*/
/**
* @defgroup STM32_CAN STM32 CAN Support
* @brief CAN peripheral support.
* @details The CAN driver supports the STM32 bxCAN unit.
*
* @ingroup STM32
*/
/**
* @defgroup STM32_PWM STM32 PWM Support
* @brief TIMx peripherals as PWM generators support.
* @details The PWM driver supports the STM32 TIMx units as PWM generators.
*
* @ingroup STM32
*/
/**
* @defgroup STM32_SPI STM32 SPI Support
* @brief SPI peripherals support.
* @details The SPI driver supports the STM32 SPIs using DMA channels for
* improved performance.
*
* @ingroup STM32
*/

View File

@@ -0,0 +1,12 @@
# List of all the STM32 platform files.
PLATFORMSRC = ${CHIBIOS}/os/hal/platforms/STM32/hal_lld.c \
${CHIBIOS}/os/hal/platforms/STM32/adc_lld.c \
${CHIBIOS}/os/hal/platforms/STM32/can_lld.c \
${CHIBIOS}/os/hal/platforms/STM32/pal_lld.c \
${CHIBIOS}/os/hal/platforms/STM32/pwm_lld.c \
${CHIBIOS}/os/hal/platforms/STM32/serial_lld.c \
${CHIBIOS}/os/hal/platforms/STM32/spi_lld.c \
${CHIBIOS}/os/hal/platforms/STM32/stm32_dma.c
# Required include directories
PLATFORMINC = ${CHIBIOS}/os/hal/platforms/STM32

View File

@@ -0,0 +1,455 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/pwm_lld.c
* @brief STM32 PWM subsystem low level driver header.
*
* @addtogroup STM32_PWM
* @{
*/
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_PWM || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/**
* @brief PWM1 driver identifier.
* @note The driver PWM1 allocates the complex timer TIM1 when enabled.
*/
#if defined(USE_STM32_PWM1) || defined(__DOXYGEN__)
PWMDriver PWMD1;
#endif
/**
* @brief PWM2 driver identifier.
* @note The driver PWM2 allocates the timer TIM2 when enabled.
*/
#if defined(USE_STM32_PWM2) || defined(__DOXYGEN__)
PWMDriver PWMD2;
#endif
/**
* @brief PWM3 driver identifier.
* @note The driver PWM3 allocates the timer TIM3 when enabled.
*/
#if defined(USE_STM32_PWM3) || defined(__DOXYGEN__)
PWMDriver PWMD3;
#endif
/**
* @brief PWM4 driver identifier.
* @note The driver PWM4 allocates the timer TIM4 when enabled.
*/
#if defined(USE_STM32_PWM4) || defined(__DOXYGEN__)
PWMDriver PWMD4;
#endif
/*===========================================================================*/
/* Driver local variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
#if USE_STM32_PWM2 || USE_STM32_PWM3 || USE_STM32_PWM4 || defined(__DOXYGEN__)
/**
* @brief Common TIM2...TIM4 IRQ handler.
* @note It is assumed that the various sources are only activated if the
* associated callback pointer is not equal to @p NULL in order to not
* perform an extra check in a potentially critical interrupt handler.
*/
static void serve_interrupt(PWMDriver *pwmp) {
uint16_t sr;
sr = pwmp->pd_tim->SR & pwmp->pd_tim->DIER;
pwmp->pd_tim->SR = ~(TIM_SR_CC1IF | TIM_SR_CC2IF | TIM_SR_CC3IF |
TIM_SR_CC4IF | TIM_SR_UIF);
if ((sr & TIM_SR_CC1IF) != 0)
pwmp->pd_config->pc_channels[0].pcc_callback(pwmp);
if ((sr & TIM_SR_CC2IF) != 0)
pwmp->pd_config->pc_channels[1].pcc_callback(pwmp);
if ((sr & TIM_SR_CC3IF) != 0)
pwmp->pd_config->pc_channels[2].pcc_callback(pwmp);
if ((sr & TIM_SR_CC4IF) != 0)
pwmp->pd_config->pc_channels[3].pcc_callback(pwmp);
if ((sr & TIM_SR_UIF) != 0)
pwmp->pd_config->pc_callback(pwmp);
}
#endif /* USE_STM32_PWM2 || USE_STM32_PWM3 || USE_STM32_PWM4 */
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
#if USE_STM32_PWM1
/**
* @brief TIM1 update interrupt handler.
* @note It is assumed that this interrupt is only activated if the callback
* pointer is not equal to @p NULL in order to not perform an extra
* check in a potentially critical interrupt handler.
*/
CH_IRQ_HANDLER(VectorA4) {
CH_IRQ_PROLOGUE();
TIM1->SR = ~TIM_SR_UIF;
PWMD1.pd_config->pc_callback(&PWMD1);
CH_IRQ_EPILOGUE();
}
/**
* @brief TIM1 compare interrupt handler.
* @note It is assumed that the various sources are only activated if the
* associated callback pointer is not equal to @p NULL in order to not
* perform an extra check in a potentially critical interrupt handler.
*/
CH_IRQ_HANDLER(VectorAC) {
uint16_t sr;
CH_IRQ_PROLOGUE();
sr = TIM1->SR & TIM1->DIER;
TIM1->SR = ~(TIM_SR_CC1IF | TIM_SR_CC2IF | TIM_SR_CC3IF | TIM_SR_CC4IF);
if ((sr & TIM_SR_CC1IF) != 0)
PWMD1.pd_config->pc_channels[0].pcc_callback(&PWMD1);
if ((sr & TIM_SR_CC2IF) != 0)
PWMD1.pd_config->pc_channels[1].pcc_callback(&PWMD1);
if ((sr & TIM_SR_CC3IF) != 0)
PWMD1.pd_config->pc_channels[2].pcc_callback(&PWMD1);
if ((sr & TIM_SR_CC4IF) != 0)
PWMD1.pd_config->pc_channels[3].pcc_callback(&PWMD1);
CH_IRQ_EPILOGUE();
}
#endif /* USE_STM32_PWM1 */
#if USE_STM32_PWM2
/**
* @brief TIM2 interrupt handler.
*/
CH_IRQ_HANDLER(VectorB0) {
CH_IRQ_PROLOGUE();
serve_interrupt(&PWMD2);
CH_IRQ_EPILOGUE();
}
#endif /* USE_STM32_PWM2 */
#if USE_STM32_PWM3
/**
* @brief TIM3 interrupt handler.
*/
CH_IRQ_HANDLER(VectorB4) {
CH_IRQ_PROLOGUE();
serve_interrupt(&PWMD3);
CH_IRQ_EPILOGUE();
}
#endif /* USE_STM32_PWM3 */
#if USE_STM32_PWM4
/**
* @brief TIM4 interrupt handler.
*/
CH_IRQ_HANDLER(VectorB8) {
CH_IRQ_PROLOGUE();
serve_interrupt(&PWMD4);
CH_IRQ_EPILOGUE();
}
#endif /* USE_STM32_PWM4 */
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level PWM driver initialization.
*/
void pwm_lld_init(void) {
#if USE_STM32_PWM1
/* TIM1 reset, ensures reset state in order to avoid trouble with JTAGs.*/
RCC->APB2RSTR = RCC_APB2RSTR_TIM1RST;
RCC->APB2RSTR = 0;
/* Driver initialization.*/
pwmObjectInit(&PWMD1);
PWMD1.pd_enabled_channels = 0;
PWMD1.pd_tim = TIM1;
#endif
#if USE_STM32_PWM2
/* TIM2 reset, ensures reset state in order to avoid trouble with JTAGs.*/
RCC->APB1RSTR = RCC_APB1RSTR_TIM2RST;
RCC->APB1RSTR = 0;
/* Driver initialization.*/
pwmObjectInit(&PWMD2);
PWMD2.pd_enabled_channels = 0;
PWMD2.pd_tim = TIM2;
#endif
#if USE_STM32_PWM3
/* TIM2 reset, ensures reset state in order to avoid trouble with JTAGs.*/
RCC->APB1RSTR = RCC_APB1RSTR_TIM3RST;
RCC->APB1RSTR = 0;
/* Driver initialization.*/
pwmObjectInit(&PWMD3);
PWMD3.pd_enabled_channels = 0;
PWMD3.pd_tim = TIM3;
#endif
#if USE_STM32_PWM4
/* TIM2 reset, ensures reset state in order to avoid trouble with JTAGs.*/
RCC->APB1RSTR = RCC_APB1RSTR_TIM4RST;
RCC->APB1RSTR = 0;
/* Driver initialization.*/
pwmObjectInit(&PWMD4);
PWMD4.pd_enabled_channels = 0;
PWMD4.pd_tim = TIM4;
#endif
}
/**
* @brief Configures and activates the PWM peripheral.
*
* @param[in] pwmp pointer to a @p PWMDriver object
*/
void pwm_lld_start(PWMDriver *pwmp) {
uint16_t ccer;
/* Reset channels.*/
pwmp->pd_enabled_channels = 0; /* All channels disabled. */
if (pwmp->pd_state == PWM_STOP) {
/* Clock activation and timer reset.*/
#if USE_STM32_PWM1
if (&PWMD1 == pwmp) {
RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;
RCC->APB2RSTR = RCC_APB2RSTR_TIM1RST;
RCC->APB2RSTR = 0;
NVICEnableVector(TIM1_UP_IRQn,
CORTEX_PRIORITY_MASK(STM32_PWM1_IRQ_PRIORITY));
NVICEnableVector(TIM1_CC_IRQn,
CORTEX_PRIORITY_MASK(STM32_PWM1_IRQ_PRIORITY));
}
#endif
#if USE_STM32_PWM2
if (&PWMD2 == pwmp) {
RCC->APB1ENR |= RCC_APB1ENR_TIM2EN;
RCC->APB1RSTR = RCC_APB1RSTR_TIM2RST;
RCC->APB1RSTR = 0;
NVICEnableVector(TIM2_IRQn,
CORTEX_PRIORITY_MASK(STM32_PWM2_IRQ_PRIORITY));
}
#endif
#if USE_STM32_PWM3
if (&PWMD3 == pwmp) {
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
RCC->APB1RSTR = RCC_APB1RSTR_TIM3RST;
RCC->APB1RSTR = 0;
NVICEnableVector(TIM3_IRQn,
CORTEX_PRIORITY_MASK(STM32_PWM3_IRQ_PRIORITY));
}
#endif
#if USE_STM32_PWM4
if (&PWMD4 == pwmp) {
RCC->APB1ENR |= RCC_APB1ENR_TIM4EN;
RCC->APB1RSTR = RCC_APB1RSTR_TIM4RST;
RCC->APB1RSTR = 0;
NVICEnableVector(TIM4_IRQn,
CORTEX_PRIORITY_MASK(STM32_PWM4_IRQ_PRIORITY));
}
#endif
}
else {
/* Driver re-configuration scenario, it must be stopped first.*/
/* Really required ?????????? */
pwmp->pd_tim->CR1 = 0; /* Timer stopped. */
pwmp->pd_tim->CR2 = 0; /* Timer stopped. */
pwmp->pd_tim->SMCR = 0; /* Slave mode disabled. */
pwmp->pd_tim->CCR1 = 0; /* Comparator 1 disabled. */
pwmp->pd_tim->CCR2 = 0; /* Comparator 2 disabled. */
pwmp->pd_tim->CCR3 = 0; /* Comparator 3 disabled. */
pwmp->pd_tim->CCR4 = 0; /* Comparator 4 disabled. */
pwmp->pd_tim->CNT = 0;
}
/* Timer configuration.*/
pwmp->pd_tim->CR2 = pwmp->pd_config->pc_cr2;
pwmp->pd_tim->PSC = pwmp->pd_config->pc_psc;
pwmp->pd_tim->ARR = pwmp->pd_config->pc_arr;
/* Output enables and polarities setup.*/
ccer = 0;
switch (pwmp->pd_config->pc_channels[0].pcc_mode) {
case PWM_OUTPUT_ACTIVE_LOW:
ccer |= TIM_CCER_CC1P;
case PWM_OUTPUT_ACTIVE_HIGH:
ccer |= TIM_CCER_CC1E;
default:
;
}
switch (pwmp->pd_config->pc_channels[1].pcc_mode) {
case PWM_OUTPUT_ACTIVE_LOW:
ccer |= TIM_CCER_CC2P;
case PWM_OUTPUT_ACTIVE_HIGH:
ccer |= TIM_CCER_CC2E;
default:
;
}
switch (pwmp->pd_config->pc_channels[2].pcc_mode) {
case PWM_OUTPUT_ACTIVE_LOW:
ccer |= TIM_CCER_CC3P;
case PWM_OUTPUT_ACTIVE_HIGH:
ccer |= TIM_CCER_CC3E;
default:
;
}
switch (pwmp->pd_config->pc_channels[3].pcc_mode) {
case PWM_OUTPUT_ACTIVE_LOW:
ccer |= TIM_CCER_CC4P;
case PWM_OUTPUT_ACTIVE_HIGH:
ccer |= TIM_CCER_CC4E;
default:
;
}
pwmp->pd_tim->CCER = ccer;
pwmp->pd_tim->EGR = TIM_EGR_UG; /* Update event. */
pwmp->pd_tim->SR = 0; /* Clear pending IRQs. */
pwmp->pd_tim->DIER = pwmp->pd_config->pc_callback == NULL ? 0 : TIM_DIER_UIE;
pwmp->pd_tim->BDTR = TIM_BDTR_MOE;
/* Timer configured and started.*/
pwmp->pd_tim->CR1 = TIM_CR1_ARPE | TIM_CR1_URS | TIM_CR1_CEN;
}
/**
* @brief Deactivates the PWM peripheral.
*
* @param[in] pwmp pointer to a @p PWMDriver object
*/
void pwm_lld_stop(PWMDriver *pwmp) {
/* If in ready state then disables the PWM clock.*/
if (pwmp->pd_state == PWM_READY) {
pwmp->pd_enabled_channels = 0; /* All channels disabled. */
pwmp->pd_tim->CR1 = 0;
pwmp->pd_tim->CR2 = 0;
pwmp->pd_tim->CCER = 0; /* Outputs disabled. */
pwmp->pd_tim->CCR1 = 0; /* Comparator 1 disabled. */
pwmp->pd_tim->CCR2 = 0; /* Comparator 2 disabled. */
pwmp->pd_tim->CCR3 = 0; /* Comparator 3 disabled. */
pwmp->pd_tim->CCR4 = 0; /* Comparator 4 disabled. */
pwmp->pd_tim->BDTR = 0;
pwmp->pd_tim->DIER = 0;
pwmp->pd_tim->SR = 0;
pwmp->pd_tim->EGR = TIM_EGR_UG; /* Update event. */
#if USE_STM32_PWM1
if (&PWMD1 == pwmp) {
NVICDisableVector(TIM1_UP_IRQn);
NVICDisableVector(TIM1_CC_IRQn);
RCC->APB2ENR &= ~RCC_APB2ENR_TIM1EN;
}
#endif
#if USE_STM32_PWM2
if (&PWMD2 == pwmp) {
NVICDisableVector(TIM2_IRQn);
RCC->APB1ENR &= ~RCC_APB1ENR_TIM2EN;
}
#endif
#if USE_STM32_PWM3
if (&PWMD3 == pwmp) {
NVICDisableVector(TIM3_IRQn);
RCC->APB1ENR &= ~RCC_APB1ENR_TIM3EN;
}
#endif
#if USE_STM32_PWM4
if (&PWMD4 == pwmp) {
NVICDisableVector(TIM4_IRQn);
RCC->APB1ENR &= ~RCC_APB1ENR_TIM4EN;
}
#endif
}
}
/**
* @brief Enables a PWM channel.
*
* @param[in] pwmp pointer to a @p PWMDriver object
* @param[in] channel PWM channel identifier (0...PWM_CHANNELS-1)
* @param[in] width PWM pulse width as clock pulses number
*/
void pwm_lld_enable_channel(PWMDriver *pwmp,
pwmchannel_t channel,
pwmcnt_t width) {
*(&pwmp->pd_tim->CCR1 + (channel * 2)) = width; /* New duty cycle. */
if ((pwmp->pd_enabled_channels & (1 << channel)) == 0) {
/* The channel is not enabled yet.*/
pwmp->pd_enabled_channels |= (1 << channel);
/* If there is a callback associated to the channel then the proper
interrupt is cleared and enabled.*/
if (pwmp->pd_config->pc_channels[channel].pcc_callback) {
pwmp->pd_tim->SR = ~(2 << channel);
pwmp->pd_tim->DIER |= (2 << channel);
}
}
}
/**
* @brief Disables a PWM channel.
* @details The channel is disabled and its output line returned to the
* idle state.
*
* @param[in] pwmp pointer to a @p PWMDriver object
* @param[in] channel PWM channel identifier (0...PWM_CHANNELS-1)
*/
void pwm_lld_disable_channel(PWMDriver *pwmp, pwmchannel_t channel) {
*(&pwmp->pd_tim->CCR1 + (channel * 2)) = 0;
pwmp->pd_tim->DIER &= ~(2 << channel);
pwmp->pd_enabled_channels &= ~(1 << channel);
}
#endif /* CH_HAL_USE_PWM */
/** @} */

View File

@@ -0,0 +1,347 @@
/*
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/>.
*/
/**
* @file STM32/pwm_lld.h
* @brief STM32 PWM subsystem low level driver header.
*
* @addtogroup PWM
* @{
*/
#ifndef _PWM_LLD_H_
#define _PWM_LLD_H_
#if CH_HAL_USE_PWM || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
/**
* @brief Number of PWM channels per PWM driver.
*/
#define PWM_CHANNELS 4
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @brief PWM1 driver enable switch.
* @details If set to @p TRUE the support for PWM1 is included.
* @note The default is @p TRUE.
*/
#if !defined(USE_STM32_PWM1) || defined(__DOXYGEN__)
#define USE_STM32_PWM1 TRUE
#endif
/**
* @brief PWM2 driver enable switch.
* @details If set to @p TRUE the support for PWM2 is included.
* @note The default is @p TRUE.
*/
#if !defined(USE_STM32_PWM2) || defined(__DOXYGEN__)
#define USE_STM32_PWM2 TRUE
#endif
/**
* @brief PWM3 driver enable switch.
* @details If set to @p TRUE the support for PWM3 is included.
* @note The default is @p TRUE.
*/
#if !defined(USE_STM32_PWM3) || defined(__DOXYGEN__)
#define USE_STM32_PWM3 TRUE
#endif
/**
* @brief PWM4 driver enable switch.
* @details If set to @p TRUE the support for PWM4 is included.
* @note The default is @p TRUE.
*/
#if !defined(USE_STM32_PWM4) || defined(__DOXYGEN__)
#define USE_STM32_PWM4 TRUE
#endif
/**
* @brief PWM1 interrupt priority level setting.
*/
#if !defined(STM32_PWM1_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_PWM1_IRQ_PRIORITY 7
#endif
/**
* @brief PWM2 interrupt priority level setting.
*/
#if !defined(STM32_PWM2_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_PWM2_IRQ_PRIORITY 7
#endif
/**
* @brief PWM3 interrupt priority level setting.
*/
#if !defined(STM32_PWM3_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_PWM3_IRQ_PRIORITY 7
#endif
/**
* @brief PWM4 interrupt priority level setting.
*/
#if !defined(STM32_PWM4_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_PWM4_IRQ_PRIORITY 7
#endif
/*===========================================================================*/
/* Configuration checks. */
/*===========================================================================*/
#if USE_STM32_PWM4 && defined(STM32F10X_LD)
#error "TIM4 not present in low density STM32 devices"
#endif
#if !USE_STM32_PWM1 && !USE_STM32_PWM2 && \
!USE_STM32_PWM3 && !USE_STM32_PWM4
#error "PWM driver activated but no TIM peripheral assigned"
#endif
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
/**
* @brief PWM channel type.
*/
typedef uint8_t pwmchannel_t;
/**
* @brief PWM counter type.
*/
typedef uint16_t pwmcnt_t;
/**
* @brief Type of a structure representing an PWM driver.
*/
typedef struct PWMDriver PWMDriver;
/**
* @brief PWM notification callback type.
*
* @param[in] pwmp pointer to a @p PWMDriver object
*/
typedef void (*pwmcallback_t)(PWMDriver *pwmp);
/**
* @brief PWM driver channel configuration structure.
*/
typedef struct {
/**
* @brief Channel active logic level.
*/
pwmmode_t pcc_mode;
/**
* @brief Channel callback pointer.
* @note This callback is invoked on the channel compare event. If set to
* @p NULL then the callback is disabled.
*/
pwmcallback_t pcc_callback;
/* End of the mandatory fields.*/
} PWMChannelConfig;
/**
* @brief PWM driver configuration structure.
*/
typedef struct {
/**
* @brief Periodic callback pointer.
* @note This callback is invoked on PWM counter reset. If set to
* @p NULL then the callback is disabled.
*/
pwmcallback_t pc_callback;
/**
* @brief Channels configurations.
*/
PWMChannelConfig pc_channels[PWM_CHANNELS];
/* End of the mandatory fields.*/
/**
* @brief TIM PSC (pre-scaler) register initialization data.
*/
uint16_t pc_psc;
/**
* @brief TIM ARR (auto-reload) register initialization data.
*/
uint16_t pc_arr;
/**
* @brief TIM CR2 register initialization data.
* @note The value of this field should normally be equal to zero.
*/
uint16_t pc_cr2;
} PWMConfig;
/**
* @brief Structure representing a PWM driver.
*/
struct PWMDriver {
/**
* @brief Driver state.
*/
pwmstate_t pd_state;
/**
* @brief Current driver configuration data.
*/
const PWMConfig *pd_config;
#if defined(PWM_DRIVER_EXT_FIELDS)
PWM_DRIVER_EXT_FIELDS
#endif
/* End of the mandatory fields.*/
/**
* @brief Bit mask of the enabled channels.
*/
uint32_t pd_enabled_channels;
/**
* @brief Pointer to the TIMx registers block.
*/
TIM_TypeDef *pd_tim;
};
/*===========================================================================*/
/* Driver macros. */
/*===========================================================================*/
/**
* @brief PWM clock prescaler initialization utility.
* @note The real clock value is rounded to the lower valid value, please
* make sure that the source clock frequency is a multiple of the
* requested PWM clock frequency.
* @note The calculated value must fit into an unsigned 16 bits integer.
*
* @param[in] clksrc clock source frequency, depending on the target timer
* cell it can be one of:
* - STM32_TIMCLK1
* - STM32_TIMCLK2
* .
* Please refer to the STM32 HAL driver documentation
* and/or the STM32 Reference Manual for the right clock
* source.
* @param[in] pwmclk PWM clock frequency in cycles
* @return The value to be stored in the @p pc_psc field of the
* @p PWMConfig structure.
*/
#define PWM_COMPUTE_PSC(clksrc, pwmclk) \
((uint16_t)(((clksrc) / (pwmclk)) - 1))
/**
* @brief PWM cycle period initialization utility.
* @note The calculated value must fit into an unsigned 16 bits integer.
*
* @param[in] pwmclk PWM clock frequency in cycles
* @param[in] pwmperiod PWM cycle period in nanoseconds
* @return The value to be stored in the @p pc_arr field of the
* @p PWMConfig structure.
*/
#define PWM_COMPUTE_ARR(pwmclk, pwmperiod) \
((uint16_t)(((pwmclk) / (1000000000 / (pwmperiod))) - 1))
/**
* @brief Converts from fraction to pulse width.
* @note Be careful with rounding errors, this is integer math not magic.
* You can specify tenths of thousandth but make sure you have the
* proper hardware resolution by carefully choosing the clock source
* and prescaler settings, see @p PWM_COMPUTE_PSC.
*
* @param[in] numerator numerator of the fraction
* @param[in] denominator percentage as an integer between 0 and numerator
* @return The pulse width to be passed to @p pwmEnableChannel().
*
* @api
*/
#define PWM_FRACTION_TO_WIDTH(pwmp, numerator, denominator) \
((uint16_t)((((uint32_t)(pwmp)->pd_config->pc_arr + 1UL) * \
(uint32_t)(denominator)) / (uint32_t)(numerator)))
/**
* @brief Converts from degrees to pulse width.
* @note Be careful with rounding errors, this is integer math not magic.
* You can specify hundredths of degrees but make sure you have the
* proper hardware resolution by carefully choosing the clock source
* and prescaler settings, see @p PWM_COMPUTE_PSC.
*
* @param[in] pwmp pointer to a @p PWMDriver object
* @param[in] degrees degrees as an integer between 0 and 36000
* @return The pulse width to be passed to @p pwmEnableChannel().
*
* @api
*/
#define PWM_DEGREES_TO_WIDTH(pwmp, degrees) \
PWM_FRACTION_TO_WIDTH(pwmp, 36000, degrees)
/**
* @brief Converts from percentage to pulse width.
* @note Be careful with rounding errors, this is integer math not magic.
* You can specify tenths of thousandth but make sure you have the
* proper hardware resolution by carefully choosing the clock source
* and prescaler settings, see @p PWM_COMPUTE_PSC.
*
* @param[in] pwmp pointer to a @p PWMDriver object
* @param[in] percentage percentage as an integer between 0 and 10000
* @return The pulse width to be passed to @p pwmEnableChannel().
*
* @api
*/
#define PWM_PERCENTAGE_TO_WIDTH(pwmp, percentage) \
PWM_FRACTION_TO_WIDTH(pwmp, 10000, percentage)
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#if defined(USE_STM32_PWM1) && !defined(__DOXYGEN__)
extern PWMDriver PWMD1;
#endif
#if defined(USE_STM32_PWM2) && !defined(__DOXYGEN__)
extern PWMDriver PWMD2;
#endif
#if defined(USE_STM32_PWM3) && !defined(__DOXYGEN__)
extern PWMDriver PWMD3;
#endif
#if defined(USE_STM32_PWM4) && !defined(__DOXYGEN__)
extern PWMDriver PWMD4;
#endif
#ifdef __cplusplus
extern "C" {
#endif
void pwm_lld_init(void);
void pwm_lld_start(PWMDriver *pwmp);
void pwm_lld_stop(PWMDriver *pwmp);
void pwm_lld_enable_channel(PWMDriver *pwmp,
pwmchannel_t channel,
pwmcnt_t width);
void pwm_lld_disable_channel(PWMDriver *pwmp, pwmchannel_t channel);
#ifdef __cplusplus
}
#endif
#endif /* CH_HAL_USE_PWM */
#endif /* _PWM_LLD_H_ */
/** @} */

View File

@@ -0,0 +1,433 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/serial_lld.c
* @brief STM32 low level serial driver code.
*
* @addtogroup STM32_SERIAL
* @{
*/
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_SERIAL || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/** @brief USART1 serial driver identifier.*/
#if USE_STM32_USART1 || defined(__DOXYGEN__)
SerialDriver SD1;
#endif
/** @brief USART2 serial driver identifier.*/
#if USE_STM32_USART2 || defined(__DOXYGEN__)
SerialDriver SD2;
#endif
/** @brief USART3 serial driver identifier.*/
#if USE_STM32_USART3 || defined(__DOXYGEN__)
SerialDriver SD3;
#endif
#if defined(STM32F10X_HD) || defined(STM32F10X_CL) || defined(__DOXYGEN__)
/** @brief UART4 serial driver identifier.*/
#if USE_STM32_UART4 || defined(__DOXYGEN__)
SerialDriver SD4;
#endif
/** @brief UART5 serial driver identifier.*/
#if USE_STM32_UART5 || defined(__DOXYGEN__)
SerialDriver SD5;
#endif
#endif
/*===========================================================================*/
/* Driver local variables. */
/*===========================================================================*/
/** @brief Driver default configuration.*/
static const SerialConfig default_config =
{
SERIAL_DEFAULT_BITRATE,
0,
USART_CR2_STOP1_BITS | USART_CR2_LINEN,
0
};
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
/**
* @brief USART 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 usart_init(SerialDriver *sdp, const SerialConfig *config) {
USART_TypeDef *u = sdp->usart;
/*
* Baud rate setting.
*/
if (sdp->usart == USART1)
u->BRR = STM32_PCLK2 / config->sc_speed;
else
u->BRR = STM32_PCLK1 / config->sc_speed;
/*
* Note that some bits are enforced.
*/
u->CR1 = config->sc_cr1 | USART_CR1_UE | USART_CR1_PEIE |
USART_CR1_RXNEIE | USART_CR1_TE |
USART_CR1_RE;
u->CR2 = config->sc_cr2 | USART_CR2_LBDIE;
u->CR3 = config->sc_cr3 | USART_CR3_EIE;
(void)u->SR; /* SR reset step 1.*/
(void)u->DR; /* SR reset step 2.*/
}
/**
* @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] sdp pointer to a @p SerialDriver object
* @param[in] sr USART SR register value
*/
static void set_error(SerialDriver *sdp, uint16_t sr) {
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_NE)
sts |= SD_NOISE_ERROR;
if (sr & USART_SR_LBD)
sts |= SD_BREAK_DETECTED;
chSysLockFromIsr();
sdAddFlagsI(sdp, sts);
chSysUnlockFromIsr();
}
/**
* @brief Common IRQ handler.
*
* @param[in] sdp communication channel associated to the USART
*/
static void serve_interrupt(SerialDriver *sdp) {
USART_TypeDef *u = sdp->usart;
uint16_t cr1 = u->CR1;
uint16_t sr = u->SR; /* SR reset step 1.*/
uint16_t dr = u->DR; /* SR reset step 2.*/
if (sr & (USART_SR_LBD | USART_SR_ORE | USART_SR_NE |
USART_SR_FE | USART_SR_PE)) {
set_error(sdp, sr);
u->SR = 0; /* Clears the LBD bit in the SR.*/
}
if (sr & USART_SR_RXNE) {
chSysLockFromIsr();
sdIncomingDataI(sdp, (uint8_t)dr);
chSysUnlockFromIsr();
}
if ((cr1 & USART_CR1_TXEIE) && (sr & USART_SR_TXE)) {
msg_t b;
chSysLockFromIsr();
b = chOQGetI(&sdp->oqueue);
if (b < Q_OK) {
chEvtBroadcastI(&sdp->oevent);
u->CR1 = cr1 & ~USART_CR1_TXEIE;
}
else
u->DR = b;
chSysUnlockFromIsr();
}
}
#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
#if defined(STM32F10X_HD) || defined(STM32F10X_CL) || defined(__DOXYGEN__)
#if USE_STM32_UART4 || defined(__DOXYGEN__)
static void notify4(void) {
UART4->CR1 |= USART_CR1_TXEIE;
}
#endif
#if USE_STM32_UART5 || defined(__DOXYGEN__)
static void notify5(void) {
UART5->CR1 |= USART_CR1_TXEIE;
}
#endif
#endif
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
#if USE_STM32_USART1 || defined(__DOXYGEN__)
CH_IRQ_HANDLER(VectorD4) {
CH_IRQ_PROLOGUE();
serve_interrupt(&SD1);
CH_IRQ_EPILOGUE();
}
#endif
#if USE_STM32_USART2 || defined(__DOXYGEN__)
CH_IRQ_HANDLER(VectorD8) {
CH_IRQ_PROLOGUE();
serve_interrupt(&SD2);
CH_IRQ_EPILOGUE();
}
#endif
#if USE_STM32_USART3 || defined(__DOXYGEN__)
CH_IRQ_HANDLER(VectorDC) {
CH_IRQ_PROLOGUE();
serve_interrupt(&SD3);
CH_IRQ_EPILOGUE();
}
#endif
#if defined(STM32F10X_HD) || defined(STM32F10X_CL) || defined(__DOXYGEN__)
#if USE_STM32_UART4 || defined(__DOXYGEN__)
CH_IRQ_HANDLER(Vector110) {
CH_IRQ_PROLOGUE();
serve_interrupt(&SD4);
CH_IRQ_EPILOGUE();
}
#endif
#if USE_STM32_UART5 || defined(__DOXYGEN__)
CH_IRQ_HANDLER(Vector114) {
CH_IRQ_PROLOGUE();
serve_interrupt(&SD5);
CH_IRQ_EPILOGUE();
}
#endif
#endif
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level serial driver initialization.
*/
void sd_lld_init(void) {
#if USE_STM32_USART1
sdObjectInit(&SD1, NULL, notify1);
SD1.usart = USART1;
#endif
#if USE_STM32_USART2
sdObjectInit(&SD2, NULL, notify2);
SD2.usart = USART2;
#endif
#if USE_STM32_USART3
sdObjectInit(&SD3, NULL, notify3);
SD3.usart = USART3;
#endif
#if defined(STM32F10X_HD) || defined(STM32F10X_CL)
#if USE_STM32_UART4
sdObjectInit(&SD4, NULL, notify4);
SD4.usart = UART4;
#endif
#if USE_STM32_UART5
sdObjectInit(&SD5, NULL, notify5);
SD5.usart = UART5;
#endif
#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 SerialConfig *config) {
if (config == NULL)
config = &default_config;
if (sdp->state == SD_STOP) {
#if USE_STM32_USART1
if (&SD1 == sdp) {
RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
NVICEnableVector(USART1_IRQn,
CORTEX_PRIORITY_MASK(STM32_USART1_PRIORITY));
}
#endif
#if USE_STM32_USART2
if (&SD2 == sdp) {
RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
NVICEnableVector(USART2_IRQn,
CORTEX_PRIORITY_MASK(STM32_USART2_PRIORITY));
}
#endif
#if USE_STM32_USART3
if (&SD3 == sdp) {
RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
NVICEnableVector(USART3_IRQn,
CORTEX_PRIORITY_MASK(STM32_USART3_PRIORITY));
}
#endif
#if defined(STM32F10X_HD) || defined(STM32F10X_CL)
#if USE_STM32_UART4
if (&SD4 == sdp) {
RCC->APB1ENR |= RCC_APB1ENR_UART4EN;
NVICEnableVector(UART4_IRQn,
CORTEX_PRIORITY_MASK(STM32_UART4_PRIORITY));
}
#endif
#if USE_STM32_UART5
if (&SD5 == sdp) {
RCC->APB1ENR |= RCC_APB1ENR_UART5EN;
NVICEnableVector(UART5_IRQn,
CORTEX_PRIORITY_MASK(STM32_UART5_PRIORITY));
}
#endif
#endif
}
usart_init(sdp, config);
}
/**
* @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 (sdp->state == SD_READY) {
usart_deinit(sdp->usart);
#if USE_STM32_USART1
if (&SD1 == sdp) {
RCC->APB2ENR &= ~RCC_APB2ENR_USART1EN;
NVICDisableVector(USART1_IRQn);
return;
}
#endif
#if USE_STM32_USART2
if (&SD2 == sdp) {
RCC->APB1ENR &= ~RCC_APB1ENR_USART2EN;
NVICDisableVector(USART2_IRQn);
return;
}
#endif
#if USE_STM32_USART3
if (&SD3 == sdp) {
RCC->APB1ENR &= ~RCC_APB1ENR_USART3EN;
NVICDisableVector(USART3_IRQn);
return;
}
#endif
#if defined(STM32F10X_HD) || defined(STM32F10X_CL)
#if USE_STM32_UART4
if (&SD4 == sdp) {
RCC->APB1ENR &= ~RCC_APB1ENR_UART4EN;
NVICDisableVector(UART4_IRQn);
return;
}
#endif
#if USE_STM32_UART5
if (&SD5 == sdp) {
RCC->APB1ENR &= ~RCC_APB1ENR_UART5EN;
NVICDisableVector(UART5_IRQn);
return;
}
#endif
#endif
}
}
#endif /* CH_HAL_USE_SERIAL */
/** @} */

View File

@@ -0,0 +1,244 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/serial_lld.h
* @brief STM32 low level serial driver header.
*
* @addtogroup STM32_SERIAL
* @{
*/
#ifndef _SERIAL_LLD_H_
#define _SERIAL_LLD_H_
#if CH_HAL_USE_SERIAL || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @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 TRUE
#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 TRUE
#endif
#if defined(STM32F10X_HD) || defined(STM32F10X_CL) || defined(__DOXYGEN__)
/**
* @brief UART4 driver enable switch.
* @details If set to @p TRUE the support for UART4 is included.
* @note The default is @p FALSE.
*/
#if !defined(USE_STM32_UART4) || defined(__DOXYGEN__)
#define USE_STM32_UART4 TRUE
#endif
/**
* @brief UART5 driver enable switch.
* @details If set to @p TRUE the support for UART5 is included.
* @note The default is @p FALSE.
*/
#if !defined(USE_STM32_UART5) || defined(__DOXYGEN__)
#define USE_STM32_UART5 TRUE
#endif
#endif
/**
* @brief USART1 interrupt priority level setting.
*/
#if !defined(STM32_USART1_PRIORITY) || defined(__DOXYGEN__)
#define STM32_USART1_PRIORITY 12
#endif
/**
* @brief USART2 interrupt priority level setting.
*/
#if !defined(STM32_USART2_PRIORITY) || defined(__DOXYGEN__)
#define STM32_USART2_PRIORITY 12)
#endif
/**
* @brief USART3 interrupt priority level setting.
*/
#if !defined(STM32_USART3_PRIORITY) || defined(__DOXYGEN__)
#define STM32_USART3_PRIORITY 12
#endif
#if defined(STM32F10X_HD) || defined(STM32F10X_CL) || defined(__DOXYGEN__)
/**
* @brief UART4 interrupt priority level setting.
*/
#if !defined(STM32_UART4_PRIORITY) || defined(__DOXYGEN__)
#define STM32_UART4_PRIORITY 12
#endif
/**
* @brief UART5 interrupt priority level setting.
*/
#if !defined(STM32_UART5_PRIORITY) || defined(__DOXYGEN__)
#define STM32_UART5_PRIORITY 12
#endif
#endif
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
/**
* @brief Serial Driver condition flags type.
*/
typedef uint32_t sdflags_t;
/**
* @brief STM32 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 Initialization value for the CR1 register.
*/
uint16_t sc_cr1;
/**
* @brief Initialization value for the CR2 register.
*/
uint16_t sc_cr2;
/**
* @brief Initialization value for the CR3 register.
*/
uint16_t sc_cr3;
} 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; \
/* Status Change @p EventSource.*/ \
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]; \
/* End of the mandatory fields.*/ \
/* Pointer to the USART registers block.*/ \
USART_TypeDef *usart;
/*===========================================================================*/
/* 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.*/
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#if USE_STM32_USART1 && !defined(__DOXYGEN__)
extern SerialDriver SD1;
#endif
#if USE_STM32_USART2 && !defined(__DOXYGEN__)
extern SerialDriver SD2;
#endif
#if USE_STM32_USART3 && !defined(__DOXYGEN__)
extern SerialDriver SD3;
#endif
#if defined(STM32F10X_HD) || defined(STM32F10X_CL)
#if USE_STM32_UART4 && !defined(__DOXYGEN__)
extern SerialDriver SD4;
#endif
#if USE_STM32_UART5 && !defined(__DOXYGEN__)
extern SerialDriver SD5;
#endif
#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 /* CH_HAL_USE_SERIAL */
#endif /* _SERIAL_LLD_H_ */
/** @} */

View File

@@ -0,0 +1,377 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/spi_lld.c
* @brief STM32 SPI subsystem low level driver source.
* @addtogroup STM32_SPI
* @{
*/
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_SPI || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/** @brief SPI1 driver identifier.*/
#if USE_STM32_SPI1 || defined(__DOXYGEN__)
SPIDriver SPID1;
#endif
/** @brief SPI2 driver identifier.*/
#if USE_STM32_SPI2 || defined(__DOXYGEN__)
SPIDriver SPID2;
#endif
/*===========================================================================*/
/* Driver local variables. */
/*===========================================================================*/
static uint16_t dummyrx;
static uint16_t dummytx;
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
static void spi_stop(SPIDriver *spip) {
/* Stops RX and TX DMA channels.*/
spip->spd_dmarx->CCR = 0;
spip->spd_dmatx->CCR = 0;
/* Stops SPI operations.*/
spip->spd_spi->CR1 &= ~SPI_CR1_SPE;
chSysLockFromIsr();
chSchReadyI(spip->spd_thread);
chSysUnlockFromIsr();
}
static void spi_start_wait(SPIDriver *spip, size_t n,
const void *txbuf, void *rxbuf) {
uint32_t ccr;
/* Common DMA setup.*/
ccr = spip->spd_dmaprio;
if ((spip->spd_config->spc_cr1 & SPI_CR1_DFF) != 0)
ccr |= DMA_CCR1_MSIZE_0 | DMA_CCR1_PSIZE_0; /* 16 bits transfer.*/
/* RX DMA setup.*/
spip->spd_dmarx->CMAR = (uint32_t)rxbuf;
spip->spd_dmarx->CNDTR = (uint32_t)n;
spip->spd_dmarx->CCR |= ccr;
/* TX DMA setup.*/
spip->spd_dmatx->CMAR = (uint32_t)txbuf;
spip->spd_dmatx->CNDTR = (uint32_t)n;
spip->spd_dmatx->CCR |= ccr;
/* SPI enable.*/
chSysLock();
spip->spd_spi->CR1 |= SPI_CR1_SPE;
/* DMAs start.*/
spip->spd_dmarx->CCR |= DMA_CCR1_EN;
spip->spd_dmatx->CCR |= DMA_CCR1_EN;
/* Wait for completion event.*/
spip->spd_thread = currp;
chSchGoSleepS(THD_STATE_SUSPENDED);
spip->spd_thread = NULL;
chSysUnlock();
}
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
#if USE_STM32_SPI1 || defined(__DOXYGEN__)
/**
* @brief SPI1 RX DMA interrupt handler (channel 2).
*/
CH_IRQ_HANDLER(Vector70) {
CH_IRQ_PROLOGUE();
spi_stop(&SPID1);
if ((DMA1->ISR & DMA_ISR_TEIF2) != 0) {
STM32_SPI1_DMA_ERROR_HOOK();
}
DMA1->IFCR |= DMA_IFCR_CGIF2 | DMA_IFCR_CTCIF2 |
DMA_IFCR_CHTIF2 | DMA_IFCR_CTEIF2;
CH_IRQ_EPILOGUE();
}
/**
* @brief SPI1 TX DMA interrupt handler (channel 3).
*/
CH_IRQ_HANDLER(Vector74) {
CH_IRQ_PROLOGUE();
STM32_SPI1_DMA_ERROR_HOOK();
DMA1->IFCR |= DMA_IFCR_CGIF3 | DMA_IFCR_CTCIF3 |
DMA_IFCR_CHTIF3 | DMA_IFCR_CTEIF3;
CH_IRQ_EPILOGUE();
}
#endif
#if USE_STM32_SPI2 || defined(__DOXYGEN__)
/**
* @brief SPI2 RX DMA interrupt handler (channel 4).
*/
CH_IRQ_HANDLER(Vector78) {
CH_IRQ_PROLOGUE();
spi_stop(&SPID2);
if ((DMA1->ISR & DMA_ISR_TEIF4) != 0) {
STM32_SPI2_DMA_ERROR_HOOK();
}
DMA1->IFCR |= DMA_IFCR_CGIF4 | DMA_IFCR_CTCIF4 |
DMA_IFCR_CHTIF4 | DMA_IFCR_CTEIF4;
CH_IRQ_EPILOGUE();
}
/**
* @brief SPI2 TX DMA interrupt handler (channel 5).
*/
CH_IRQ_HANDLER(Vector7C) {
CH_IRQ_PROLOGUE();
STM32_SPI2_DMA_ERROR_HOOK();
DMA1->IFCR |= DMA_IFCR_CGIF5 | DMA_IFCR_CTCIF5 |
DMA_IFCR_CHTIF5 | DMA_IFCR_CTEIF5;
CH_IRQ_EPILOGUE();
}
#endif
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level SPI driver initialization.
*/
void spi_lld_init(void) {
dummytx = 0xFFFF;
#if USE_STM32_SPI1
RCC->APB2RSTR = RCC_APB2RSTR_SPI1RST;
RCC->APB2RSTR = 0;
spiObjectInit(&SPID1);
SPID1.spd_thread = NULL;
SPID1.spd_spi = SPI1;
SPID1.spd_dmarx = DMA1_Channel2;
SPID1.spd_dmatx = DMA1_Channel3;
SPID1.spd_dmaprio = STM32_SPI1_DMA_PRIORITY << 12;
#endif
#if USE_STM32_SPI2
RCC->APB1RSTR = RCC_APB1RSTR_SPI2RST;
RCC->APB1RSTR = 0;
spiObjectInit(&SPID2);
SPID2.spd_thread = NULL;
SPID2.spd_spi = SPI2;
SPID2.spd_dmarx = DMA1_Channel4;
SPID2.spd_dmatx = DMA1_Channel5;
SPID2.spd_dmaprio = STM32_SPI2_DMA_PRIORITY << 12;
#endif
}
/**
* @brief Configures and activates the SPI peripheral.
*
* @param[in] spip pointer to the @p SPIDriver object
*/
void spi_lld_start(SPIDriver *spip) {
/* If in stopped state then enables the SPI and DMA clocks.*/
if (spip->spd_state == SPI_STOP) {
#if USE_STM32_SPI1
if (&SPID1 == spip) {
dmaEnable(DMA1_ID); /* NOTE: Must be enabled before the IRQs.*/
NVICEnableVector(DMA1_Channel2_IRQn,
CORTEX_PRIORITY_MASK(STM32_SPI1_IRQ_PRIORITY));
NVICEnableVector(DMA1_Channel3_IRQn,
CORTEX_PRIORITY_MASK(STM32_SPI1_IRQ_PRIORITY));
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
}
#endif
#if USE_STM32_SPI2
if (&SPID2 == spip) {
dmaEnable(DMA1_ID); /* NOTE: Must be enabled before the IRQs.*/
NVICEnableVector(DMA1_Channel4_IRQn,
CORTEX_PRIORITY_MASK(STM32_SPI2_IRQ_PRIORITY));
NVICEnableVector(DMA1_Channel5_IRQn,
CORTEX_PRIORITY_MASK(STM32_SPI2_IRQ_PRIORITY));
RCC->APB1ENR |= RCC_APB1ENR_SPI2EN;
}
#endif
}
/* SPI setup.*/
spip->spd_spi->CR1 = spip->spd_config->spc_cr1 | SPI_CR1_MSTR;
spip->spd_spi->CR2 = SPI_CR2_SSOE | SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN;
/* DMA setup.*/
spip->spd_dmarx->CPAR = (uint32_t)&spip->spd_spi->DR;
spip->spd_dmatx->CPAR = (uint32_t)&spip->spd_spi->DR;
}
/**
* @brief Deactivates the SPI peripheral.
*
* @param[in] spip pointer to the @p SPIDriver object
*/
void spi_lld_stop(SPIDriver *spip) {
/* If in ready state then disables the SPI clock.*/
if (spip->spd_state == SPI_READY) {
#if USE_STM32_SPI1
if (&SPID1 == spip) {
NVICDisableVector(DMA1_Channel2_IRQn);
NVICDisableVector(DMA1_Channel3_IRQn);
dmaDisable(DMA1_ID);
RCC->APB2ENR &= ~RCC_APB2ENR_SPI1EN;
}
#endif
#if USE_STM32_SPI2
if (&SPID2 == spip) {
NVICDisableVector(DMA1_Channel4_IRQn);
NVICDisableVector(DMA1_Channel5_IRQn);
dmaDisable(DMA1_ID);
RCC->APB1ENR &= ~RCC_APB1ENR_SPI2EN;
}
#endif
}
}
/**
* @brief Asserts the slave select signal and prepares for transfers.
*
* @param[in] spip pointer to the @p SPIDriver object
*/
void spi_lld_select(SPIDriver *spip) {
palClearPad(spip->spd_config->spc_ssport, spip->spd_config->spc_sspad);
}
/**
* @brief Deasserts the slave select signal.
* @details The previously selected peripheral is unselected.
*
* @param[in] spip pointer to the @p SPIDriver object
*/
void spi_lld_unselect(SPIDriver *spip) {
palSetPad(spip->spd_config->spc_ssport, spip->spd_config->spc_sspad);
}
/**
* @brief Ignores data on the SPI bus.
* @details This function transmits a series of idle words on the SPI bus and
* ignores the received data. This function can be invoked even
* when a slave select signal has not been yet asserted.
*
* @param[in] spip pointer to the @p SPIDriver object
* @param[in] n number of words to be ignored
*/
void spi_lld_ignore(SPIDriver *spip, size_t n) {
spip->spd_dmarx->CCR = DMA_CCR1_TCIE | DMA_CCR1_TEIE;
spip->spd_dmatx->CCR = DMA_CCR1_DIR | DMA_CCR1_TEIE;
spi_start_wait(spip, n, &dummytx, &dummyrx);
}
/**
* @brief Exchanges data on the SPI bus.
* @details This function performs a simultaneous transmit/receive operation.
*
* @param[in] spip pointer to the @p SPIDriver object
* @param[in] n number of words to be exchanged
* @param[in] txbuf the pointer to the transmit buffer
* @param[out] rxbuf the pointer to the receive buffer
*
* @note The buffers are organized as uint8_t arrays for data sizes below or
* equal to 8 bits else it is organized as uint16_t arrays.
*/
void spi_lld_exchange(SPIDriver *spip, size_t n,
const void *txbuf, void *rxbuf) {
spip->spd_dmarx->CCR = DMA_CCR1_TCIE | DMA_CCR1_MINC | DMA_CCR1_TEIE;
spip->spd_dmatx->CCR = DMA_CCR1_DIR | DMA_CCR1_MINC | DMA_CCR1_TEIE;
spi_start_wait(spip, n, txbuf, rxbuf);
}
/**
* @brief Sends data ever the SPI bus.
*
* @param[in] spip pointer to the @p SPIDriver object
* @param[in] n number of words to send
* @param[in] txbuf the pointer to the transmit buffer
*
* @note The buffers are organized as uint8_t arrays for data sizes below or
* equal to 8 bits else it is organized as uint16_t arrays.
*/
void spi_lld_send(SPIDriver *spip, size_t n, const void *txbuf) {
spip->spd_dmarx->CCR = DMA_CCR1_TCIE | DMA_CCR1_TEIE;
spip->spd_dmatx->CCR = DMA_CCR1_DIR | DMA_CCR1_MINC | DMA_CCR1_TEIE;
spi_start_wait(spip, n, txbuf, &dummyrx);
}
/**
* @brief Receives data from the SPI bus.
*
* @param[in] spip pointer to the @p SPIDriver object
* @param[in] n number of words to receive
* @param[out] rxbuf the pointer to the receive buffer
*
* @note The buffers are organized as uint8_t arrays for data sizes below or
* equal to 8 bits else it is organized as uint16_t arrays.
*/
void spi_lld_receive(SPIDriver *spip, size_t n, void *rxbuf) {
spip->spd_dmarx->CCR = DMA_CCR1_TCIE | DMA_CCR1_MINC | DMA_CCR1_TEIE;
spip->spd_dmatx->CCR = DMA_CCR1_DIR | DMA_CCR1_TEIE;
spi_start_wait(spip, n, &dummytx, rxbuf);
}
#endif /* CH_HAL_USE_SPI */
/** @} */

View File

@@ -0,0 +1,226 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file STM32/spi_lld.h
* @brief STM32 SPI subsystem low level driver header.
*
* @addtogroup STM32_SPI
* @{
*/
#ifndef _SPI_LLD_H_
#define _SPI_LLD_H_
#if CH_HAL_USE_SPI || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @brief SPI1 driver enable switch.
* @details If set to @p TRUE the support for SPI1 is included.
* @note The default is @p TRUE.
*/
#if !defined(USE_STM32_SPI1) || defined(__DOXYGEN__)
#define USE_STM32_SPI1 TRUE
#endif
/**
* @brief SPI2 driver enable switch.
* @details If set to @p TRUE the support for SPI2 is included.
* @note The default is @p TRUE.
*/
#if !defined(USE_STM32_SPI2) || defined(__DOXYGEN__)
#define USE_STM32_SPI2 TRUE
#endif
/**
* @brief SPI1 DMA priority (0..3|lowest..highest).
* @note The priority level is used for both the TX and RX DMA channels but
* because of the channels ordering the RX channel has always priority
* over the TX channel.
*/
#if !defined(STM32_SPI1_DMA_PRIORITY) || defined(__DOXYGEN__)
#define STM32_SPI1_DMA_PRIORITY 2
#endif
/**
* @brief SPI2 DMA priority (0..3|lowest..highest).
* @note The priority level is used for both the TX and RX DMA channels but
* because of the channels ordering the RX channel has always priority
* over the TX channel.
*/
#if !defined(STM32_SPI2_DMA_PRIORITY) || defined(__DOXYGEN__)
#define STM32_SPI2_DMA_PRIORITY 2
#endif
/**
* @brief SPI1 interrupt priority level setting.
*/
#if !defined(STM32_SPI1_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_SPI1_IRQ_PRIORITY 10
#endif
/**
* @brief SPI2 interrupt priority level setting.
*/
#if !defined(STM32_SPI2_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_SPI2_IRQ_PRIORITY 10
#endif
/**
* @brief SPI1 DMA error hook.
* @note The default action for DMA errors is a system halt because DMA error
* can only happen because programming errors.
*/
#if !defined(STM32_SPI1_DMA_ERROR_HOOK) || defined(__DOXYGEN__)
#define STM32_SPI1_DMA_ERROR_HOOK() chSysHalt()
#endif
/**
* @brief SPI2 DMA error hook.
* @note The default action for DMA errors is a system halt because DMA error
* can only happen because programming errors.
*/
#if !defined(STM32_SPI2_DMA_ERROR_HOOK) || defined(__DOXYGEN__)
#define STM32_SPI2_DMA_ERROR_HOOK() chSysHalt()
#endif
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
/**
* @brief Driver configuration structure.
*/
typedef struct {
/**
* @brief The chip select line port.
*/
ioportid_t spc_ssport;
/**
* @brief The chip select line pad number.
*/
uint16_t spc_sspad;
/**
* @brief SPI initialization data.
*/
uint16_t spc_cr1;
} SPIConfig;
/**
* @brief Structure representing a SPI driver.
*/
typedef struct {
/**
* @brief Driver state.
*/
spistate_t spd_state;
#if SPI_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__)
#if CH_USE_MUTEXES || defined(__DOXYGEN__)
/**
* @brief Mutex protecting the bus.
*/
Mutex spd_mutex;
#elif CH_USE_SEMAPHORES
Semaphore spd_semaphore;
#endif
#endif /* SPI_USE_MUTUAL_EXCLUSION */
/**
* @brief Current configuration data.
*/
const SPIConfig *spd_config;
/* End of the mandatory fields.*/
/**
* @brief Thread waiting for I/O completion.
*/
Thread *spd_thread;
/**
* @brief Pointer to the SPIx registers block.
*/
SPI_TypeDef *spd_spi;
/**
* @brief Pointer to the receive DMA channel registers block.
*/
DMA_Channel_TypeDef *spd_dmarx;
/**
* @brief Pointer to the transmit DMA channel registers block.
*/
DMA_Channel_TypeDef *spd_dmatx;
/**
* @brief DMA priority bit mask.
*/
uint32_t spd_dmaprio;
} SPIDriver;
/*===========================================================================*/
/* Driver macros. */
/*===========================================================================*/
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#if USE_STM32_SPI1 && !defined(__DOXYGEN__)
extern SPIDriver SPID1;
#endif
#if USE_STM32_SPI2 && !defined(__DOXYGEN__)
extern SPIDriver SPID2;
#endif
#ifdef __cplusplus
extern "C" {
#endif
void spi_lld_init(void);
void spi_lld_start(SPIDriver *spip);
void spi_lld_stop(SPIDriver *spip);
void spi_lld_select(SPIDriver *spip);
void spi_lld_unselect(SPIDriver *spip);
void spi_lld_ignore(SPIDriver *spip, size_t n);
void spi_lld_exchange(SPIDriver *spip, size_t n,
const void *txbuf, void *rxbuf);
void spi_lld_send(SPIDriver *spip, size_t n, const void *txbuf);
void spi_lld_receive(SPIDriver *spip, size_t n, void *rxbuf);
#ifdef __cplusplus
}
#endif
#endif /* CH_HAL_USE_SPI */
#endif /* _SPI_LLD_H_ */
/** @} */

View File

@@ -0,0 +1,119 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file stm32_dma.c
* @brief STM32 DMA helper driver code.
* @addtogroup STM32_DMA
* @{
*/
#include "ch.h"
#include "hal.h"
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver local variables. */
/*===========================================================================*/
static cnt_t dmacnt1;
#if defined(STM32F10X_HD) || defined (STM32F10X_CL)
static cnt_t dmacnt2;
#endif
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief STM32 DMA helper initialization.
*/
void dmaInit(void) {
dmacnt1 = 0;
#if defined(STM32F10X_HD) || defined (STM32F10X_CL)
dmacnt2 = 0;
#endif
}
/**
* @brief Enables the specified DMA controller clock.
*
* @param[in] dma the DMA controller id
*/
void dmaEnable(uint32_t dma) {
switch (dma) {
case DMA1_ID:
if (dmacnt1++ == 0) {
RCC->AHBENR |= RCC_AHBENR_DMA1EN;
DMA1->IFCR = 0x0FFFFFFF;
}
break;
#if defined(STM32F10X_HD) || defined (STM32F10X_CL)
case DMA2_ID:
if (dmacnt2++ == 0) {
RCC->AHBENR |= RCC_AHBENR_DMA2EN;
DMA2->IFCR = 0x0FFFFFFF;
}
break;
#endif
}
}
/**
* @brief Disables the specified DMA controller clock.
*
* @param[in] dma the DMA controller id
*/
void dmaDisable(uint32_t dma) {
switch (dma) {
case DMA1_ID:
if (--dmacnt1 == 0)
RCC->AHBENR &= ~RCC_AHBENR_DMA1EN;
break;
#if defined(STM32F10X_HD) || defined (STM32F10X_CL)
case DMA2_ID:
if (--dmacnt2 == 0)
RCC->AHBENR &= ~RCC_AHBENR_DMA2EN;
break;
#endif
}
}
/** @} */

View File

@@ -0,0 +1,82 @@
/*
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/>.
---
A special exception to the GPL can be applied should you wish to distribute
a combined work that includes ChibiOS/RT, without being obliged to provide
the source code for any proprietary components. See the file exception.txt
for full details of how and when the exception can be applied.
*/
/**
* @file stm32_dma.h
* @brief STM32 DMA helper driver header.
*
* @addtogroup STM32_DMA
* @{
*/
#ifndef _STM32_DMA_H_
#define _STM32_DMA_H_
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
/** @brief DMA1 identifier.*/
#define DMA1_ID 0
/** @brief DMA2 identifier.*/
#if defined(STM32F10X_HD) || defined (STM32F10X_CL) || defined(__DOXYGEN__)
#define DMA2_ID 1
#endif
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver macros. */
/*===========================================================================*/
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#ifdef __cplusplus
extern "C" {
#endif
void dmaInit(void);
void dmaEnable(uint32_t dma);
void dmaDisable(uint32_t dma);
#ifdef __cplusplus
}
#endif
#endif /* _STM32_DMA_H_ */
/** @} */

File diff suppressed because it is too large Load Diff