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

master
gdisirio 2011-06-19 10:45:38 +00:00
parent e612b8c794
commit ec3ca5b4e6
8 changed files with 792 additions and 150 deletions

View File

@ -54,83 +54,104 @@
/*
* I/O ports initial setup, this configuration is established soon after reset
* in the initialization code.
*
* The digits have the following meaning:
* 0 - Analog input.
* 1 - Push Pull output 10MHz.
* 2 - Push Pull output 2MHz.
* 3 - Push Pull output 50MHz.
* 4 - Digital input.
* 5 - Open Drain output 10MHz.
* 6 - Open Drain output 2MHz.
* 7 - Open Drain output 50MHz.
* 8 - Digital input with PullUp or PullDown resistor depending on ODR.
* 9 - Alternate Push Pull output 10MHz.
* A - Alternate Push Pull output 2MHz.
* B - Alternate Push Pull output 50MHz.
* C - Reserved.
* D - Alternate Open Drain output 10MHz.
* E - Alternate Open Drain output 2MHz.
* F - Alternate Open Drain output 50MHz.
* Please refer to the STM32 Reference Manual for details.
*/
#define PIN_MODE_INPUT(n) (0 << ((n) * 2))
#define PIN_MODE_OUTPUT(n) (1 << ((n) * 2))
#define PIN_MODE_ALTERNATE(n) (2 << ((n) * 2))
#define PIN_MODE_ANALOG(n) (3 << ((n) * 2))
#define PIN_OTYPE_PUSHPULL(n) (0 << (n))
#define PIN_OTYPE_OPENDRAIN(n) (1 << (n))
#define PIN_OSPEED_400K(n) (0 << ((n) * 2))
#define PIN_OSPEED_2M(n) (1 << ((n) * 2))
#define PIN_OSPEED_10M(n) (2 << ((n) * 2))
#define PIN_OSPEED_40M(n) (3 << ((n) * 2))
#define PIN_PUDR_FLOATING(n) (0 << ((n) * 2))
#define PIN_PUDR_PULLUP(n) (1 << ((n) * 2))
#define PIN_PUDR_PULLDOWN(n) (2 << ((n) * 2))
/*
* Port A setup.
* Everything input with pull-up except:
* PA0 - Normal input (BUTTON).
* PA2 - Alternate output (USART2 TX).
* PA3 - Normal input (USART2 RX).
* PA4 - Push pull output (SPI1 NSS), initially high state.
* PA5 - Alternate output (SPI1 SCK).
* PA6 - Normal input (SPI1 MISO).
* PA7 - Alternate output (SPI1 MOSI).
* PA9 - Alternate output (USART1 TX).
* PA10 - Normal input (USART1 RX).
* All input with pull-up except:
* PA0 - GPIOA_BUTTON (input floating).
* PA13 - JTMS/SWDAT (alternate 0).
* PA14 - JTCK/SWCLK (alternate 0).
* PA15 - JTDI (alternate 0).
*/
#define VAL_GPIOACRL 0xB4B34B84 /* PA7...PA0 */
#define VAL_GPIOACRH 0x888884B8 /* PA15...PA8 */
#define VAL_GPIOAODR 0xFFFFFFFF
#define VAL_GPIOA_MODER (PIN_MODE_INPUT(GPIOA_BUTTON) | \
PIN_MODE_ALTERNATE(13) | \
PIN_MODE_ALTERNATE(14) | \
PIN_MODE_ALTERNATE(15))
#define VAL_GPIOA_OTYPER 0x00000000
#define VAL_GPIOA_OSPEEDR 0xFFFFFFFF
#define VAL_GPIOA_PUPDR (~(PIN_PUDR_FLOATING(GPIOA_BUTTON) | \
PIN_PUDR_FLOATING(13) | \
PIN_PUDR_FLOATING(14) | \
PIN_PUDR_FLOATING(15)))
#define VAL_GPIOA_ODR 0xFFFFFFFF
/*
* Port B setup.
* Everything input with pull-up except:
* PB12 - Push pull output (SPI2 NSS), initially high state.
* PB13 - Alternate output (SPI2 SCK).
* PB14 - Normal input (SPI2 MISO).
* PB15 - Alternate output (SPI2 MOSI).
* All input with pull-up except:
* PB3 - JTDO (alternate 0).
* PB4 - JNTRST (alternate 0).
* PB6 - GPIOB_LED4 (output push-pull).
* PB7 - GPIOB_LED3 (output push-pull).
*/
#define VAL_GPIOBCRL 0x88888888 /* PB7...PB0 */
#define VAL_GPIOBCRH 0xB4B38888 /* PB15...PB8 */
#define VAL_GPIOBODR 0xFFFFFFFF
#define VAL_GPIOB_MODER (PIN_MODE_ALTERNATE(3) | \
PIN_MODE_ALTERNATE(4) | \
PIN_MODE_OUTPUT(GPIOB_LED4) | \
PIN_MODE_OUTPUT(GPIOB_LED3))
#define VAL_GPIOB_OTYPER 0x00000000
#define VAL_GPIOB_OSPEEDR 0xFFFFFFFF
#define VAL_GPIOB_PUPDR (~(PIN_PUDR_FLOATING(3) | \
PIN_PUDR_FLOATING(4) | \
PIN_PUDR_FLOATING(GPIOB_LED4) | \
PIN_PUDR_FLOATING(GPIOB_LED3)))
#define VAL_GPIOB_ODR 0xFFFFFFFF
/*
* Port C setup.
* Everything input with pull-up except:
* PC8 - Push-pull output (LED4), initially low state.
* PC9 - Push-pull output (LED3), initially low state.
* All input with pull-up except:
* PC13 - OSC32_OUT (input floating).
* PC14 - OSC32_IN (input floating).
*/
#define VAL_GPIOCCRL 0x88888888 /* PC7...PC0 */
#define VAL_GPIOCCRH 0x88888833 /* PC15...PC8 */
#define VAL_GPIOCODR 0xFFFFFCFF
#define VAL_GPIOC_MODER 0x00000000
#define VAL_GPIOC_OTYPER 0x00000000
#define VAL_GPIOC_OSPEEDR 0xFFFFFFFF
#define VAL_GPIOC_PUPDR (~(PIN_PUDR_FLOATING(15) | \
PIN_PUDR_FLOATING(14)))
#define VAL_GPIOC_ODR 0xFFFFFFFF
/*
* Port D setup.
* Everything input with pull-up except:
* PD0 - Normal input (XTAL).
* PD1 - Normal input (XTAL).
* All input with pull-up.
*/
#define VAL_GPIODCRL 0x88888844 /* PD7...PD0 */
#define VAL_GPIODCRH 0x88888888 /* PD15...PD8 */
#define VAL_GPIODODR 0xFFFFFFFF
#define VAL_GPIOD_MODER 0x00000000
#define VAL_GPIOD_OTYPER 0x00000000
#define VAL_GPIOD_OSPEEDR 0xFFFFFFFF
#define VAL_GPIOD_PUPDR 0xFFFFFFFF
#define VAL_GPIOD_ODR 0xFFFFFFFF
/*
* Port E setup.
* Everything input with pull-up except:
* All input with pull-up.
*/
#define VAL_GPIOECRL 0x88888888 /* PE7...PE0 */
#define VAL_GPIOECRH 0x88888888 /* PE15...PE8 */
#define VAL_GPIOEODR 0xFFFFFFFF
#define VAL_GPIOE_MODER 0x00000000
#define VAL_GPIOE_OTYPER 0x00000000
#define VAL_GPIOE_OSPEEDR 0xFFFFFFFF
#define VAL_GPIOE_PUPDR 0xFFFFFFFF
#define VAL_GPIOE_ODR 0xFFFFFFFF
/*
* Port H setup.
* All input with pull-up.
*/
#define VAL_GPIOH_MODER 0x00000000
#define VAL_GPIOH_OTYPER 0x00000000
#define VAL_GPIOH_OSPEEDR 0xFFFFFFFF
#define VAL_GPIOH_PUPDR 0xFFFFFFFF
#define VAL_GPIOH_ODR 0xFFFFFFFF
#if !defined(_FROM_ASM_)
#ifdef __cplusplus

