forked from Archive/PX4-Autopilot
Add missing STM32 F1 pin remapping definitions
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5180 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
parent
5b51b5e3a4
commit
b58026b8f0
|
@ -739,7 +739,6 @@ static void *httpd_handler(void *arg)
|
||||||
{
|
{
|
||||||
pstate->ht_keepalive = false;
|
pstate->ht_keepalive = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Then handle the next httpd command */
|
/* Then handle the next httpd command */
|
||||||
|
|
||||||
status = httpd_parse(pstate);
|
status = httpd_parse(pstate);
|
||||||
|
|
|
@ -265,48 +265,58 @@
|
||||||
|
|
||||||
/* AF remap and debug I/O configuration register */
|
/* AF remap and debug I/O configuration register */
|
||||||
|
|
||||||
#define AFIO_MAPR_SWJ_CFG_SHIFT (24) /* Bits 26-24: Serial Wire JTAG configuration*/
|
#define AFIO_MAPR_SPI1_REMAP (1 << 0) /* Bit 0: SPI1 remapping */
|
||||||
|
#define AFIO_MAPR_I2C1_REMAP (1 << 1) /* Bit 1: I2C1 remapping */
|
||||||
|
#define AFIO_MAPR_USART1_REMAP (1 << 2) /* Bit 2: USART1 remapping */
|
||||||
|
#define AFIO_MAPR_USART2_REMAP (1 << 3) /* Bit 3: USART2 remapping */
|
||||||
|
#define AFIO_MAPR_USART3_REMAP_SHIFT (4) /* Bits 5-4: USART3 remapping */
|
||||||
|
#define AFIO_MAPR_USART3_REMAP_MASK (3 << AFIO_MAPR_USART3_REMAP_SHIFT)
|
||||||
|
# define AFIO_MAPR_USART3_NOREMAP (0 << AFIO_MAPR_USART3_REMAP_SHIFT) /* 00: No remap */
|
||||||
|
# define AFIO_MAPR_USART3_PARTREMAP (1 << AFIO_MAPR_USART3_REMAP_SHIFT) /* 01: Partial remap */
|
||||||
|
# define AFIO_MAPR_USART3_FULLREMAP (3 << AFIO_MAPR_USART3_REMAP_SHIFT) /* 11: Full remap */
|
||||||
|
#define AFIO_MAPR_TIM1_REMAP_SHIFT (6) /* Bits 7-6: TIM1 remapping */
|
||||||
|
#define AFIO_MAPR_TIM1_REMAP_MASK (3 << AFIO_MAPR_TIM1_REMAP_SHIFT)
|
||||||
|
# define AFIO_MAPR_TIM1_NOREMAP (0 << AFIO_MAPR_TIM1_REMAP_SHIFT) /* 00: No remap */
|
||||||
|
# define AFIO_MAPR_TIM1_PARTREMAP (1 << AFIO_MAPR_TIM1_REMAP_SHIFT) /* 01: Partial remap */
|
||||||
|
# define AFIO_MAPR_TIM1_FULLREMAP (3 << AFIO_MAPR_TIM1_REMAP_SHIFT) /* 11: Full remap */
|
||||||
|
#define AFIO_MAPR_TIM2_REMAP_SHIFT (8) /* Bits 9-8: TIM2 remapping */
|
||||||
|
#define AFIO_MAPR_TIM2_REMAP_MASK (3 << AFIO_MAPR_TIM2_REMAP_SHIFT)
|
||||||
|
# define AFIO_MAPR_TIM2_NOREMAP (0 << AFIO_MAPR_TIM2_REMAP_SHIFT) /* 00: No remap */
|
||||||
|
# define AFIO_MAPR_TIM2_PARTREMAP1 (1 << AFIO_MAPR_TIM2_REMAP_SHIFT) /* 01: Partial remap */
|
||||||
|
# define AFIO_MAPR_TIM2_PARTREMAP2 (2 << AFIO_MAPR_TIM2_REMAP_SHIFT) /* 10: Partial remap */
|
||||||
|
# define AFIO_MAPR_TIM2_FULLREMAP (3 << AFIO_MAPR_TIM2_REMAP_SHIFT) /* 11: Full remap */
|
||||||
|
#define AFIO_MAPR_TIM3_REMAP_SHIFT (10) /* Bits 11-10: TIM3 remapping */
|
||||||
|
#define AFIO_MAPR_TIM3_REMAP_MASK (3 << AFIO_MAPR_TIM3_REMAP_SHIFT)
|
||||||
|
# define AFIO_MAPR_TIM3_NOREMAP (0 << AFIO_MAPR_TIM3_REMAP_SHIFT) /* 00: No remap */
|
||||||
|
# define AFIO_MAPR_TIM3_PARTREMAP (2 << AFIO_MAPR_TIM3_REMAP_SHIFT) /* 10: Partial remap */
|
||||||
|
# define AFIO_MAPR_TIM3_FULLREMAP (3 << AFIO_MAPR_TIM3_REMAP_SHIFT) /* 11: Full remap */
|
||||||
|
#define AFIO_MAPR_TIM4_REMAP (1 << 12) /* Bit 12: TIM4 remapping */
|
||||||
|
#define AFIO_MAPR_CAN1_REMAP_SHIFT (13) /* Bits 14-13: CAN Alternate function remapping */
|
||||||
|
#define AFIO_MAPR_CAN1_REMAP_MASK (3 << AFIO_MAPR_CAN1_REMAP_SHIFT)
|
||||||
|
# define AFIO_MAPR_PA1112 (0 << AFIO_MAPR_CAN1_REMAP_SHIFT) /* 00: CANRX mapped to PA11, CANTX mapped to PA12 */
|
||||||
|
# define AFIO_MAPR_PB89 (2 << AFIO_MAPR_CAN1_REMAP_SHIFT) /* 10: CANRX mapped to PB8, CANTX mapped to PB9 */
|
||||||
|
# define AFIO_MAPR_PD01 (3 << AFIO_MAPR_CAN1_REMAP_SHIFT) /* 11: CANRX mapped to PD0, CANTX mapped to PD1 */
|
||||||
|
#define AFIO_MAPR_PD01_REMAP (1 << 15) /* Bit 15 : Port D0/Port D1 mapping on OSC_IN/OSC_OUT */
|
||||||
|
#define AFIO_MAPR_TIM5CH4_IREMAP (1 << 16) /* Bit 16: TIM5 channel4 internal remap */
|
||||||
|
/* Bits 17-20: Reserved */
|
||||||
|
#ifdef CONFIG_STM32_CONNECTIVITYLINE
|
||||||
|
# define AFIO_MAPR_ETH_REMAP (1 << 21) /* Bit 21: Ethernet MAC I/O remapping */
|
||||||
|
# define AFIO_MAPR_CAN2_REMAP (1 << 22) /* Bit 22: CAN2 I/O remapping */
|
||||||
|
# define AFIO_MAPR_MII_RMII_SEL (1 << 23) /* Bit 23: MII or RMII selection */
|
||||||
|
#endif
|
||||||
|
#define AFIO_MAPR_SWJ_CFG_SHIFT (24) /* Bits 26-24: Serial Wire JTAG configuration */
|
||||||
#define AFIO_MAPR_SWJ_CFG_MASK (7 << AFIO_MAPR_SWJ_CFG_SHIFT)
|
#define AFIO_MAPR_SWJ_CFG_MASK (7 << AFIO_MAPR_SWJ_CFG_SHIFT)
|
||||||
# define AFIO_MAPR_SWJRST (0 << AFIO_MAPR_SWJ_CFG_SHIFT) /* 000: Full SWJ (JTAG-DP + SW-DP): Reset State */
|
# define AFIO_MAPR_SWJRST (0 << AFIO_MAPR_SWJ_CFG_SHIFT) /* 000: Full SWJ (JTAG-DP + SW-DP): Reset State */
|
||||||
# define AFIO_MAPR_SWJ (1 << AFIO_MAPR_SWJ_CFG_SHIFT) /* 001: Full SWJ (JTAG-DP + SW-DP) but without JNTRST */
|
# define AFIO_MAPR_SWJ (1 << AFIO_MAPR_SWJ_CFG_SHIFT) /* 001: Full SWJ (JTAG-DP + SW-DP) but without JNTRST */
|
||||||
# define AFIO_MAPR_SWDP (2 << AFIO_MAPR_SWJ_CFG_SHIFT) /* 010: JTAG-DP Disabled and SW-DP Enabled */
|
# define AFIO_MAPR_SWDP (2 << AFIO_MAPR_SWJ_CFG_SHIFT) /* 010: JTAG-DP Disabled and SW-DP Enabled */
|
||||||
# define AFIO_MAPR_DISAB (4 << AFIO_MAPR_SWJ_CFG_SHIFT) /* 100: JTAG-DP Disabled and SW-DP Disabled */
|
# define AFIO_MAPR_DISAB (4 << AFIO_MAPR_SWJ_CFG_SHIFT) /* 100: JTAG-DP Disabled and SW-DP Disabled */
|
||||||
|
/* Bit 27: Reserved */
|
||||||
#ifdef CONFIG_STM32_CONNECTIVITYLINE
|
#ifdef CONFIG_STM32_CONNECTIVITYLINE
|
||||||
# define AFIO_MAPR_MII_RMII_SEL (1 << 23) /* MII or RMII selection */
|
# define AFIO_MAPR_SPI3_REMAP (1 << 28) /* Bit 28: SPI3 remapping */
|
||||||
|
# define AFIO_MAPR_TIM2ITR1_IREMAP (1 << 29) /* Bit 29: TIM2 internal trigger 1 remapping */
|
||||||
|
# define AFIO_MAPR_PTP_PPS_REMAP (1 << 30) /* Bit 30: Ethernet PTP PPS remapping */
|
||||||
#endif
|
#endif
|
||||||
#define AFIO_MAPR_PD01_REMAP (1 << 15) /* Bit 15 : Port D0/Port D1 mapping on OSC_IN/OSC_OUT */
|
/* Bit 31: Reserved */
|
||||||
#define AFIO_MAPR_CAN_REMAP_SHIFT (13) /* Bits 14-13: CAN Alternate function remapping */
|
|
||||||
#define AFIO_MAPR_CAN_REMAP_MASK (3 << AFIO_MAPR_CAN_REMAP_SHIFT)
|
|
||||||
# define AFIO_MAPR_PA1112 (0 << AFIO_MAPR_CAN_REMAP_SHIFT) /* 00: CANRX mapped to PA11, CANTX mapped to PA12 */
|
|
||||||
# define AFIO_MAPR_PB89 (2 << AFIO_MAPR_CAN_REMAP_SHIFT) /* 10: CANRX mapped to PB8, CANTX mapped to PB9 */
|
|
||||||
# define AFIO_MAPR_PD01 (3 << AFIO_MAPR_CAN_REMAP_SHIFT) /* 11: CANRX mapped to PD0, CANTX mapped to PD1 */
|
|
||||||
#define AFIO_MAPR_TIM4_REMAP (1 << 12) /* Bit 12: TIM4 remapping */
|
|
||||||
#define AFIO_MAPR_TIM3_REMAP_SHIFT (10) /* Bits 11-10: TIM3 remapping */
|
|
||||||
#define AFIO_MAPR_TIM3_REMAP_MASK (3 << AFIO_MAPR_TIM3_REMAP_SHIFT)
|
|
||||||
# define AFIO_MAPR_TIM3_NOREMAP (0 << AFIO_MAPR_TIM3_REMAP_SHIFT) /* 00: No remap (CH1/PA6, CH2/PA7, CH3/PB0, CH4/PB1) */
|
|
||||||
# define AFIO_MAPR_TIM3_PARTREMAP (2 << AFIO_MAPR_TIM3_REMAP_SHIFT) /* 10: Partial remap (CH1/PB4, CH2/PB5, CH3/PB0, CH4/PB1) */
|
|
||||||
# define AFIO_MAPR_TIM3_FULLREMAP (3 << AFIO_MAPR_TIM3_REMAP_SHIFT) /* 11: Full remap (CH1/PC6, CH2/PC7, CH3/PC8, CH4/PC9) */
|
|
||||||
#define AFIO_MAPR_TIM2_REMAP_SHIFT (8) /* Bits 9-8: TIM2 remapping */
|
|
||||||
#define AFIO_MAPR_TIM2_REMAP_MASK (3 << AFIO_MAPR_TIM2_REMAP_SHIFT)
|
|
||||||
# define AFIO_MAPR_TIM2_NOREMAP (0 << AFIO_MAPR_TIM2_REMAP_SHIFT) /* 00: No remap (CH1/ETR/PA0, CH2/PA1, CH3/PA2, CH4/PA3) */
|
|
||||||
# define AFIO_MAPR_TIM2_PARTREMAP1 (1 << AFIO_MAPR_TIM2_REMAP_SHIFT) /* 01: Partial remap (CH1/ETR/PA15, CH2/PB3, CH3/PA2, CH4/PA3) */
|
|
||||||
# define AFIO_MAPR_TIM2_PARTREMAP2 (2 << AFIO_MAPR_TIM2_REMAP_SHIFT) /* 10: Partial remap (CH1/ETR/PA0, CH2/PA1, CH3/PB10, CH4/PB11) */
|
|
||||||
# define AFIO_MAPR_TIM2_FULLREMAP (3 << AFIO_MAPR_TIM2_REMAP_SHIFT) /* 11: Full remap (CH1/ETR/PA15, CH2/PB3, CH3/PB10, CH4/PB11) */
|
|
||||||
#define AFIO_MAPR_TIM1_REMAP_SHIFT (6) /* Bits 7-6: TIM1 remapping */
|
|
||||||
#define AFIO_MAPR_TIM1_REMAP_MASK (3 << AFIO_MAPR_TIM1_REMAP_SHIFT)
|
|
||||||
# define AFIO_MAPR_TIM1_NOREMAP (0 << AFIO_MAPR_TIM1_REMAP_SHIFT) /* 00: No remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PB12, CH1N/PB13, CH2N/PB14, CH3N/PB15) */
|
|
||||||
# define AFIO_MAPR_TIM1_PARTREMAP (1 << AFIO_MAPR_TIM1_REMAP_SHIFT) /* 01: Partial remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PA6, CH1N/PA7, CH2N/PB0, CH3N/PB1) */
|
|
||||||
# define AFIO_MAPR_TIM1_FULLREMAP (3 << AFIO_MAPR_TIM1_REMAP_SHIFT) /* 11: Full remap (ETR/PE7, CH1/PE9, CH2/PE11, CH3/PE13, CH4/PE14, BKIN/PE15, CH1N/PE8, CH2N/PE10, CH3N/PE12) */
|
|
||||||
#define AFIO_MAPR_USART3_REMAP_SHIFT (6) /* Bits 5-4: USART3 remapping */
|
|
||||||
#define AFIO_MAPR_USART3_REMAP_MASK (3 << AFIO_MAPR_USART3_REMAP_SHIFT)
|
|
||||||
# define AFIO_MAPR_USART3_NOREMAP (0 << AFIO_MAPR_USART3_REMAP_SHIFT) /* 00: No remap (TX/PB10, RX/PB11, CK/PB12, CTS/PB13, RTS/PB14) */
|
|
||||||
# define AFIO_MAPR_USART3_PARTREMAP (1 << AFIO_MAPR_USART3_REMAP_SHIFT) /* 01: Partial remap (TX/PC10, RX/PC11, CK/PC12, CTS/PB13, RTS/PB14) */
|
|
||||||
# define AFIO_MAPR_USART3_FULLREMAP (3 << AFIO_MAPR_USART3_REMAP_SHIFT) /* 11: Full remap (TX/PD8, RX/PD9, CK/PD10, CTS/PD11, RTS/PD12) */
|
|
||||||
#define AFIO_MAPR_USART2_REMAP (1 << 3) /* Bit 3: USART2 remapping */
|
|
||||||
#define AFIO_MAPR_USART1_REMAP (1 << 2) /* Bit 2: USART1 remapping */
|
|
||||||
#define AFIO_MAPR_I2C1_REMAP (1 << 1) /* Bit 1: I2C1 remapping */
|
|
||||||
#define AFIO_MAPR_SPI1_REMAP (1 << 0) /* Bit 0: SPI1 remapping */
|
|
||||||
|
|
||||||
/* External interrupt configuration register 1 */
|
/* External interrupt configuration register 1 */
|
||||||
|
|
||||||
#define AFIO_EXTICR_PORT_MASK (0x0f)
|
#define AFIO_EXTICR_PORT_MASK (0x0f)
|
||||||
|
|
|
@ -124,14 +124,27 @@ static inline void stm32_gpioremap(void)
|
||||||
|
|
||||||
uint32_t val = 0;
|
uint32_t val = 0;
|
||||||
|
|
||||||
#ifdef CONFIG_STM32_JTAG_FULL_ENABLE
|
#ifdef CONFIG_STM32_SPI1_REMAP
|
||||||
/* The reset default */
|
val |= AFIO_MAPR_SPI1_REMAP;
|
||||||
#elif CONFIG_STM32_JTAG_NOJNTRST_ENABLE
|
#endif
|
||||||
val |= AFIO_MAPR_SWJ; /* enabled but without JNTRST */
|
#ifdef CONFIG_STM32_SPI3_REMAP
|
||||||
#elif CONFIG_STM32_JTAG_SW_ENABLE
|
#endif
|
||||||
val |= AFIO_MAPR_SWDP; /* set JTAG-DP disabled and SW-DP enabled */
|
|
||||||
#else
|
#ifdef CONFIG_STM32_I2C1_REMAP
|
||||||
val |= AFIO_MAPR_DISAB; /* set JTAG-DP and SW-DP Disabled */
|
val |= AFIO_MAPR_I2C1_REMAP;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32_USART1_REMAP
|
||||||
|
val |= AFIO_MAPR_USART1_REMAP;
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_STM32_USART2_REMAP
|
||||||
|
val |= AFIO_MAPR_USART2_REMAP;
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_STM32_USART3_FULL_REMAP
|
||||||
|
val |= AFIO_MAPR_USART3_FULLREMAP;
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_STM32_USART3_PARTIAL_REMAP
|
||||||
|
val |= AFIO_MAPR_USART3_PARTREMAP;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CONFIG_STM32_TIM1_FULL_REMAP
|
#ifdef CONFIG_STM32_TIM1_FULL_REMAP
|
||||||
|
@ -159,35 +172,29 @@ static inline void stm32_gpioremap(void)
|
||||||
val |= AFIO_MAPR_TIM4_REMAP;
|
val |= AFIO_MAPR_TIM4_REMAP;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CONFIG_STM32_USART1_REMAP
|
|
||||||
val |= AFIO_MAPR_USART1_REMAP;
|
|
||||||
#endif
|
|
||||||
#ifdef CONFIG_STM32_USART2_REMAP
|
|
||||||
val |= AFIO_MAPR_USART2_REMAP;
|
|
||||||
#endif
|
|
||||||
#ifdef CONFIG_STM32_USART3_FULL_REMAP
|
|
||||||
val |= AFIO_MAPR_USART3_FULLREMAP;
|
|
||||||
#endif
|
|
||||||
#ifdef CONFIG_STM32_USART3_PARTIAL_REMAP
|
|
||||||
val |= AFIO_MAPR_USART3_PARTREMAP;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CONFIG_STM32_SPI1_REMAP
|
|
||||||
val |= AFIO_MAPR_SPI1_REMAP;
|
|
||||||
#endif
|
|
||||||
#ifdef CONFIG_STM32_SPI3_REMAP
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CONFIG_STM32_I2C1_REMAP
|
|
||||||
val |= AFIO_MAPR_I2C1_REMAP;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CONFIG_STM32_CAN1_REMAP1
|
#ifdef CONFIG_STM32_CAN1_REMAP1
|
||||||
val |= AFIO_MAPR_PB89;
|
val |= AFIO_MAPR_PB89;
|
||||||
#endif
|
#endif
|
||||||
#ifdef CONFIG_STM32_CAN1_REMAP2
|
#ifdef CONFIG_STM32_CAN1_REMAP2
|
||||||
val |= AFIO_MAPR_PD01;
|
val |= AFIO_MAPR_PD01;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef CONFIG_STM32_CAN2_REMAP /* Connectivity line only */
|
||||||
|
val |= AFIO_MAPR_CAN2_REMAP;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32_ETH_REMAP /* Connectivity line only */
|
||||||
|
val |= AFIO_MAPR_ETH_REMAP;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32_JTAG_FULL_ENABLE
|
||||||
|
/* The reset default */
|
||||||
|
#elif CONFIG_STM32_JTAG_NOJNTRST_ENABLE
|
||||||
|
val |= AFIO_MAPR_SWJ; /* enabled but without JNTRST */
|
||||||
|
#elif CONFIG_STM32_JTAG_SW_ENABLE
|
||||||
|
val |= AFIO_MAPR_SWDP; /* set JTAG-DP disabled and SW-DP enabled */
|
||||||
|
#else
|
||||||
|
val |= AFIO_MAPR_DISAB; /* set JTAG-DP and SW-DP Disabled */
|
||||||
|
#endif
|
||||||
|
|
||||||
putreg32(val, STM32_AFIO_MAPR);
|
putreg32(val, STM32_AFIO_MAPR);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -65,6 +65,34 @@
|
||||||
/* Shenzhou GPIO Configuration **********************************************************************/
|
/* Shenzhou GPIO Configuration **********************************************************************/
|
||||||
|
|
||||||
/* STM3240G-EVAL GPIOs ******************************************************************************/
|
/* STM3240G-EVAL GPIOs ******************************************************************************/
|
||||||
|
/* Ethernet
|
||||||
|
*
|
||||||
|
* -- ---- -------------- ----------------------------------------------------------
|
||||||
|
* PN NAME SIGNAL NOTES
|
||||||
|
* -- ---- -------------- ----------------------------------------------------------
|
||||||
|
* 24 PA1 MII_RX_CLK Ethernet PHY NOTE: Despite the MII labeling of these
|
||||||
|
* RMII_REF_CLK Ethernet PHY signals, the DM916AEP is actually configured
|
||||||
|
* 25 PA2 MII_MDIO Ethernet PHY to work in RMII mode.
|
||||||
|
* 48 PB11 MII_TX_EN Ethernet PHY
|
||||||
|
* 51 PB12 MII_TXD0 Ethernet PHY
|
||||||
|
* 52 PB13 MII_TXD1 Ethernet PHY
|
||||||
|
* 16 PC1 MII_MDC Ethernet PHY
|
||||||
|
* 34 PC5 MII_INT Ethernet PHY
|
||||||
|
* 55 PD8 MII_RX_DV Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP
|
||||||
|
* 55 PD8 RMII_CRSDV Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP
|
||||||
|
* 56 PD9 MII_RXD0 Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP
|
||||||
|
* 57 PD10 MII_RXD1 Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP
|
||||||
|
*
|
||||||
|
* The board desdign can support a 50MHz external clock to drive the PHY
|
||||||
|
* (U9). However, on my board, U9 is not present.
|
||||||
|
*
|
||||||
|
* 67 PA8 MCO DM9161AEP
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32_ETHMAC
|
||||||
|
# define GPIO_MII_INT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN5)
|
||||||
|
#endif
|
||||||
|
|
||||||
/* Wireless
|
/* Wireless
|
||||||
*
|
*
|
||||||
* -- ---- -------------- -------------------------------------------------------------------
|
* -- ---- -------------- -------------------------------------------------------------------
|
||||||
|
|
Loading…
Reference in New Issue