git-svn-id: svn://svn.code.sf.net/p/chibios/svn/trunk@1347 35acf78f-673a-0410-8e92-d51de3d6d3f4

This commit is contained in:
gdisirio 2009-11-29 08:40:11 +00:00
parent 3dc0fb372d
commit 544117e9eb
30 changed files with 687 additions and 104 deletions

13
os/io/hal.mk Normal file
View File

@ -0,0 +1,13 @@
# List of all the ChibiOS/RT HAL files, there is no need to remove the files
# from this list, you can disable parts of the kernel by editing halconf.h.
HALSRC = ${CHIBIOS}/os/hal/src/hal.c \
${CHIBIOS}/os/hal/src/adc.c \
${CHIBIOS}/os/hal/src/can.c \
${CHIBIOS}/os/hal/src/mac.c \
${CHIBIOS}/os/hal/src/pal.c \
${CHIBIOS}/os/hal/src/serial.c \
${CHIBIOS}/os/hal/src/spi.c \
${CHIBIOS}/os/hal/src/mmc_spi.c
# Required include directories
HALINC = ${CHIBIOS}/os/hal/include

View File

@ -27,6 +27,8 @@
#ifndef _ADC_H_
#define _ADC_H_
#if CH_HAL_USE_ADC
#if !CH_USE_SEMAPHORES
#error "ADC driver requires CH_USE_SEMAPHORES"
#endif
@ -38,7 +40,8 @@ typedef enum {
ADC_UNINIT = 0, /**< @brief Not initialized. */
ADC_STOP = 1, /**< @brief Stopped. */
ADC_READY = 2, /**< @brief Ready. */
ADC_RUNNING = 3 /**< @brief Conversion running. */
ADC_RUNNING = 3, /**< @brief Conversion running. */
ADC_COMPLETE = 4 /**< @brief Conversion complete.*/
} adcstate_t;
#include "adc_lld.h"
@ -61,6 +64,8 @@ extern "C" {
}
#endif
#endif /* CH_HAL_USE_ADC */
#endif /* _ADC_H_ */
/** @} */

View File

@ -27,6 +27,8 @@
#ifndef _CAN_H_
#define _CAN_H_
#if CH_HAL_USE_CAN
/**
* @brief Driver state machine possible states.
*/
@ -56,6 +58,8 @@ extern "C" {
}
#endif
#endif /* CH_HAL_USE_CAN */
#endif /* _CAN_H_ */
/** @} */

View File

@ -27,6 +27,8 @@
#ifndef _MAC_H_
#define _MAC_H_
#if CH_HAL_USE_MAC
#include "mac_lld.h"
/**
@ -84,6 +86,8 @@ extern "C" {
}
#endif
#endif /* CH_HAL_USE_MAC */
#endif /* _MAC_H_ */
/** @} */

View File

@ -19,7 +19,7 @@
/**
* @file mmc_spi.h
* @brief MMC over SPI driver header
* @brief MMC over SPI driver header.
* @addtogroup MMC_SPI
* @{
*/
@ -27,6 +27,8 @@
#ifndef _MMC_SPI_H_
#define _MMC_SPI_H_
#if CH_HAL_USE_MMC_SPI
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
@ -199,6 +201,8 @@ extern "C" {
}
#endif
#endif /* CH_HAL_USE_MMC_SPI */
#endif /* _MMC_SPI_H_ */
/** @} */

View File

@ -27,6 +27,8 @@
#ifndef _PAL_H_
#define _PAL_H_
#if CH_HAL_USE_PAL
/**
* @brief Bits in a mode word dedicated as mode selector.
* @details The other bits are not defined and may be used as device-specific
@ -81,9 +83,7 @@
*/
#define PAL_MODE_OUTPUT_OPENDRAIN 7
#ifndef _PAL_LLD_H_
#include "pal_lld.h"
#endif
/**
* @brief Logical low state.
@ -464,4 +464,6 @@ extern "C" {
#endif /* _PAL_H_ */
#endif /* CH_HAL_USE_PAL */
/** @} */

View File

