summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_gpio.c65
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_internal.h8
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_lowputc.c27
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_rcc.c16
4 files changed, 77 insertions, 39 deletions
diff --git a/nuttx/arch/arm/src/stm32/stm32_gpio.c b/nuttx/arch/arm/src/stm32/stm32_gpio.c
index 3d849f96a..280760aca 100755
--- a/nuttx/arch/arm/src/stm32/stm32_gpio.c
+++ b/nuttx/arch/arm/src/stm32/stm32_gpio.c
@@ -114,7 +114,7 @@ int stm32_configgpio(uint32 cfgset)
unsigned int pin;
unsigned int pos;
unsigned int modecnf;
- boolean output;
+ boolean input;
/* Verify that this hardware supports the select GPIO port */
@@ -141,17 +141,21 @@ int stm32_configgpio(uint32 cfgset)
/* Input or output? */
- output = ((cfgset & GPIO_OUTPUT) != 0);
+ input = ((cfgset & GPIO_INPUT) != 0);
/* Decode the mode and configuration */
- if (output)
+ if (input)
{
- modecnf = (cfgset & GPIO_MODE_MASK) >> GPIO_MODE_SHIFT;
+ /* Input.. force mode = INPUT */
+
+ modecnf = 0;
}
else
{
- modecnf = 0;
+ /* Output or alternate function */
+
+ modecnf = (cfgset & GPIO_MODE_MASK) >> GPIO_MODE_SHIFT;
}
modecnf |= ((cfgset & GPIO_CNF_MASK) >> GPIO_CNF_SHIFT) << 2;
@@ -165,24 +169,37 @@ int stm32_configgpio(uint32 cfgset)
/* Set or reset the corresponding BRR/BSRR bit */
- if (output)
+ if (!input)
{
- /* It is an output pin, we need to instantiate the initial
- * pin output value
- */
-
- if ((cfgset & GPIO_OUTPUT_SET) != 0)
- {
- /* Use the BSRR register to set the output */
-
- regaddr = base + STM32_GPIO_BSRR_OFFSET;
- }
- else
- {
- /* Use the BRR register to clear */
-
- regaddr = base + STM32_GPIO_BRR_OFFSET;
- }
+ /* It is an output or an alternate function. We have to look at the CNF
+ * bits to know which.
+ */
+
+ unsigned int cnf = (cfgset & GPIO_CNF_MASK);
+ if (cnf == GPIO_CNF_OUTPP || cnf == GPIO_CNF_OUTOD)
+ {
+
+ /* Its an output... set the pin to the correct initial state */
+
+ if ((cfgset & GPIO_OUTPUT_SET) != 0)
+ {
+ /* Use the BSRR register to set the output */
+
+ regaddr = base + STM32_GPIO_BSRR_OFFSET;
+ }
+ else
+ {
+ /* Use the BRR register to clear */
+
+ regaddr = base + STM32_GPIO_BRR_OFFSET;
+ }
+ }
+ else
+ {
+ /* Its an alternate function pin... we can return early */
+
+ return OK;
+ }
}
else
{
@@ -191,13 +208,13 @@ int stm32_configgpio(uint32 cfgset)
* function.
*/
- if ((cfgset & GPIO_MODE_MASK) == GPIO_CNF_INPULLUP)
+ if ((cfgset & GPIO_CNF_MASK) == GPIO_CNF_INPULLUP)
{
/* Set the ODR bit (using BSRR) to one for the PULL-UP functionality */
regaddr = base + STM32_GPIO_BSRR_OFFSET;
}
- else if ((cfgset & GPIO_MODE_MASK) == GPIO_CNF_INPULLDWN)
+ else if ((cfgset & GPIO_CNF_MASK) == GPIO_CNF_INPULLDWN)
{
/* Clear the ODR bit (using BRR) to zero for the PULL-DOWN functionality */
diff --git a/nuttx/arch/arm/src/stm32/stm32_internal.h b/nuttx/arch/arm/src/stm32/stm32_internal.h
index 404dbeaa4..0b4dbdb84 100755
--- a/nuttx/arch/arm/src/stm32/stm32_internal.h
+++ b/nuttx/arch/arm/src/stm32/stm32_internal.h
@@ -67,8 +67,8 @@
* .... .... .... .... O... .... VPPP BBBB
*/
-#define GPIO_OUTPUT (1 << 15) /* Bit 15: Output mode */
-#define GPIO_INPUT (0)
+#define GPIO_INPUT (1 << 15) /* Bit 15: 1=Input mode */
+#define GPIO_OUTPUT (0) /* 0=Output or alternate function */
#define GPIO_ALT (0)
/* These bits set the primary function of the pin:
@@ -85,8 +85,8 @@
# define GPIO_CNF_OUTPP (0 << GPIO_CNF_SHIFT) /* Output push-pull */
# define GPIO_CNF_OUTOD (1 << GPIO_CNF_SHIFT) /* Output open-drain */
-# define GPIO_CNF_AFPP (2 << GPIO_CNF_SHIFT) /* Altnernate function push-pull */
-# define GPIO_CNF_AFOD (3 << GPIO_CNF_SHIFT) /* Altnernate function open-drain */
+# define GPIO_CNF_AFPP (2 << GPIO_CNF_SHIFT) /* Alternate function push-pull */
+# define GPIO_CNF_AFOD (3 << GPIO_CNF_SHIFT) /* Alternate function open-drain */
/* Maximum frequency selection:
* .... .... .... .... ...S S... .... ....
diff --git a/nuttx/arch/arm/src/stm32/stm32_lowputc.c b/nuttx/arch/arm/src/stm32/stm32_lowputc.c
index 0f649bbd7..da6cdc138 100644
--- a/nuttx/arch/arm/src/stm32/stm32_lowputc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_lowputc.c
@@ -149,17 +149,38 @@
* usartdiv = fCK / (16 * baud)
*
* Where fCK is the input clock to the peripheral (PCLK1 for USART2, 3, 4, 5
- * or PCLK2 for USART1)
+ * or PCLK2 for USART1). Example, fCK=72MHz baud=115200, usartdiv=39.0625=39 1/16th;
*
- * First calculate (NOTE: all stand baud values are even so dividing by two
- * does not lose precision):
+ * First calculate:
*
* usartdiv32 = 32 * usartdiv = fCK / (baud/2)
+ *
+ * (NOTE: all standard baud values are even so dividing by two does not
+ * lose precision). Eg. (same fCK and buad), usartdiv32 = 1250
*/
#define STM32_USARTDIV32 (STM32_APBCLOCK / (STM32_CONSOLE_BAUD >> 1))
+
+/* The mantissa is then usartdiv32 * 32:
+ *
+ * mantissa = 32 * usartdiv32
+ *
+ * Eg. usartdiv32=1250, mantissa = 39
+ */
+
#define STM32_MANTISSA (STM32_USARTDIV32 >> 5)
+
+/* And the fraction:
+ *
+ * fraction = (usartdiv32 - mantissa*32 + 1) / 2
+ *
+ * Eg., (1,250 - 39*32 + 1)/2 = 1 (or 0.0625)
+ */
+
#define STM32_FRACTION ((STM32_USARTDIV32 - (STM32_MANTISSA << 5) + 1) >> 1)
+
+/* And, finally, the BRR value is: */
+
#define STM32_BRR_VALUE ((STM32_MANTISSA << USART_BRR_MANT_SHIFT) | (STM32_FRACTION << USART_BRR_FRAC_SHIFT))
/**************************************************************************
diff --git a/nuttx/arch/arm/src/stm32/stm32_rcc.c b/nuttx/arch/arm/src/stm32/stm32_rcc.c
index b9bb3c28b..3678f8ca1 100755
--- a/nuttx/arch/arm/src/stm32/stm32_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_rcc.c
@@ -223,7 +223,7 @@ static inline void rcc_enableapb1(void)
regval |= RCC_APB1ENR_DACEN;
#endif
- putreg32(regval, STM32_RCC_APB2ENR);
+ putreg32(regval, STM32_RCC_APB1ENR);
#if CONFIG_STM32_USB
/* USB clock divider */
@@ -246,23 +246,23 @@ static inline void rcc_enableapb2(void)
#if STM32_NGPIO > 0
|RCC_APB2ENR_IOPAEN
#endif
-#if STM32_NGPIO > 1
+#if STM32_NGPIO > 16
|RCC_APB2ENR_IOPBEN
#endif
-#if STM32_NGPIO > 2
+#if STM32_NGPIO > 32
|RCC_APB2ENR_IOPCEN
#endif
-#if STM32_NGPIO > 3
+#if STM32_NGPIO > 48
|RCC_APB2ENR_IOPDEN
#endif
-#if STM32_NGPIO > 4
+#if STM32_NGPIO > 64
|RCC_APB2ENR_IOPEEN
#endif
-#if STM32_NGPIO > 5
+#if STM32_NGPIO > 80
|RCC_APB2ENR_IOPFEN
#endif
-#if STM32_NGPIO > 6
- |RCC_APB2ENR_IOPEEN
+#if STM32_NGPIO > 96
+ |RCC_APB2ENR_IOPGEN
#endif
);