View File

@ -35,13 +35,6 @@
/* Driver constants. */
/*===========================================================================*/
/**
* @brief Bits in a mode word dedicated as mode selector.
* @details The other bits are not defined and may be used as device-specific
* option bits.
*/
#define PAL_MODE_MASK 0x1F
/**
* @brief After reset state.
* @details The state itself is not specified and is architecture dependent,
@ -516,7 +509,7 @@ extern "C" {
#endif
ioportmask_t palReadBus(IOBus *bus);
void palWriteBus(IOBus *bus, ioportmask_t bits);
void palSetBusMode(IOBus *bus, uint_fast8_t mode);
void palSetBusMode(IOBus *bus, iomode_t mode);
#ifdef __cplusplus
}
#endif

View File

@ -20,7 +20,7 @@
/*
* Parts of this files have been modified in ChibiOS/RT in order to fix
* some code quality issues.
* some code quality issues and conflicting declarations.
*/
/**************************************************************************//**
@ -1106,7 +1106,7 @@ static __INLINE void __CLREX() { __ASM ("clrex"); }
*
* Return the actual process stack pointer
*/
extern uint32_t __get_PSP(void);
//extern uint32_t __get_PSP(void);
/**
* @brief Set the Process Stack Pointer
@ -1116,7 +1116,7 @@ extern uint32_t __get_PSP(void);
* Assign the value ProcessStackPointer to the MSP
* (process stack pointer) Cortex processor register
*/
extern void __set_PSP(uint32_t topOfProcStack);
//extern void __set_PSP(uint32_t topOfProcStack);
/**
* @brief Return the Main Stack Pointer
@ -1126,7 +1126,7 @@ extern void __set_PSP(uint32_t topOfProcStack);
* Return the current value of the MSP (main stack pointer)
* Cortex processor register
*/
extern uint32_t __get_MSP(void);
//extern uint32_t __get_MSP(void);
/**
* @brief Set the Main Stack Pointer
@ -1136,7 +1136,7 @@ extern uint32_t __get_MSP(void);
* Assign the value mainStackPointer to the MSP
* (main stack pointer) Cortex processor register
*/
extern void __set_MSP(uint32_t topOfMainStack);
//extern void __set_MSP(uint32_t topOfMainStack);
/**
* @brief Reverse byte order in unsigned short value
@ -1146,7 +1146,7 @@ extern void __set_MSP(uint32_t topOfMainStack);
*
* Reverse byte order in unsigned short value
*/
extern uint32_t __REV16(uint16_t value);
//extern uint32_t __REV16(uint16_t value);
/**
* @brief Reverse bit order of value
@ -1156,7 +1156,7 @@ extern uint32_t __REV16(uint16_t value);
*
* Reverse bit order of value
*/
extern uint32_t __RBIT(uint32_t value);
//extern uint32_t __RBIT(uint32_t value);
/**
* @brief LDR Exclusive (8 bit)
@ -1197,7 +1197,7 @@ extern uint32_t __LDREXW(uint32_t *addr);
*
* Exclusive STR command for 8 bit values
*/
extern uint32_t __STREXB(uint8_t value, uint8_t *addr);
//extern uint32_t __STREXB(uint8_t value, uint8_t *addr);
/**
* @brief STR Exclusive (16 bit)
@ -1208,7 +1208,7 @@ extern uint32_t __STREXB(uint8_t value, uint8_t *addr);
*
* Exclusive STR command for 16 bit values
*/
extern uint32_t __STREXH(uint16_t value, uint16_t *addr);
//extern uint32_t __STREXH(uint16_t value, uint16_t *addr);
/**
* @brief STR Exclusive (32 bit)

View File

@ -59,10 +59,10 @@
void hal_lld_init(void) {
/* Reset of all peripherals.*/
RCC->APB1RSTR = 0xFFFFFFFF;
RCC->APB2RSTR = 0xFFFFFFFF;
RCC->APB1RSTR = 0;
RCC->APB2RSTR = 0;
// RCC->APB1RSTR = 0xFFFFFFFF;
// RCC->APB2RSTR = 0xFFFFFFFF;
// RCC->APB1RSTR = 0;
// RCC->APB2RSTR = 0;
/* SysTick initialization using the system clock.*/
SysTick->LOAD = STM32_HCLK / CH_FREQUENCY - 1;
@ -129,8 +129,12 @@ void stm32_clock_init(void) {
#endif
#if STM32_LSE_ENABLED
/* LSE activation.*/
/* LSE activation, have to unlock the register.*/
if ((RCC->CSR & RCC_CSR_LSEON) == 0) {
PWR->CR |= PWR_CR_DBP;
RCC->CSR |= RCC_CSR_LSEON;
PWR->CR &= ~PWR_CR_DBP;
}
while ((RCC->CSR & RCC_CSR_LSERDY) == 0)
; /* Waits until LSE is stable. */
#endif

View File

@ -63,6 +63,7 @@
#define STM32_VOS_1P5 (2 << 11) /**< Core voltage 1.5 Volts. */
#define STM32_VOS_1P8 (3 << 11) /**< Core voltage 1.8 Volts. */
/* RCC_CR register bits definitions.*/
#define STM32_RTCPRE_MASK (3 << 29) /**< RTCPRE mask. */
#define STM32_RTCPRE_DIV2 (0 << 29) /**< HSE divided by 2. */
#define STM32_RTCPRE_DIV4 (1 << 29) /**< HSE divided by 4. */

View File

@ -0,0 +1,186 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011 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/pal_lld.c
* @brief STM32 GPIO low level driver code.
*
* @addtogroup PAL
* @{
*/
#include "ch.h"
#include "hal.h"
#if HAL_USE_PAL || defined(__DOXYGEN__)
#if STM32_HAS_GPIOG
#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)
#elif STM32_HAS_GPIOE
#define APB2_EN_MASK (RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN | \
RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | \
RCC_APB2ENR_IOPEEN | RCC_APB2ENR_AFIOEN)
#else
#define APB2_EN_MASK (RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN | \
RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | \
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
*
* @notapi
*/
void _pal_lld_init(const PALConfig *config) {
/*
* Enables the GPIO related clocks.
*/
RCC->APB2ENR |= APB2_EN_MASK;
/*
* Initial GPIO setup.
*/
GPIOA->ODR = config->PAData.odr;
GPIOA->CRH = config->PAData.crh;
GPIOA->CRL = config->PAData.crl;
GPIOB->ODR = config->PBData.odr;
GPIOB->CRH = config->PBData.crh;
GPIOB->CRL = config->PBData.crl;
GPIOC->ODR = config->PCData.odr;
GPIOC->CRH = config->PCData.crh;
GPIOC->CRL = config->PCData.crl;
GPIOD->ODR = config->PDData.odr;
GPIOD->CRH = config->PDData.crh;
GPIOD->CRL = config->PDData.crl;
#if STM32_HAS_GPIOE || defined(__DOXYGEN__)
GPIOE->ODR = config->PEData.odr;
GPIOE->CRH = config->PEData.crh;
GPIOE->CRL = config->PEData.crl;
#if STM32_HAS_GPIOF || defined(__DOXYGEN__)
GPIOF->ODR = config->PFData.odr;
GPIOF->CRH = config->PFData.crh;
GPIOF->CRL = config->PFData.crl;
#if STM32_HAS_GPIOG || defined(__DOXYGEN__)
GPIOG->ODR = config->PGData.odr;
GPIOG->CRH = config->PGData.crh;
GPIOG->CRL = config->PGData.crl;
#endif
#endif
#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
*
* @notapi
*/
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 /* HAL_USE_PAL */
/** @} */

View File

@ -0,0 +1,437 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011 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/pal_lld.h
* @brief STM32 GPIO low level driver header.
*
* @addtogroup PAL
* @{
*/
#ifndef _PAL_LLD_H_
#define _PAL_LLD_H_
#if HAL_USE_PAL || defined(__DOXYGEN__)
/*===========================================================================*/
/* Unsupported modes and specific modes */
/*===========================================================================*/
#undef PAL_MODE_RESET
#undef PAL_MODE_UNCONNECTED
#undef PAL_MODE_INPUT
#undef PAL_MODE_INPUT_PULLUP
#undef PAL_MODE_INPUT_PULLDOWN
#undef PAL_MODE_INPUT_ANALOG
#undef PAL_MODE_OUTPUT_PUSHPULL
#undef PAL_MODE_OUTPUT_OPENDRAIN
#define PAL_STM32_MODE_MASK (3 >> 0)
#define PAL_STM32_MODE_INPUT (0 >> 0)
#define PAL_STM32_MODE_OUTPUT (1 >> 0)
#define PAL_STM32_MODE_ALTERNATE (2 >> 0)
#define PAL_STM32_MODE_ANALOG (3 >> 0)
#define PAL_STM32_OTYPE_MASK (1 >> 2)
#define PAL_STM32_OTYPE_PUSHPULL (0 >> 2)
#define PAL_STM32_OTYPE_OPENDRAIN (1 >> 2)
#define PAL_STM32_OSPEED_MASK (3 >> 3)
#define PAL_STM32_OSPEED_400K (0 >> 3)
#define PAL_STM32_OSPEED_2M (1 >> 3)
#define PAL_STM32_OSPEED_10M (2 >> 3)
#define PAL_STM32_OSPEED_40M (3 >> 3)
#define PAL_STM32_PUDR_MASK (3 >> 5)
#define PAL_STM32_PUDR_FLOATING (0 >> 5)
#define PAL_STM32_PUDR_PULLUP (1 >> 5)
#define PAL_STM32_PUDR_PULLDOWN (2 >> 5)
#define PAL_STM32_ALTERNATE_MASK (15 >> 7)
#define PAL_STM32_ALTERNATE(n) ((n) >> 7)
/**
* @brief This mode is implemented as input.
*/
#define PAL_MODE_RESET PAL_STM32_MODE_INPUT
/**
* @brief This mode is implemented as output.
*/
#define PAL_MODE_UNCONNECTED PAL_STM32_MODE_OUTPUT
/**
* @brief Regular input high-Z pad.
*/
#define PAL_MODE_INPUT PAL_STM32_MODE_INPUT
/**
* @brief Input pad with weak pull up resistor.
*/
#define PAL_MODE_INPUT_PULLUP (PAL_STM32_MODE_INPUT | \
PAL_STM32_PUDR_PULLUP)
/**
* @brief Input pad with weak pull down resistor.
*/
#define PAL_MODE_INPUT_PULLDOWN (PAL_STM32_MODE_INPUT | \
PAL_STM32_PUDR_PULLDOWN)
/**
* @brief Analog input mode.
*/
#define PAL_MODE_INPUT_ANALOG PAL_STM32_MODE_ANALOG
/**
* @brief Push-pull output pad.
*/
#define PAL_MODE_OUTPUT_PUSHPULL (PAL_STM32_MODE_OUTPUT | \
PAL_STM32_OTYPE_PUSHPULL)
/**
* @brief Open-drain output pad.
*/
#define PAL_MODE_OUTPUT_OPENDRAIN (PAL_STM32_MODE_OUTPUT | \
PAL_STM32_OTYPE_OPENDRAIN)
/**
* @brief Alternate push-pull output.
*
* @param[in] n alternate function selector
*/
#define PAL_MODE_ALTERNATE_PUSHPULL(n) (PAL_STM32_MODE_ALTERNATE | \
PAL_STM32_OTYPE_PUSHPULL | \
PAL_STM32_ALTERNATE(n))
/**
* @brief Alternate push-pull output.
*
* @param[in] n alternate function selector
*/
#define PAL_MODE_ALTERNATE_OPENDRAIN(n) (PAL_STM32_MODE_ALTERNATE | \
PAL_STM32_OTYPE_OPENDRAIN | \
PAL_STM32_ALTERNATE(n))
/*===========================================================================*/
/* I/O Ports Types and constants. */
/*===========================================================================*/
/**
* @brief GPIO port setup info.
*/
typedef struct {
/** Initial value for MODER register.*/
uint32_t moder;
/** Initial value for OTYPER register.*/
uint32_t otyper;
/** Initial value for OSPEEDR register.*/
uint32_t ospeedr;
/** Initial value for PUPDR register.*/
uint32_t pupdr;
/** Initial value for ODR register.*/
uint32_t odr;
} 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 STM32_HAS_GPIOE || defined(__DOXYGEN__)
/** @brief Port E setup data.*/
stm32_gpio_setup_t PEData;
#endif
#if STM32_HAS_GPIOF || defined(__DOXYGEN__)
/** @brief Port F setup data.*/
stm32_gpio_setup_t PFData;
#endif
#if STM32_HAS_GPIOG || defined(__DOXYGEN__)
/** @brief Port G setup data.*/
stm32_gpio_setup_t PGData;
#endif
#if STM32_HAS_GPIOH || defined(__DOXYGEN__)
/** @brief Port H 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.
* @details 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 Digital I/O modes.
*/
typedef uint32_t iomode_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.
*/
#if STM32_HAS_GPIOA || defined(__DOXYGEN__)
#define IOPORT1 GPIOA
#endif
/**
* @brief GPIO port B identifier.
*/
#if STM32_HAS_GPIOB || defined(__DOXYGEN__)
#define IOPORT2 GPIOB
#endif
/**
* @brief GPIO port C identifier.
*/
#if STM32_HAS_GPIOC || defined(__DOXYGEN__)
#define IOPORT3 GPIOC
#endif
/**
* @brief GPIO port D identifier.
*/
#if STM32_HAS_GPIOD || defined(__DOXYGEN__)
#define IOPORT4 GPIOD
#endif
/**
* @brief GPIO port E identifier.
*/
#if STM32_HAS_GPIOE || defined(__DOXYGEN__)
#define IOPORT5 GPIOE
#endif
/**
* @brief GPIO port F identifier.
*/
#if STM32_HAS_GPIOF || defined(__DOXYGEN__)
#define IOPORT6 GPIOF
#endif
/**
* @brief GPIO port G identifier.
*/
#if STM32_HAS_GPIOG || defined(__DOXYGEN__)
#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.
*
* @notapi
*/
#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.
*
* @notapi
*/
#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.
*
* @notapi
*/
#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
*
* @notapi
*/
#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
*
* @notapi
*/
#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
*
* @notapi
*/
#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.
*
* @notapi
*/
#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
*
* @notapi
*/
#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
*
* @notapi
*/
#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 /* HAL_USE_PAL */
#endif /* _PAL_LLD_H_ */
/** @} */

View File

@ -110,7 +110,7 @@ void palWriteBus(IOBus *bus, ioportmask_t bits) {
*
* @api
*/
void palSetBusMode(IOBus *bus, uint_fast8_t mode) {
void palSetBusMode(IOBus *bus, iomode_t mode) {
chDbgCheck((bus != NULL) &&
(bus->offset < PAL_IOPORTS_WIDTH), "palSetBusMode");