48 #include "stm32f4xx_rcc.h" 62 #define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE) 66 #define PMC_OFFSET (SYSCFG_OFFSET + 0x04) 67 #define MII_RMII_SEL_BitNumber ((uint8_t)0x17) 68 #define PMC_MII_RMII_SEL_BB (PERIPH_BB_BASE + (PMC_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4)) 72 #define CMPCR_OFFSET (SYSCFG_OFFSET + 0x20) 73 #define CMP_PD_BitNumber ((uint8_t)0x00) 74 #define CMPCR_CMP_PD_BB (PERIPH_BB_BASE + (CMPCR_OFFSET * 32) + (CMP_PD_BitNumber * 4)) 112 SYSCFG->MEMRMP = SYSCFG_MemoryRemap;
136 tmp = ((uint32_t)0x0F) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03));
137 SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] &= ~tmp;
138 SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] |= (((uint32_t)EXTI_PortSourceGPIOx) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03)));
void SYSCFG_CompensationCellCmd(FunctionalState NewState)
Enables or disables the I/O Compensation Cell.
#define IS_EXTI_PIN_SOURCE(PINSOURCE)
void assert_param(int val)
#define IS_FUNCTIONAL_STATE(STATE)
This file contains all the functions prototypes for the SYSCFG firmware library.
#define IS_SYSCFG_MEMORY_REMAP_CONFING(REMAP)
#define RCC_APB2Periph_SYSCFG
FlagStatus SYSCFG_GetCompensationCellStatus(void)
Checks whether the I/O Compensation Cell ready flag is set or not.
#define IS_EXTI_PORT_SOURCE(PORTSOURCE)
#define SYSCFG_CMPCR_READY
void SYSCFG_ETH_MediaInterfaceConfig(uint32_t SYSCFG_ETH_MediaInterface)
Selects the ETHERNET media interface.
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
void SYSCFG_MemoryRemapConfig(uint8_t SYSCFG_MemoryRemap)
Changes the mapping of the specified pin.
void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex)
Selects the GPIO pin used as EXTI Line.
void SYSCFG_DeInit(void)
Deinitializes the Alternate Functions (remap and EXTI configuration) registers to their default reset...
#define PMC_MII_RMII_SEL_BB