@ -27,6 +27,8 @@
#ifndef _SERIAL_H_
#define _SERIAL_H_
#if CH_HAL_USE_SERIAL
/** No pending conditions.*/
#define SD_NO_ERROR 0
/** Connection happened.*/
@ -188,6 +190,8 @@ extern "C" {
*/
#define sdRead(sdp, b, n) chIQRead(&(sdp)->d2.iqueue, b, n)
#endif /* CH_HAL_USE_SERIAL */
#endif /* _SERIAL_H_ */
/** @} */

View File

@ -27,6 +27,8 @@
#ifndef _SPI_H_
#define _SPI_H_
#if CH_HAL_USE_SPI
/**
* @brief Enables the mutual exclusion APIs on the SPI bus.
*/
@ -71,6 +73,8 @@ extern "C" {
}
#endif
#endif /* CH_HAL_USE_SPI */
#endif /* _SPI_H_ */
/** @} */

View File

@ -24,10 +24,10 @@
* @{
*/
#include <ch.h>
#include <adc.h>
#include <stm32_dma.h>
#include <nvic.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_ADC
/*===========================================================================*/
/* Low Level Driver exported variables. */
@ -60,6 +60,8 @@ CH_IRQ_HANDLER(Vector6C) {
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) {
@ -73,8 +75,10 @@ CH_IRQ_HANDLER(Vector6C) {
/* End conversion.*/
adc_lld_stop_conversion(&ADCD1);
ADCD1.ad_grpp = NULL;
ADCD1.ad_state = ADC_READY;
ADCD1.ad_state = ADC_COMPLETE;
chSysLockFromIsr();
chSemResetI(&ADCD1.ad_sem, 0);
chSysUnlockFromIsr();
}
/* Callback handling.*/
if (ADCD1.ad_callback != NULL) {
@ -84,7 +88,7 @@ CH_IRQ_HANDLER(Vector6C) {
ADCD1.ad_callback(ADCD1.ad_samples + half, half);
}
else {
/* Invokes the callback passing the while buffer.*/
/* Invokes the callback passing the whole buffer.*/
ADCD1.ad_callback(ADCD1.ad_samples, ADCD1.ad_depth);
}
}
@ -93,8 +97,6 @@ CH_IRQ_HANDLER(Vector6C) {
/* DMA error processing.*/
STM32_ADC1_DMA_ERROR_HOOK();
}
DMA1->IFCR |= DMA_IFCR_CGIF1 | DMA_IFCR_CTCIF1 |
DMA_IFCR_CHTIF1 | DMA_IFCR_CTEIF1;
CH_IRQ_EPILOGUE();
}
@ -110,6 +112,10 @@ CH_IRQ_HANDLER(Vector6C) {
void adc_lld_init(void) {
#if USE_STM32_ADC1
/* ADC reset, ensures reset state in order to avoid truouble with JTAGs.*/
RCC->APB2RSTR = RCC_APB2RSTR_ADC1RST;
RCC->APB2RSTR = 0;
/* Driver initialization.*/
adcObjectInit(&ADCD1);
ADCD1.ad_adc = ADC1;
@ -169,7 +175,7 @@ void adc_lld_start(ADCDriver *adcp) {
*/
void adc_lld_stop(ADCDriver *adcp) {
/* If in ready state then disables the SPI clock.*/
/* If in ready state then disables the ADC clock.*/
if (adcp->ad_state == ADC_READY) {
#if USE_STM32_ADC1
if (&ADCD1 == adcp) {
@ -233,4 +239,6 @@ void adc_lld_stop_conversion(ADCDriver *adcp) {
adcp->ad_dma->CCR = 0;
}
#endif /* CH_HAL_USE_ADC */
/** @} */

View File

@ -27,11 +27,7 @@
#ifndef _ADC_LLD_H_
#define _ADC_LLD_H_
#undef FALSE
#undef TRUE
#include <stm32f10x.h>
#define FALSE 0
#define TRUE (!FALSE)
#if CH_HAL_USE_ADC
/*===========================================================================*/
/* Driver pre-compile time settings. */
@ -74,7 +70,7 @@
/* Driver constants. */
/*===========================================================================*/
#define ADC_CR2_EXTSEL_SRC(n) (n << 17) /**< @brief Trigger source. */
#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. */
@ -96,26 +92,26 @@
#define ADC_CHANNEL_SENSOR 16 /**< @brief Internal temperature sensor.*/
#define ADC_CHANNEL_VREFINT 17 /**< @brief Internal reference. */
#define ADC_SQR1_NUM_CH(n) (n << 20)
#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_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_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)
#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)
/*===========================================================================*/
/* Driver data structures and types. */
@ -271,6 +267,8 @@ extern "C" {
#endif
/** @endcond*/
#endif /* CH_HAL_USE_ADC */
#endif /* _ADC_LLD_H_ */
/** @} */

View File

@ -0,0 +1,159 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file 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
/*===========================================================================*/
/* Low Level Driver exported variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Low Level Driver local variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Low Level Driver local functions. */
/*===========================================================================*/
/*===========================================================================*/
/* Low Level Driver interrupt handlers. */
/*===========================================================================*/
/*===========================================================================*/
/* Low Level Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level CAN driver initialization.
*/
void can_lld_init(void) {
}
/**
* @brief Configures and activates the CAN peripheral.
*
* @param[in] canp pointer to the @p CANDriver object
*/
void can_lld_start(CANDriver *canp) {
if (canp->can_state == CAN_STOP) {
/* Clock activation.*/
}
/* Configuration.*/
}
/**
* @brief Deactivates the CAN peripheral.
*
* @param[in] canp pointer to the @p CANDriver object
*/
void can_lld_stop(CANDriver *canp) {
}
/**
* @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 FALSE;
}
/**
* @brief Inserts a frame into the transmit queue.
*
* @param[in] canp pointer to the @p CANDriver object
* @param[in] cfp pointer to the CAN frame to be transmitted
*
* @return The operation status.
* @retval RDY_OK frame transmitted.
*/
msg_t can_lld_transmit(CANDriver *canp, const CANFrame *cfp) {
return RDY_OK;
}
/**
* @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 FALSE;
}
/**
* @brief Receives a frame from the input queue.
*
* @param[in] canp pointer to the @p CANDriver object
* @param[out] cfp pointer to the buffer where the CAN frame is copied
*
* @return The operation status.
* @retval RDY_OK frame received.
*/
msg_t can_lld_receive(CANDriver *canp, CANFrame *cfp) {
return RDY_OK;
}
#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) {
}
/**
* @brief Enforces leaving the sleep mode.
*
* @param[in] canp pointer to the @p CANDriver object
*/
void can_lld_wakeup(CANDriver *canp) {
}
#endif /* CAN_USE_SLEEP_MODE */
#endif /* CH_HAL_USE_CAN */
/** @} */

View File

@ -0,0 +1,154 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file 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
/**
* @brief This switch defines whether the driver implementation supports
* a low power switch mode with automatic an wakeup feature.
*/
#define CAN_SUPPORTS_SLEEP TRUE
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @brief Sleep mode related APIs inclusion switch.
* @note This switch is enforced to @p FALSE if the driver implementation
* does not support the sleep mode.
*/
#if CAN_SUPPORTS_SLEEP || defined(__DOXYGEN__)
#if !defined(CAN_USE_SLEEP_MODE) || defined(__DOXYGEN__)
#define CAN_USE_SLEEP_MODE TRUE
#endif
#else /* !CAN_SUPPORTS_SLEEP */
#define CAN_USE_SLEEP_MODE FALSE
#endif /* !CAN_SUPPORTS_SLEEP */
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
/**
* @brief CAN 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 {
uint8_t cf_DLC:4; /**< @brief Data length. */
uint8_t cf_IDE:1; /**< @brief Identifier type. */
uint8_t cf_RTR:1; /**< @brief Frame type. */
uint32_t cf_id; /**< @brief Frame 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. */
};
} CANFrame;
/**
* @brief Driver configuration structure.
* @note It could be empty on some architectures.
*/
typedef struct {
} CANConfig;
/**
* @brief Structure representing an CAN driver.
*/
typedef struct {
/**
* @brief Driver state.
*/
canstate_t can_state;
/**
* @brief Current configuration data.
*/
const CANConfig *can_config;
/**
* @brief Transmission queue semaphore.
*/
Semaphore can_txsem;
/**
* @brief Receive queue semaphore.
*/
Semaphore can_rxsem;
/**
* @brief One or more frames become available.
*/
EventSource can_rxfull_event;
/**
* @brief One or more transmission slots become available.
*/
EventSource can_txempty_event;
#if CAN_USE_SLEEP_MODE || defined (__DOXYGEN__)
/**
* @brief Entering sleep state event.
*/
EventSource can_sleep_event;
/**
* @brief Exiting sleep state event.
*/
EventSource can_wakeup_event;
#endif /* CAN_USE_SLEEP_MODE */
/* End of the mandatory fields.*/
} CANDriver;
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#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);
msg_t can_lld_transmit(CANDriver *canp, const CANFrame *cfp);
bool_t can_lld_can_receive(CANDriver *canp);
msg_t can_lld_receive(CANDriver *canp, CANFrame *cfp);
#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,128 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file 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
/*===========================================================================*/
/* Low Level Driver exported variables. */
/*===========================================================================*/
/*===========================================================================*/
/* Low Level Driver local variables. */
/*===========================================================================*/
/*
* Digital I/O ports static configuration as defined in @p board.h.
*/
const STM32GPIOConfig 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)
{VAL_GPIOEODR, VAL_GPIOECRL, VAL_GPIOECRH},
#endif
#if defined(STM32F10X_HD)
{VAL_GPIOFODR, VAL_GPIOFCRL, VAL_GPIOFCRH},
{VAL_GPIOGODR, VAL_GPIOGCRL, VAL_GPIOGCRH},
#endif
};
/*===========================================================================*/
/* Low Level Driver local functions. */
/*===========================================================================*/
/*===========================================================================*/
/* Low Level Driver interrupt handlers. */
/*===========================================================================*/
/*===========================================================================*/
/* Low Level Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level HAL driver initialization.
*/
void hal_lld_init(void) {
#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.
*/
void stm32_clock_init(void) {
/* HSI setup.*/
RCC->CR = RCC_CR_HSITRIM_RESET_BITS | RCC_CR_HSION;
while (!(RCC->CR & RCC_CR_HSIRDY))
; /* Waits until HSI stable. */
/* HSE setup.*/
RCC->CR |= RCC_CR_HSEON;
while (!(RCC->CR & RCC_CR_HSERDY))
; /* Waits until HSE stable. */
/* PLL setup.*/
RCC->CFGR = RCC_CFGR_PLLSRC_HSE_BITS | PLLPREBITS | PLLMULBITS;
RCC->CR |= RCC_CR_PLLON;
while (!(RCC->CR & RCC_CR_PLLRDY))
; /* Waits until PLL stable. */
/* Clock sources.*/
RCC->CFGR |= RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE1_DIV2 |
RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_ADCPRE_DIV8 |
RCC_CFGR_MCO_NOCLOCK | USBPREBITS;
/* Flash setup and final clock selection. */
FLASH->ACR = FLASHBITS; /* Flash wait states depending on clock. */
RCC->CFGR |= RCC_CFGR_SW_PLL; /* Switches the PLL clock ON. */
while ((RCC->CFGR & RCC_CFGR_SW) != RCC_CFGR_SW_PLL)
;
}
/**
* @brief STM32 NVIC/SCB/SYSTICK initialization.
* @note All the involved constants come from the file @p board.h.
*/
void stm32_nvic_init(void) {
/* Note: PRIGROUP 4:0 (4:4).*/
SCB->AIRCR = AIRCR_VECTKEY | SCB_AIRCR_PRIGROUP_0 | SCB_AIRCR_PRIGROUP_1;
NVICSetSystemHandlerPriority(HANDLER_SVCALL, PRIORITY_SVCALL);
NVICSetSystemHandlerPriority(HANDLER_SYSTICK, PRIORITY_SYSTICK);
NVICSetSystemHandlerPriority(HANDLER_PENDSV, PRIORITY_PENDSV);
SysTick->LOAD = SYSCLK / (8000000 / CH_FREQUENCY) - 1;
SysTick->VAL = 0;
SysTick->CTRL = SysTick_CTRL_ENABLE | SysTick_CTRL_TICKINT;
}
/** @} */

View File

@ -0,0 +1,61 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file STM32/hal_lld.h
* @brief STM32 HAL subsystem low level driver header
* @addtogroup STM32_HAL
* @{
*/
#ifndef _HAL_LLD_H_
#define _HAL_LLD_H_
#include "nvic.h"
#include "stm32_dma.h"
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#ifdef __cplusplus
extern "C" {
#endif
void hal_lld_init(void);
void stm32_clock_init(void);
void stm32_nvic_init(void);
#ifdef __cplusplus
}
#endif
#endif /* _HAL_LLD_H_ */
/** @} */

View File

@ -24,8 +24,10 @@
* @{
*/
#include <ch.h>
#include <pal.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_PAL
#if defined(STM32F10X_LD)
#define APB2_RST_MASK (RCC_APB2RSTR_IOPARST | RCC_APB2RSTR_IOPBRST | \
@ -156,4 +158,6 @@ void _pal_lld_setgroupmode(ioportid_t port,
port->CRL = (port->CRL & ml) | crl;
}
#endif /* CH_HAL_USE_PAL */
/** @} */

View File

@ -27,11 +27,7 @@
#ifndef _PAL_LLD_H_
#define _PAL_LLD_H_
#undef FALSE
#undef TRUE
#include <stm32f10x.h>
#define FALSE 0
#define TRUE (!FALSE)
#if CH_HAL_USE_PAL
/*===========================================================================*/
/* I/O Ports Types and constants. */
@ -296,6 +292,8 @@ extern "C" {
}
#endif
#endif /* CH_HAL_USE_PAL */
#endif /* _PAL_LLD_H_ */
/** @} */

View File

@ -0,0 +1,11 @@
# 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/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

@ -24,10 +24,10 @@
* @{
*/
#include <ch.h>
#include <serial.h>
#include <nvic.h>
#include <board.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_SERIAL
#if USE_STM32_USART1 || defined(__DOXYGEN__)
/** @brief USART1 serial driver identifier.*/
@ -300,4 +300,6 @@ void sd_lld_stop(SerialDriver *sdp) {
#endif
}
#endif /* CH_HAL_USE_SERIAL */
/** @} */

View File

@ -27,11 +27,7 @@
#ifndef _SERIAL_LLD_H_
#define _SERIAL_LLD_H_
#undef FALSE
#undef TRUE
#include <stm32f10x.h>
#define FALSE 0
#define TRUE (!FALSE)
#if CH_HAL_USE_SERIAL
/*===========================================================================*/
/* Driver pre-compile time settings. */
@ -195,6 +191,8 @@ extern "C" {
#endif
/** @endcond*/
#endif /* CH_HAL_USE_SERIAL */
#endif /* _SERIAL_LLD_H_ */
/** @} */

View File

@ -24,10 +24,10 @@
* @{
*/
#include <ch.h>
#include <spi.h>
#include <stm32_dma.h>
#include <nvic.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_SPI
/*===========================================================================*/
/* Low Level Driver exported variables. */
@ -184,6 +184,8 @@ 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;
@ -194,6 +196,8 @@ void spi_lld_init(void) {
#endif
#if USE_STM32_SPI2
RCC->APB1RSTR = RCC_APB1RSTR_SPI2RST;
RCC->APB1RSTR = 0;
spiObjectInit(&SPID2);
SPID2.spd_thread = NULL;
SPID2.spd_spi = SPI2;
@ -359,4 +363,6 @@ void spi_lld_receive(SPIDriver *spip, size_t n, void *rxbuf) {
spi_start_wait(spip, n, &dummytx, rxbuf);
}
#endif /* CH_HAL_USE_SPI */
/** @} */

View File

@ -27,13 +27,7 @@
#ifndef _SPI_LLD_H_
#define _SPI_LLD_H_
#include <pal.h>
#undef FALSE
#undef TRUE
#include <stm32f10x.h>
#define FALSE 0
#define TRUE (!FALSE)
#if CH_HAL_USE_SPI
/*===========================================================================*/
/* Driver pre-compile time settings. */
@ -209,6 +203,8 @@ extern "C" {
#endif
/** @endcond*/
#endif /* CH_HAL_USE_SPI */
#endif /* _SPI_LLD_H_ */
/** @} */

View File

@ -24,15 +24,8 @@
* @{
*/
#include <ch.h>
#include "stm32_dma.h"
#undef FALSE
#undef TRUE
#include <stm32f10x.h>
#define FALSE 0
#define TRUE (!FALSE)
#include "ch.h"
#include "hal.h"
static cnt_t dmacnt1;
#if defined(STM32F10X_HD) || defined (STM32F10X_CL)

View File

@ -27,12 +27,6 @@
#ifndef _STM32_DMA_H_
#define _STM32_DMA_H_
#undef FALSE
#undef TRUE
#include <stm32f10x.h>
#define FALSE 0
#define TRUE (!FALSE)
/** @brief DMA1 identifier.*/
#define DMA1_ID 0

View File

@ -24,8 +24,10 @@
* @{
*/
#include <ch.h>
#include <adc.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_ADC
/**
* @brief ADC Driver initialization.
@ -132,7 +134,8 @@ bool_t adcStartConversion(ADCDriver *adcp,
chSysLock();
chDbgAssert((adcp->ad_state == ADC_READY) ||
(adcp->ad_state == ADC_RUNNING),
(adcp->ad_state == ADC_RUNNING) ||
(adcp->ad_state == ADC_COMPLETE),
"adcStartConversion(), #1",
"invalid state");
if (adcp->ad_state == ADC_RUNNING) {
@ -160,19 +163,26 @@ void adcStopConversion(ADCDriver *adcp) {
chSysLock();
chDbgAssert((adcp->ad_state == ADC_READY) ||
(adcp->ad_state == ADC_RUNNING),
(adcp->ad_state == ADC_RUNNING) ||
(adcp->ad_state == ADC_COMPLETE),
"adcStopConversion(), #1",
"invalid state");
if (adcp->ad_state == ADC_RUNNING) {
adc_lld_stop_conversion(adcp);
adcp->ad_grpp = NULL;
adcp->ad_state = ADC_READY;
chSemResetI(&adcp->ad_sem, 0);
chSchRescheduleS();
}
else
adcp->ad_state = ADC_READY;
chSysUnlock();
}
/**
* @brief Waits for completion.
* @details If the conversion is not completed or not yet started then the
* invoking thread waits for a conversion completion event.
*
* @param[in] adcp pointer to the @p ADCDriver object
* @param[in] timeout the number of ticks before the operation timeouts,
@ -181,17 +191,18 @@ void adcStopConversion(ADCDriver *adcp) {
* - @a TIME_INFINITE no timeout.
* .
* @return The operation result.
* @retval RDY_OK conversion finished (or not started).
* @retval RDY_OK conversion finished.
* @retval RDY_TIMEOUT conversion not finished within the specified time.
*/
msg_t adcWaitConversion(ADCDriver *adcp, systime_t timeout) {
chSysLock();
chDbgAssert((adcp->ad_state == ADC_READY) ||
(adcp->ad_state == ADC_RUNNING),
(adcp->ad_state == ADC_RUNNING) ||
(adcp->ad_state == ADC_COMPLETE),
"adcWaitConversion(), #1",
"invalid state");
if (adcp->ad_state == ADC_RUNNING) {
if (adcp->ad_state != ADC_COMPLETE) {
if (chSemWaitTimeoutS(&adcp->ad_sem, timeout) == RDY_TIMEOUT) {
chSysUnlock();
return RDY_TIMEOUT;
@ -201,4 +212,6 @@ msg_t adcWaitConversion(ADCDriver *adcp, systime_t timeout) {
return RDY_OK;
}
#endif /* CH_HAL_USE_ADC */
/** @} */

View File

@ -24,8 +24,10 @@
* @{
*/
#include <ch.h>
#include <can.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_CAN
/**
* @brief CAN Driver initialization.
@ -44,8 +46,8 @@ void canObjectInit(CANDriver *canp) {
canp->can_state = CAN_STOP;
canp->can_config = NULL;
chSemInit(&canp->can_txsem);
chSemInit(&canp->can_rxsem);
chSemInit(&canp->can_txsem, 0);
chSemInit(&canp->can_rxsem, 0);
chEvtInit(&canp->can_rxfull_event);
chEvtInit(&canp->can_txempty_event);
#if CAN_USE_SLEEP_MODE
@ -183,7 +185,7 @@ void canSleep(CANDriver *canp) {
chDbgAssert((canp->can_state == CAN_READY) || (canp->can_state == CAN_SLEEP),
"canSleep(), #1",
"invalid state");
if (canp->can_state = CAN_READY) {
if (canp->can_state == CAN_READY) {
can_lld_sleep(canp);
canp->can_state = CAN_SLEEP;
chEvtBroadcastI(&canp->can_sleep_event);
@ -207,7 +209,7 @@ void canWakeup(CANDriver *canp) {
chDbgAssert((canp->can_state == CAN_READY) || (canp->can_state == CAN_SLEEP),
"canWakeup(), #1",
"invalid state");
if (canp->can_state = CAN_SLEEP) {
if (canp->can_state == CAN_SLEEP) {
can_lld_wakeup(canp);
canp->can_state = CAN_READY;
chEvtBroadcastI(&canp->can_wakeup_event);
@ -217,4 +219,6 @@ void canWakeup(CANDriver *canp) {
}
#endif /* CAN_USE_SLEEP_MODE */
#endif /* CH_HAL_USE_CAN */
/** @} */

View File

@ -24,8 +24,10 @@
* @{
*/
#include <ch.h>
#include <mac.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_MAC
/**
* @brief MAC Driver initialization.
@ -171,4 +173,6 @@ bool_t macPollLinkStatus(MACDriver *macp) {
return mac_lld_poll_link_status(macp);
}
#endif /* CH_HAL_USE_MAC */
/** @} */

View File

@ -24,14 +24,14 @@
* @{
*/
#include <ch.h>
#include <mac.h>
#include <mii.h>
#include "ch.h"
#include "mac.h"
#include "mii.h"
/*
* Currently there is no code, everything is done in the header, you may
* Currently there is no code, everything is done in the header, you may
* omit this file from the project but this may change in future releases.
* The file is here because the driver's naming pattern.
*/
/** @} */

View File

@ -24,8 +24,10 @@
* @{
*/
#include <ch.h>
#include <pal.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_PAL
/**
* @brief Read from an I/O bus.
@ -91,4 +93,6 @@ void palSetBusMode(IOBus *bus, uint_fast8_t mode) {
palSetGroupMode(bus->bus_portid, bus->bus_mask, mode);
}
#endif /* CH_HAL_USE_PAL */
/** @} */

View File

@ -24,8 +24,10 @@
* @{
*/
#include <ch.h>
#include <serial.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_SERIAL
/*
* Interface implementation, the following functions just invoke the equivalent
@ -194,4 +196,6 @@ sdflags_t sdGetAndClearFlags(SerialDriver *sd) {
return mask;
}
#endif /* CH_HAL_USE_SERIAL */
/** @} */

View File

@ -24,8 +24,10 @@
* @{
*/
#include <ch.h>
#include <spi.h>
#include "ch.h"
#include "hal.h"
#if CH_HAL_USE_SPI
/**
* @brief SPI Driver initialization.
@ -255,4 +257,6 @@ void spiReleaseBus(SPIDriver *spip) {
}
#endif /*SPI_USE_MUTUAL_EXCLUSION */
#endif /* CH_HAL_USE_SPI */
/** @} */