summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-27 15:42:07 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-27 15:42:07 +0000
commitb1374fdcf46709b5e014dc9dbfc78e0394e8d6aa (patch)
tree1a350b3fb02cc7bddae7d11cb54cdcb6a0629af5 /nuttx/arch/arm
parentcc5f5a4daa8d8928bf85f6dc653602133511586f (diff)
downloadpx4-nuttx-b1374fdcf46709b5e014dc9dbfc78e0394e8d6aa.tar.gz
px4-nuttx-b1374fdcf46709b5e014dc9dbfc78e0394e8d6aa.tar.bz2
px4-nuttx-b1374fdcf46709b5e014dc9dbfc78e0394e8d6aa.zip
Add support for the ISOTEL NetClamps VSN board
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3321 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/common/up_idle.c8
-rwxr-xr-xnuttx/arch/arm/src/stm32/chip.h40
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_flash.h4
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_internal.h6
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_rcc.c59
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f103re_pinmap.h330
6 files changed, 418 insertions, 29 deletions
diff --git a/nuttx/arch/arm/src/common/up_idle.c b/nuttx/arch/arm/src/common/up_idle.c
index 4927ce0e8..ba6affb0e 100644
--- a/nuttx/arch/arm/src/common/up_idle.c
+++ b/nuttx/arch/arm/src/common/up_idle.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/common/up_idle.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -83,5 +83,11 @@ void up_idle(void)
sched_process_timer();
#endif
+
+ /* Sleep until an interrupt occurs to save power */
+
+#if 0
+ asm("WFI"); /* For example */
+#endif
}
diff --git a/nuttx/arch/arm/src/stm32/chip.h b/nuttx/arch/arm/src/stm32/chip.h
index f6430b2c1..f916f1682 100755
--- a/nuttx/arch/arm/src/stm32/chip.h
+++ b/nuttx/arch/arm/src/stm32/chip.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,11 +48,11 @@
/* Get customizations for each supported chip (only the STM32F103Z right now) */
-#if defined(CONFIG_ARCH_CHIP_STM32F103ZET6)
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+#if defined(CONFIG_ARCH_CHIP_STM32F103ZET6)
+# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
-# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
+# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
# define STM32_NATIM 1 /* One advanced timers TIM1 */
# define STM32_NGTIM 4 /* General timers TIM2,3,4,5 */
# define STM32 NBTIM 0 /* No basic timers */
@@ -67,11 +67,32 @@
# define STM32_NDAC 0 /* No DAC */
# define STM32_NCRC 0 /* No CRC */
# define STM32_NTHERNET 0 /* No ethernet */
+
+#elif defined(CONFIG_ARCH_CHIP_STM32F103RET6)
+# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
+# define STM32_NATIM 1 /* One advanced timers TIM1 */
+# define STM32_NGTIM 4 /* General timers TIM2,3,4,5 */
+# define STM32 NBTIM 0 /* No basic timers */
+# define STM32_NDMA 2 /* DMA1-2 */
+# define STM32_NSPI 2 /* SPI1-2 */
+# define STM32_NUSART 3 /* USART1-3 */
+# define STM32_NI2C 2 /* I2C1-2 */
+# define STM32_NCAN 1 /* bxCAN1 */
+# define STM32_NSDIO 1 /* SDIO */
+# define STM32_NGPIO 112 /* GPIOA-G */
+# define STM32_NADC 1 /* ADC1 */
+# define STM32_NDAC 0 /* No DAC */
+# define STM32_NCRC 0 /* No CRC */
+# define STM32_NTHERNET 0 /* No ethernet */
+
#elif defined(CONFIG_ARCH_CHIP_STM32F107VC)
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
-# define CONFIG_STM32_CONNECTIVITYLINE 1 /* STM32F105x and STM32F107x */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# define CONFIG_STM32_CONNECTIVITYLINE 1 /* STM32F105x and STM32F107x */
# define STM32_NATIM 1 /* One advanced timers TIM1 */
# define STM32_NGTIM 4 /* General timers TIM2,3,4,5 */
# define STM32 NBTIM 2 /* Two basic timers, TIM6-7 */
@@ -86,6 +107,7 @@
# define STM32_NDAC 2 /* DAC1-2 */
# define STM32_NCRC 1 /* CRC */
# define STM32_NTHERNET 1 /* 100/100 Ethernet MAC */
+
#else
# error "Unsupported STM32 chip"
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_flash.h b/nuttx/arch/arm/src/stm32/stm32_flash.h
index 414641aa1..19ee5e172 100755
--- a/nuttx/arch/arm/src/stm32/stm32_flash.h
+++ b/nuttx/arch/arm/src/stm32/stm32_flash.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_flash.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -79,7 +79,7 @@
#define ACR_LATENCY_SHIFT (0)
#define ACR_LATENCY_MASK (7 << ACR_LATENCY_SHIFT)
# define ACR_LATENCY_0 (0 << ACR_LATENCY_SHIFT) /* FLASH Zero Latency cycle */
-# define ACR_LATENCY_1 (1 << ACR_LATENCY_SHIFT)) /* FLASH One Latency cycle */
+# define ACR_LATENCY_1 (1 << ACR_LATENCY_SHIFT) /* FLASH One Latency cycle */
# define ACR_LATENCY_2 (2 << ACR_LATENCY_SHIFT) /* FLASH Two Latency cycles */
#define ACR_HLFCYA (1 << 3) /* FLASH half cycle access */
#define ACR_PRTFBE (1 << 4) /* FLASH prefetch enable */
diff --git a/nuttx/arch/arm/src/stm32/stm32_internal.h b/nuttx/arch/arm/src/stm32/stm32_internal.h
index a98d579dd..f5094d50a 100755
--- a/nuttx/arch/arm/src/stm32/stm32_internal.h
+++ b/nuttx/arch/arm/src/stm32/stm32_internal.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_internal.h
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -167,9 +167,11 @@
* include that header file. NOTE: You can get the chip-specific pin-mapping info
* from the chip datasheet.
*/
-
+
#if defined(CONFIG_ARCH_CHIP_STM32F103ZET6)
# include "stm32f103ze_pinmap.h"
+#elif defined(CONFIG_ARCH_CHIP_STM32F103RET6)
+# include "stm32f103re_pinmap.h"
#elif defined(CONFIG_ARCH_CHIP_STM32F107VC)
# include "stm32f107vc_pinmap.h"
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_rcc.c b/nuttx/arch/arm/src/stm32/stm32_rcc.c
index 22c67d120..c789a5643 100755
--- a/nuttx/arch/arm/src/stm32/stm32_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_rcc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_rcc.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -364,28 +364,21 @@ static inline void rcc_enableapb2(void)
}
/****************************************************************************
- * Global Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: stm32_clockconfig
+ * Name: stm32_stdclockconfig
*
* Description:
- * Called to change to new clock based on settings in board.h.
- * NOTE: This logic needs to be extended so that we can selected low-power
- * clocking modes as well!
+ * Called to set clocking based on standard definitions in board.h.
+ * NOTE: This logic would need to be extended if you need to select low-
+ * power clocking modes!
*
****************************************************************************/
-void stm32_clockconfig(void)
+#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG)
+static inline void stm32_stdclockconfig(void)
{
uint32_t regval;
volatile int32_t timeout;
- /* Make sure that we are starting in the reset state */
-
- rcc_reset();
-
/* Enable External High-Speed Clock (HSE) */
regval = getreg32(STM32_RCC_CR);
@@ -465,9 +458,45 @@ void stm32_clockconfig(void)
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS);
}
+}
+#endif
- /* Enable peripheral clocking */
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: stm32_clockconfig
+ *
+ * Description:
+ * Called to change to new clock based on settings in board.h.
+ * NOTE: This logic needs to be extended so that we can selected low-power
+ * clocking modes as well!
+ *
+ ****************************************************************************/
+
+void stm32_clockconfig(void)
+{
+ /* Make sure that we are starting in the reset state */
+
+ rcc_reset();
+
+#if defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG)
+
+ /* Invoke Board Custom Clock Configuration */
+
+ stm32_board_clockconfig();
+
+#else
+
+ /* Invoke standard, fixed clock configuration based on definitions in board.h */
+
+ stm32_stdclockconfig();
+
+#endif
+
+ /* Enable peripheral clocking */
+
rcc_enableahb();
rcc_enableapb2();
rcc_enableapb1();
diff --git a/nuttx/arch/arm/src/stm32/stm32f103re_pinmap.h b/nuttx/arch/arm/src/stm32/stm32f103re_pinmap.h
new file mode 100644
index 000000000..fea301abb
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32f103re_pinmap.h
@@ -0,0 +1,330 @@
+/************************************************************************************
+ * arch/arm/src/stm32/stm32f103re_pinmap.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Uros Platise <uros.platise@isotel.eu>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_STM32F103RE_PINMAP_H
+#define __ARCH_ARM_SRC_STM32_STM32F103RE_PINMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Alternate Pin Functions: */
+
+#if defined(CONFIG_STM32_TIM1_FULL_REMAP)
+# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN7)
+# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN9)
+# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN9)
+# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN11)
+# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN11)
+# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN13)
+# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN13)
+# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN14)
+# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN14)
+# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN15)
+# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN8)
+# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN10)
+# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTE|GPIO_PIN12)
+#elif defined(CONFIG_STM32_TIM1_PARTIAL_REMAP)
+# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
+# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8)
+# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8)
+# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9)
+# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
+# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
+# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10)
+# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11)
+# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
+# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
+# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
+# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
+# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
+#else
+# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
+# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8)
+# define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN8)
+# define GPIO_TIM1_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9)
+# define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
+# define GPIO_TIM1_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
+# define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN10)
+# define GPIO_TIM1_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN11)
+# define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
+# define GPIO_TIM1_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12)
+# define GPIO_TIM1_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
+# define GPIO_TIM1_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
+# define GPIO_TIM1_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15)
+#endif
+
+#if defined(CONFIG_STM32_TIM2_FULL_REMAP)
+# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN3)
+# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
+# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
+# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
+# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
+#elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_1)
+# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN3)
+# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
+# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
+# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
+#elif defined(CONFIG_STM32_TIM2_PARTIAL_REMAP_2)
+# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
+# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
+# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
+# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
+# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
+# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
+#else
+# define GPIO_TIM2_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+# define GPIO_TIM2_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+# define GPIO_TIM2_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
+# define GPIO_TIM2_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
+# define GPIO_TIM2_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
+# define GPIO_TIM2_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+# define GPIO_TIM2_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
+# define GPIO_TIM2_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+# define GPIO_TIM2_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
+#endif
+
+#if defined(CONFIG_STM32_TIM3_FULL_REMAP)
+# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN6)
+# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN6)
+# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN7)
+# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN7)
+# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN8)
+# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8)
+# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN9)
+# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9)
+#elif defined(CONFIG_STM32_TIM3_PARTIAL_REMAP)
+# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4)
+# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN4)
+# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5)
+# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
+# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
+# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
+# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
+#else
+# define GPIO_TIM3_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
+# define GPIO_TIM3_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6)
+# define GPIO_TIM3_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
+# define GPIO_TIM3_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
+# define GPIO_TIM3_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
+# define GPIO_TIM3_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
+# define GPIO_TIM3_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
+# define GPIO_TIM3_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
+#endif
+
+#if defined(CONFIG_STM32_TIM4_REMAP)
+# define GPIO_TIM4_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN12)
+# define GPIO_TIM4_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12)
+# define GPIO_TIM4_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN13)
+# define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN13)
+# define GPIO_TIM4_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN14)
+# define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN14)
+# define GPIO_TIM4_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN15)
+# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN15)
+#else
+# define GPIO_TIM4_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN6)
+# define GPIO_TIM4_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6)
+# define GPIO_TIM4_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN7)
+# define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7)
+# define GPIO_TIM4_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN8)
+# define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
+# define GPIO_TIM4_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9)
+# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
+#endif
+
+#define GPIO_TIM5_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_TIM5_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
+
+#if defined(CONFIG_STM32_USART1_REMAP)
+# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
+# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
+#else
+# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
+# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
+#endif
+
+#if defined(CONFIG_STM32_USART2_REMAP)
+# define GPIO_USART2_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN3)
+# define GPIO_USART2_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN4)
+# define GPIO_USART2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN5)
+# define GPIO_USART2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN6)
+# define GPIO_USART2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN7)
+#else
+# define GPIO_USART2_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+# define GPIO_USART2_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
+# define GPIO_USART2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
+# define GPIO_USART2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+# define GPIO_USART2_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4)
+#endif
+
+#if defined(CONFIG_STM32_USART3_FULL_REMAP)
+# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN8)
+# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN9)
+# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN10)
+# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN11)
+# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN12)
+#elif defined(CONFIG_STM32_USART3_PARTIAL_REMAP)
+# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10)
+# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11)
+# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12)
+# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
+# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
+#else
+# define GPIO_USART3_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
+# define GPIO_USART3_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+# define GPIO_USART3_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
+# define GPIO_USART3_CTS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
+# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
+#endif
+
+#if defined(CONFIG_STM32_SPI1_REMAP)
+# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
+# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4)
+# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+#else
+# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4)
+# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN5)
+# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6)
+# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
+#endif
+
+#if defined(CONFIG_STM32_SPI3_REMAP)
+# define GPIO_SPI3_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+# define GPIO_SPI3_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10)
+# define GPIO_SPI3_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11)
+# define GPIO_SPI3_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12)
+#else
+# define GPIO_SPI3_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_SPI3_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
+# define GPIO_SPI3_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4)
+# define GPIO_SPI3_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+#endif
+
+#if defined(CONFIG_STM32_I2C1_REMAP)
+# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
+# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
+#else
+# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6)
+# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7)
+#endif
+
+#if defined(CONFIG_STM32_CAN1_FULL_REMAP)
+# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN0)
+# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1)
+#elif defined(CONFIG_STM32_CAN1_PARTIAL_REMAP)
+# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
+# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9)
+#else
+# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
+# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
+#endif
+
+#if defined(CONFIG_STM32_CAN2_REMAP)
+# define GPIO_CAN2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+# define GPIO_CAN2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN6)
+#else
+# define GPIO_CAN2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
+# define GPIO_CAN2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
+#endif
+
+/* SDIO */
+
+#define GPIO_SDIO_D0 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8)
+#define GPIO_SDIO_D1 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9)
+#define GPIO_SDIO_D2 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10)
+#define GPIO_SDIO_D3 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN11)
+#define GPIO_SDIO_D4 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_SDIO_D5 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
+#define GPIO_SDIO_D6 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN6)
+#define GPIO_SDIO_D7 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN7)
+#define GPIO_SDIO_CK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12)
+#define GPIO_SDIO_CMD (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN2)
+
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_STM32_STM32F103RE_PINMAP_H */