48 #define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE) 53 #define EVCR_OFFSET (AFIO_OFFSET + 0x00) 54 #define EVOE_BitNumber ((uint8_t)0x07) 55 #define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4)) 60 #define MAPR_OFFSET (AFIO_OFFSET + 0x04) 61 #define MII_RMII_SEL_BitNumber ((u8)0x17) 62 #define MAPR_MII_RMII_SEL_BB (PERIPH_BB_BASE + (MAPR_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4)) 65 #define EVCR_PORTPINCONFIG_MASK ((uint16_t)0xFF80) 66 #define LSB_MASK ((uint16_t)0xFFFF) 67 #define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000) 68 #define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF) 69 #define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000) 70 #define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000) 118 else if (GPIOx ==
GPIOB)
123 else if (GPIOx ==
GPIOC)
128 else if (GPIOx ==
GPIOD)
133 else if (GPIOx ==
GPIOE)
138 else if (GPIOx ==
GPIOF)
175 uint32_t currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00;
176 uint32_t tmpreg = 0x00, pinmask = 0x00;
183 currentmode = ((uint32_t)GPIO_InitStruct->
GPIO_Mode) & ((uint32_t)0x0F);
184 if ((((uint32_t)GPIO_InitStruct->
GPIO_Mode) & ((uint32_t)0x10)) != 0x00)
189 currentmode |= (uint32_t)GPIO_InitStruct->
GPIO_Speed;
193 if (((uint32_t)GPIO_InitStruct->
GPIO_Pin & ((uint32_t)0x00FF)) != 0x00)
196 for (pinpos = 0x00; pinpos < 0x08; pinpos++)
198 pos = ((uint32_t)0x01) << pinpos;
200 currentpin = (GPIO_InitStruct->
GPIO_Pin) & pos;
201 if (currentpin == pos)
205 pinmask = ((uint32_t)0x0F) << pos;
208 tmpreg |= (currentmode << pos);
212 GPIOx->
BRR = (((uint32_t)0x01) << pinpos);
219 GPIOx->
BSRR = (((uint32_t)0x01) << pinpos);
228 if (GPIO_InitStruct->
GPIO_Pin > 0x00FF)
231 for (pinpos = 0x00; pinpos < 0x08; pinpos++)
233 pos = (((uint32_t)0x01) << (pinpos + 0x08));
235 currentpin = ((GPIO_InitStruct->
GPIO_Pin) & pos);
236 if (currentpin == pos)
240 pinmask = ((uint32_t)0x0F) << pos;
243 tmpreg |= (currentmode << pos);
247 GPIOx->
BRR = (((uint32_t)0x01) << (pinpos + 0x08));
252 GPIOx->
BSRR = (((uint32_t)0x01) << (pinpos + 0x08));
283 uint8_t bitstatus = 0x00;
295 bitstatus = (uint8_t)Bit_RESET;
310 return ((uint16_t)GPIOx->
IDR);
322 uint8_t bitstatus = 0x00;
333 bitstatus = (uint8_t)Bit_RESET;
348 return ((uint16_t)GPIOx->
ODR);
422 GPIOx->
ODR = PortVal;
434 uint32_t tmp = 0x00010000;
464 uint32_t tmpreg = 0x00;
472 tmpreg |= (uint32_t)GPIO_PortSource << 0x04;
473 tmpreg |= GPIO_PinSource;
551 uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00;
557 if((GPIO_Remap & 0x80000000) == 0x80000000)
559 tmpreg =
AFIO->MAPR2;
576 tmp1 = ((uint32_t)0x03) << tmpmask;
582 tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10));
588 tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10));
591 if((GPIO_Remap & 0x80000000) == 0x80000000)
593 AFIO->MAPR2 = tmpreg;
616 tmp = ((uint32_t)0x0F) << (0x04 * (GPIO_PinSource & (uint8_t)0x03));
617 AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp;
618 AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((uint32_t)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (uint8_t)0x03)));
void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState)
Changes the mapping of the specified pin.
#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE)
#define RCC_APB2Periph_GPIOD
#define IS_GPIO_MODE(MODE)
#define DBGAFR_LOCATION_MASK
void GPIO_Write(GPIO_TypeDef *GPIOx, uint16_t PortVal)
Writes data to the specified GPIO data port.
#define IS_GPIO_REMAP(REMAP)
void GPIO_StructInit(GPIO_InitTypeDef *GPIO_InitStruct)
Fills each GPIO_InitStruct member with its default value.
BitAction
GPIO Bit SET and Bit RESET enumeration.
#define IS_GPIO_ALL_PERIPH(PERIPH)
GPIOSpeed_TypeDef GPIO_Speed
#define RCC_APB2Periph_GPIOB
#define DBGAFR_POSITION_MASK
void assert_param(int val)
#define DBGAFR_NUMBITS_MASK
uint16_t GPIO_ReadInputData(GPIO_TypeDef *GPIOx)
Reads the specified GPIO input data port.
void GPIO_EventOutputCmd(FunctionalState NewState)
Enables or disables the Event Output.
#define IS_FUNCTIONAL_STATE(STATE)
This file contains all the functions prototypes for the GPIO firmware library.
#define RCC_APB2Periph_GPIOG
void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource)
Selects the GPIO pin used as Event output.
void GPIO_DeInit(GPIO_TypeDef *GPIOx)
Deinitializes the GPIOx peripheral registers to their default reset values.
void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface)
Selects the Ethernet media interface.
void GPIO_AFIODeInit(void)
Deinitializes the Alternate Functions (remap, event control and EXTI configuration) registers to thei...
#define IS_GET_GPIO_PIN(PIN)
void GPIO_WriteBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin, BitAction BitVal)
Sets or clears the selected data port bit.
GPIO Init structure definition.
#define IS_GPIO_SPEED(SPEED)
uint16_t GPIO_ReadOutputData(GPIO_TypeDef *GPIOx)
Reads the specified GPIO output data port.
#define RCC_APB2Periph_AFIO
#define RCC_APB2Periph_GPIOA
void GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_InitStruct)
Initializes the GPIOx peripheral according to the specified parameters in the GPIO_InitStruct.
void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource)
Selects the GPIO pin used as EXTI Line.
This file contains all the functions prototypes for the RCC firmware library.
#define RCC_APB2Periph_GPIOE
GPIOMode_TypeDef GPIO_Mode
uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
Reads the specified output data port bit.
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
void GPIO_PinLockConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
Locks GPIO Pins configuration registers.
void GPIO_ResetBits(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
Clears the selected data port bits.
#define IS_GPIO_BIT_ACTION(ACTION)
#define DBGAFR_SWJCFG_MASK
#define EVCR_PORTPINCONFIG_MASK
uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
Reads the specified input port pin.
void GPIO_SetBits(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
Sets the selected data port bits.
#define RCC_APB2Periph_GPIOC
#define RCC_APB2Periph_GPIOF
#define MAPR_MII_RMII_SEL_BB
#define IS_GPIO_PIN_SOURCE(PINSOURCE)
#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE)