summaryrefslogtreecommitdiff
path: root/nuttx/configs/stm32f4discovery
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/stm32f4discovery')
-rwxr-xr-xnuttx/configs/stm32f4discovery/README.txt145
-rwxr-xr-xnuttx/configs/stm32f4discovery/include/board.h6
-rw-r--r--nuttx/configs/stm32f4discovery/nsh/appconfig4
-rwxr-xr-xnuttx/configs/stm32f4discovery/nsh/defconfig16
-rw-r--r--nuttx/configs/stm32f4discovery/src/Makefile4
-rw-r--r--nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h2
-rw-r--r--nuttx/configs/stm32f4discovery/src/up_autoleds.c2
-rw-r--r--nuttx/configs/stm32f4discovery/src/up_buttons.c2
-rw-r--r--nuttx/configs/stm32f4discovery/src/up_qencoder.c144
9 files changed, 307 insertions, 18 deletions
diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt
index 2e05b2c40..7187130b4 100755
--- a/nuttx/configs/stm32f4discovery/README.txt
+++ b/nuttx/configs/stm32f4discovery/README.txt
@@ -11,9 +11,11 @@ Contents
- GNU Toolchain Options
- IDEs
- NuttX buildroot Toolchain
- - stm32f4discovery-specific Configuration Options
- LEDs
- PWM
+ - UARTs
+ - Timer Inputs/Outputs
+ - STM32F4Discovery-specific Configuration Options
- Configurations
Development Environment
@@ -139,7 +141,7 @@ NuttX buildroot Toolchain
1. You must have already configured Nuttx in <some-dir>/nuttx.
cd tools
- ./configure.sh stm32f4discovery/<sub-dir>
+ ./configure.sh STM32F4Discovery/<sub-dir>
2. Download the latest buildroot package into <some-dir>
@@ -165,10 +167,10 @@ NuttX buildroot Toolchain
LEDs
====
-The stm32f4discovery board has four LEDs; green, organge, red and blue on the
+The STM32F4Discovery board has four LEDs; green, organge, red and blue on the
board.. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
defined. In that case, the usage by the board port is defined in
-include/board.h and src/up_leds.c. The LEDs are used to encode OS-related\
+include/board.h and src/up_leds.c. The LEDs are used to encode OS-related
events as follows:
SYMBOL Meaning LED1* LED2 LED3 LED4
@@ -194,12 +196,120 @@ events as follows:
PWM
===
-The stm32f4discovery has no real on-board PWM devices, but the board can be
+The STM32F4Discovery has no real on-board PWM devices, but the board can be
configured to output a pulse train using TIM4 CH2 on PD3. This pin is
available next to the audio jack.
-stm32f4discovery-specific Configuration Options
-============================================
+UART
+====
+
+UART/USART PINS
+---------------
+
+USART1
+ CK PA8
+ CTS PA11*
+ RTS PA12*
+ RX PA10*, PB7
+ TX PA9*, PB6*
+USART2
+ CK PA4*, PD7
+ CTS PA0*, PD3
+ RTS PA1, PD4*
+ RX PA3, PD6
+ TX PA2, PD5*
+USART3
+ CK PB12, PC12*, PD10
+ CTS PB13, PD11
+ RTS PB14, PD12*
+ RX PB11, PC11, PD9
+ TX PB10*, PC10*, PD8
+UART4
+ RX PA1, PC11
+ TX PA0*, PC10*
+UART5
+ RX PD2
+ TX PC12*
+USART6
+ CK PC8, PG7**
+ CTS PG13**, PG15**
+ RTS PG12**, PG8**
+ RX PC7*, PG9**
+ TX PC6, PG14**
+
+ * Indicates pins that have other on-board functins and should be used only
+ with care (See table 5 in the STM32F4Discovery User Guide). The rest are
+ free I/O pins.
+** Port G pins are not supported by the MCU
+
+Default USART/UART Configuration
+--------------------------------
+
+USART2 is enabled in all configurations (see */defconfig). RX and TX are
+configured on pins PA3 and PA2, respectively (see include/board.h).
+
+Timer Inputs/Outputs
+====================
+
+TIM1
+ CH1 PA8, PE9
+ CH2 PA9*, PE11
+ CH3 PA10*, PE13
+ CH4 PA11*, PE14
+TIM2
+ CH1 PA0*, PA15, PA5*
+ CH2 PA1, PB3*
+ CH3 PA2, PB10*
+ CH4 PA3, PB11
+TIM3
+ CH1 PA6*, PB4, PC6
+ CH2 PA7*, PB5, PC7*
+ CH3 PB0, PC8
+ CH4 PB1, PC9
+TIM4
+ CH1 PB6*, PD12*
+ CH2 PB7, PD13*
+ CH3 PB8, PD14*
+ CH4 PB9*, PD15*
+TIM5
+ CH1 PA0*, PH10**
+ CH2 PA1, PH11**
+ CH3 PA2, PH12**
+ CH4 PA3, PI0
+TIM8
+ CH1 PC6, PI5
+ CH2 PC7*, PI6
+ CH3 PC8, PI7
+ CH4 PC9, PI2
+TIM9
+ CH1 PA2, PE5
+ CH2 PA3, PE6
+TIM10
+ CH1 PB8, PF6
+TIM11
+ CH1 PB9*, PF7
+TIM12
+ CH1 PH6**, PB14
+ CH2 PC15, PH9**
+TIM13
+ CH1 PA6*, PF8
+TIM14
+ CH1 PA7*, PF9
+
+ * Indicates pins that have other on-board functins and should be used only
+ with care (See table 5 in the STM32F4Discovery User Guide). The rest are
+ free I/O pins.
+** Port H pins are not supported by the MCU
+
+Quadrature Encode Timer Inputs
+------------------------------
+
+If enabled (by setting CONFIG_QENCODER=y), then quadrature encoder will
+user TIM2 (see nsh/defconfig) and input pins PA15, and PA1 for CH1 and
+CH2, respectively (see include board.h).
+
+STM32F4Discovery-specific Configuration Options
+===============================================
CONFIG_ARCH - Identifies the arch/ subdirectory. This should
be set to:
@@ -231,7 +341,7 @@ stm32f4discovery-specific Configuration Options
CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
hence, the board that supports the particular chip or SoC.
- CONFIG_ARCH_BOARD=stm32f4discovery (for the stm32f4discovery development board)
+ CONFIG_ARCH_BOARD=STM32F4Discovery (for the STM32F4Discovery development board)
CONFIG_ARCH_BOARD_name - For use in C code
@@ -438,11 +548,11 @@ stm32f4discovery-specific Configuration Options
Configurations
==============
-Each stm32f4discovery configuration is maintained in a sudirectory and
+Each STM32F4Discovery configuration is maintained in a sudirectory and
can be selected as follow:
cd tools
- ./configure.sh stm32f4discovery/<subdir>
+ ./configure.sh STM32F4Discovery/<subdir>
cd -
. ./setenv.sh
@@ -461,13 +571,14 @@ Where <subdir> is one of the following:
Configures the NuttShell (nsh) located at apps/examples/nsh. The
Configuration enables both the serial and telnet NSH interfaces.
- CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux / Mac OS X
+ CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux / Mac OS X
NOTES:
1. This example supports the PWM test (apps/examples/pwm) but this must
be manually enabled by selecting:
CONFIG_PWM=y : Enable the generic PWM infrastructure
+ CONFIG_STM32_TIM4=y : Enable TIM4
CONFIG_STM32_TIM4_PWM=y : Use TIM4 to generate PWM output
See also apps/examples/README.txt
@@ -476,3 +587,15 @@ Where <subdir> is one of the following:
CONFIG_DEBUG_PWM
+ 1. This example supports the Quadrature Encode test (apps/examples/qencoder)
+ but this must be manually enabled by selecting:
+
+ CONFIG_QENCODER=y : Enable the generic Quadrature Encoder infrastructure
+ CONFIG_STM32_TIM2=y : Enable TIM2
+ CONFIG_STM32_TIM2_QE=y : Use TIM2 as the quadrature encoder
+
+ See also apps/examples/README.txt
+
+ Special PWM-only debug options:
+
+ CONFIG_DEBUG_QENCODER
diff --git a/nuttx/configs/stm32f4discovery/include/board.h b/nuttx/configs/stm32f4discovery/include/board.h
index 1ac0b0701..a34f22109 100755
--- a/nuttx/configs/stm32f4discovery/include/board.h
+++ b/nuttx/configs/stm32f4discovery/include/board.h
@@ -208,6 +208,7 @@
*
* The STM32F4 Discovery has no on-board serial devices, but the console is
* brought out to PA2 (TX) and PA3 (RX) for connection to an external serial device.
+ * (See the README.txt file for other options)
*/
#define GPIO_USART2_RX GPIO_USART2_RX_1
@@ -227,6 +228,11 @@
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
+/* Timer Inputs/Outputs (see the README.txt file for options) */
+
+#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_2
+#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_1
+
/************************************************************************************
* Public Data
************************************************************************************/
diff --git a/nuttx/configs/stm32f4discovery/nsh/appconfig b/nuttx/configs/stm32f4discovery/nsh/appconfig
index 770762110..73da507f5 100644
--- a/nuttx/configs/stm32f4discovery/nsh/appconfig
+++ b/nuttx/configs/stm32f4discovery/nsh/appconfig
@@ -51,3 +51,7 @@ endif
ifeq ($(CONFIG_PWM),y)
CONFIGURED_APPS += examples/pwm
endif
+
+ifeq ($(CONFIG_QENCODER),y)
+CONFIGURED_APPS += examples/qencoder
+endif
diff --git a/nuttx/configs/stm32f4discovery/nsh/defconfig b/nuttx/configs/stm32f4discovery/nsh/defconfig
index 7bd0cec32..b95d2a52c 100755
--- a/nuttx/configs/stm32f4discovery/nsh/defconfig
+++ b/nuttx/configs/stm32f4discovery/nsh/defconfig
@@ -1,7 +1,7 @@
############################################################################
# configs/stm32f4discovery/nsh/defconfig
#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -313,19 +313,26 @@ CONFIG_STM32_PHYSR_FULLDUPLEX=0x0004
CONFIG_STM32_ETH_PTP=n
CONFIG_STM32_ETHMAC_REGDEBUG=n
-
#
# PWM configuration
#
# The stm32f4discovery has no real on-board PWM devices, but the board can be configured to output
-# a pulse train using TIM4 CH2.
+# a pulse train using TIM4 CH2. (Don't forget to set CONFIG_STM32_TIM4=y above)
#
CONFIG_PWM=n
-CONFIG_STM32_TIM4=y
CONFIG_STM32_TIM4_PWM=y
CONFIG_STM32_TIM4_CHANNEL=2
#
+# Quadrature Encoder configuration.
+#
+# Uses TIM2 (CONFIG_STM32_TIM2=y above)
+#
+#
+CONFIG_QENCODER=n
+CONFIG_STM32_TIM2_QE=y
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
@@ -452,6 +459,7 @@ CONFIG_DEBUG_RTC=n
CONFIG_DEBUG_ANALOG=n
CONFIG_DEBUG_PWM=n
CONFIG_DEBUG_CAN=n
+CONFIG_DEBUG_QENCODER=n
CONFIG_HAVE_CXX=y
CONFIG_MM_REGIONS=2
CONFIG_ARCH_LOWPUTC=y
diff --git a/nuttx/configs/stm32f4discovery/src/Makefile b/nuttx/configs/stm32f4discovery/src/Makefile
index 133cc1467..88fd4e0ec 100644
--- a/nuttx/configs/stm32f4discovery/src/Makefile
+++ b/nuttx/configs/stm32f4discovery/src/Makefile
@@ -56,6 +56,10 @@ ifeq ($(CONFIG_PWM),y)
CSRCS += up_pwm.c
endif
+ifeq ($(CONFIG_QENCODER),y)
+CSRCS += up_qencoder.c
+endif
+
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h b/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h
index 8b9ca8d3c..4c3ea10db 100644
--- a/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h
+++ b/nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h
@@ -2,7 +2,7 @@
* configs/stm3240g_eval/src/stm3240g_internal.h
* arch/arm/src/board/stm3240g_internal.n
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/configs/stm32f4discovery/src/up_autoleds.c b/nuttx/configs/stm32f4discovery/src/up_autoleds.c
index 5d97f8758..34faa33fc 100644
--- a/nuttx/configs/stm32f4discovery/src/up_autoleds.c
+++ b/nuttx/configs/stm32f4discovery/src/up_autoleds.c
@@ -2,7 +2,7 @@
* configs/stm3240g_eval/src/up_autoleds.c
* arch/arm/src/board/up_autoleds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/configs/stm32f4discovery/src/up_buttons.c b/nuttx/configs/stm32f4discovery/src/up_buttons.c
index 60ac6c369..ae1366930 100644
--- a/nuttx/configs/stm32f4discovery/src/up_buttons.c
+++ b/nuttx/configs/stm32f4discovery/src/up_buttons.c
@@ -1,7 +1,7 @@
/****************************************************************************
* configs/stm32f4discovery/src/up_buttons.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/configs/stm32f4discovery/src/up_qencoder.c b/nuttx/configs/stm32f4discovery/src/up_qencoder.c
new file mode 100644
index 000000000..5d91f4c36
--- /dev/null
+++ b/nuttx/configs/stm32f4discovery/src/up_qencoder.c
@@ -0,0 +1,144 @@
+/************************************************************************************
+ * configs/stm32f4discovery/src/up_qencoder.c
+ * arch/arm/src/board/up_qencoder.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/sensors/qencoder.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "stm32_qencoder.h"
+#include "stm32f4discovery-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Configuration *******************************************************************/
+/* The following checks assum that the quadrature encoder is on TIM2. Make the
+ * appropriate changes if your configuration differes.
+ */
+
+#define HAVE_QENCODER 1
+
+#ifndef CONFIG_QENCODER
+# undef HAVE_QENCODER
+#endif
+
+#ifndef CONFIG_STM32_TIM2
+# undef HAVE_QENCODER
+#endif
+
+#ifndef CONFIG_STM32_TIM2_QE
+# undef HAVE_QENCODER
+#endif
+
+#ifdef HAVE_QENCODER
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing the quadrature encoder */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_QENCODER
+#endif
+
+#ifdef CONFIG_DEBUG_QENCODER
+# define qedbg dbg
+# define qelldbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define qevdbg vdbg
+# define qellvdbg llvdbg
+# else
+# define qelldbg(x...)
+# define qellvdbg(x...)
+# endif
+#else
+# define qedbg(x...)
+# define qelldbg(x...)
+# define qevdbg(x...)
+# define qellvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: qe_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/qencoder.
+ *
+ ************************************************************************************/
+
+int qe_devinit(void)
+{
+ static initialized = false;
+ int ret;
+
+ /* Check if we are already initialized */
+
+ if (!initialized)
+ {
+ /* Initialize a quadrature encoder interface. */
+
+ qevdbg("Initializing the quadrature encoder\n");
+ ret = stm32_qeinitialize("/dev/qe0", 2);
+ if (ret < 0)
+ {
+ qedbg("stm32_qeinitialize failed: %d\n", ret);
+ return ret;
+ }
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif /* HAVE_QENCODER */