Browse Source

STM32F4Discovery configuration clean-up

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4985 7fd9a85b-ad96-42d3-883c-3090e2eb8679
sbg
patacongo 13 years ago
parent
commit
25e9fa05c7
  1. 2
      nuttx/arch/arm/src/stm32/stm32_serial.c
  2. 36
      nuttx/configs/stm32f4discovery/README.txt
  3. 4
      nuttx/configs/stm32f4discovery/nsh/defconfig
  4. 4
      nuttx/configs/stm32f4discovery/nxlines/defconfig
  5. 6
      nuttx/configs/stm32f4discovery/ostest/defconfig
  6. 4
      nuttx/configs/stm32f4discovery/pm/defconfig
  7. 14
      nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h
  8. 72
      nuttx/configs/stm32f4discovery/src/up_autoleds.c
  9. 4
      nuttx/configs/stm32f4discovery/src/up_pwm.c
  10. 10
      nuttx/configs/stm32f4discovery/src/up_spi.c
  11. 2
      nuttx/configs/stm32f4discovery/src/up_userleds.c

2
nuttx/arch/arm/src/stm32/stm32_serial.c

@ -1218,7 +1218,9 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) @@ -1218,7 +1218,9 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
{
struct inode *inode = filep->f_inode;
struct uart_dev_s *dev = inode->i_private;
#ifdef CONFIG_SERIAL_TERMIOS
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
#endif
int ret = OK;
switch (cmd)

36
nuttx/configs/stm32f4discovery/README.txt

@ -220,18 +220,18 @@ defined. In that case, the usage by the board port is defined in @@ -220,18 +220,18 @@ 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
events as follows:
SYMBOL Meaning LED1* LED2 LED3 LED4
green orange red blue
SYMBOL Meaning LED1* LED2 LED3 LED4
green orange red blue
------------------- ----------------------- ------- ------- ------- ------
LED_STARTED NuttX has been started ON OFF OFF OFF
LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
LED_STACKCREATED Idle stack created OFF OFF ON OFF
LED_INIRQ In an interrupt** ON N/C N/C OFF
LED_SIGNAL In a signal handler*** N/C ON N/C OFF
LED_ASSERTION An assertion failed ON ON N/C OFF
LED_PANIC The system has crashed N/C N/C N/C ON
LED_IDLE STM32 is is sleep mode (Optional, not used)
LED_STARTED NuttX has been started ON OFF OFF OFF
LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
LED_STACKCREATED Idle stack created OFF OFF ON OFF
LED_INIRQ In an interrupt** ON N/C N/C OFF
LED_SIGNAL In a signal handler*** N/C ON N/C OFF
LED_ASSERTION An assertion failed ON ON N/C OFF
LED_PANIC The system has crashed N/C N/C N/C ON
LED_IDLE STM32 is is sleep mode (Optional, not used)
* If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot
and these LEDs will give you some indication of where the failure was
@ -665,7 +665,7 @@ STM32F4Discovery-specific Configuration Options @@ -665,7 +665,7 @@ STM32F4Discovery-specific Configuration Options
CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
chip:
CONFIG_ARCH_CHIP_STM32F407IG=y
CONFIG_ARCH_CHIP_STM32F407VG=y
CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG - Enables special STM32 clock
configuration features.
@ -712,11 +712,11 @@ STM32F4Discovery-specific Configuration Options @@ -712,11 +712,11 @@ STM32F4Discovery-specific Configuration Options
CONFIG_HEAP2_END - The end (+1) of the SRAM in the FSMC address space
CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
CONFIG_ARCH_IRQPRIO - The STM32F4Discovery supports interrupt prioritization
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU)
CONFIG_ARCH_FPU - The STM32F4Discovery supports a floating point unit (FPU)
CONFIG_ARCH_FPU=y
@ -843,7 +843,7 @@ STM32F4Discovery-specific Configuration Options @@ -843,7 +843,7 @@ STM32F4Discovery-specific Configuration Options
but without JNTRST.
CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
STM3240xxx specific device driver settings
STM32F4Discovery specific device driver settings
CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART
m (m=4,5) for the console and ttys0 (default is the USART1).
@ -856,7 +856,7 @@ STM32F4Discovery-specific Configuration Options @@ -856,7 +856,7 @@ STM32F4Discovery-specific Configuration Options
CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_U[S]ARTn_2STOP - Two stop bits
STM3240xxx CAN Configuration
STM32F4Discovery CAN Configuration
CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
CONFIG_STM32_CAN2 must also be defined)
@ -875,7 +875,7 @@ STM32F4Discovery-specific Configuration Options @@ -875,7 +875,7 @@ STM32F4Discovery-specific Configuration Options
CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
dump of all CAN registers.
STM3240xxx SPI Configuration
STM32F4Discovery SPI Configuration
CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI
support. Non-interrupt-driven, poll-waiting is recommended if the
@ -883,7 +883,7 @@ STM32F4Discovery-specific Configuration Options @@ -883,7 +883,7 @@ STM32F4Discovery-specific Configuration Options
CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance.
Cannot be used with CONFIG_STM32_SPI_INTERRUPT.
STM3240xxx DMA Configuration
STM32F4Discovery DMA Configuration
CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO
and CONFIG_STM32_DMA2.

4
nuttx/configs/stm32f4discovery/nsh/defconfig

@ -52,8 +52,8 @@ @@ -52,8 +52,8 @@
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU)
# CONFIG_ARCH_IRQPRIO - The STM32F4Discovery supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM32F4Discovery supports a floating point unit (FPU)
# (But, unfortunately, GCC does not support it).
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt

4
nuttx/configs/stm32f4discovery/nxlines/defconfig

@ -52,8 +52,8 @@ @@ -52,8 +52,8 @@
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU)
# CONFIG_ARCH_IRQPRIO - The STM32F4Discovery supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM32F4Discovery supports a floating point unit (FPU)
# (But, unfortunately, GCC does not support it).
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt

6
nuttx/configs/stm32f4discovery/ostest/defconfig

@ -52,8 +52,8 @@ @@ -52,8 +52,8 @@
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU)
# CONFIG_ARCH_IRQPRIO - The STM32F4Discovery supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM32F4Discovery supports a floating point unit (FPU)
# (But, unfortunately, GCC does not support it).
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
@ -186,7 +186,7 @@ CONFIG_STM32_TIM11=n @@ -186,7 +186,7 @@ CONFIG_STM32_TIM11=n
#CONFIG_STM32_FORCEPOWER=y
#
# STM3240xxx specific serial device driver settings
# STM32F4Discovery specific serial device driver settings
#
# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the
# console and ttys0 (default is the USART1).

4
nuttx/configs/stm32f4discovery/pm/defconfig

@ -52,8 +52,8 @@ @@ -52,8 +52,8 @@
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU)
# CONFIG_ARCH_IRQPRIO - The STM32F4Discovery supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM32F4Discovery supports a floating point unit (FPU)
# (But, unfortunately, GCC does not support it).
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt

14
nuttx/configs/stm32f4discovery/src/stm32f4discovery-internal.h

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************************************
* configs/stm3240g_eval/src/stm3240g_internal.h
* arch/arm/src/board/stm3240g_internal.n
* configs/stm32f4discovery/src/stm32f4discovery-internal.h
* arch/arm/src/board/stm32f4discovery-internal.n
*
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -34,8 +34,8 @@ @@ -34,8 +34,8 @@
*
****************************************************************************************************/
#ifndef __CONFIGS_STM3240G_EVAL_SRC_STM3240G_INTERNAL_H
#define __CONFIGS_STM3240G_EVAL_SRC_STM3240G_INTERNAL_H
#ifndef __CONFIGS_STM32F4DISCOVERY_SRC_STM32F4DISCOVERY_INTERNAL_H
#define __CONFIGS_STM32F4DISCOVERY_SRC_STM32F4DISCOVERY_INTERNAL_H
/****************************************************************************************************
* Included Files
@ -88,8 +88,8 @@ @@ -88,8 +88,8 @@
* configured to output a pulse train using TIM4 CH2 on PD13.
*/
#define STM3240G_EVAL_PWMTIMER 4
#define STM3240G_EVAL_PWMCHANNEL 2
#define STM32F4DISCOVERY_PWMTIMER 4
#define STM32F4DISCOVERY_PWMCHANNEL 2
/* SPI chip selects */
@ -223,5 +223,5 @@ void up_pmbuttons(void); @@ -223,5 +223,5 @@ void up_pmbuttons(void);
#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_STM3240G_EVAL_SRC_STM3240G_INTERNAL_H */
#endif /* __CONFIGS_STM32F4DISCOVERY_SRC_STM32F4DISCOVERY_INTERNAL_H */

72
nuttx/configs/stm32f4discovery/src/up_autoleds.c

@ -1,5 +1,5 @@ @@ -1,5 +1,5 @@
/****************************************************************************
* configs/stm3240g_eval/src/up_autoleds.c
* configs/stm32f4discovery/src/up_autoleds.c
* arch/arm/src/board/up_autoleds.c
*
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
@ -74,10 +74,10 @@ @@ -74,10 +74,10 @@
/* The following definitions map the encoded LED setting to GPIO settings */
#define STM3210E_LED1 (1 << 0)
#define STM3210E_LED2 (1 << 1)
#define STM3210E_LED3 (1 << 2)
#define STM3210E_LED4 (1 << 3)
#define STM32F4_LED1 (1 << 0)
#define STM32F4_LED2 (1 << 1)
#define STM32F4_LED3 (1 << 2)
#define STM32F4_LED4 (1 << 3)
#define ON_SETBITS_SHIFT (0)
#define ON_CLRBITS_SHIFT (4)
@ -94,45 +94,45 @@ @@ -94,45 +94,45 @@
#define OFF_SETBITS(v) (SETBITS(OFF_BITS(v))
#define OFF_CLRBITS(v) (CLRBITS(OFF_BITS(v))
#define LED_STARTED_ON_SETBITS ((STM3210E_LED1) << ON_SETBITS_SHIFT)
#define LED_STARTED_ON_CLRBITS ((STM3210E_LED2|STM3210E_LED3|STM3210E_LED4) << ON_CLRBITS_SHIFT)
#define LED_STARTED_ON_SETBITS ((STM32F4_LED1) << ON_SETBITS_SHIFT)
#define LED_STARTED_ON_CLRBITS ((STM32F4_LED2|STM32F4_LED3|STM32F4_LED4) << ON_CLRBITS_SHIFT)
#define LED_STARTED_OFF_SETBITS (0 << OFF_SETBITS_SHIFT)
#define LED_STARTED_OFF_CLRBITS ((STM3210E_LED1|STM3210E_LED2|STM3210E_LED3|STM3210E_LED4) << OFF_CLRBITS_SHIFT)
#define LED_STARTED_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED2|STM32F4_LED3|STM32F4_LED4) << OFF_CLRBITS_SHIFT)
#define LED_HEAPALLOCATE_ON_SETBITS ((STM3210E_LED2) << ON_SETBITS_SHIFT)
#define LED_HEAPALLOCATE_ON_CLRBITS ((STM3210E_LED1|STM3210E_LED3|STM3210E_LED4) << ON_CLRBITS_SHIFT)
#define LED_HEAPALLOCATE_OFF_SETBITS ((STM3210E_LED1) << OFF_SETBITS_SHIFT)
#define LED_HEAPALLOCATE_OFF_CLRBITS ((STM3210E_LED2|STM3210E_LED3|STM3210E_LED4) << OFF_CLRBITS_SHIFT)
#define LED_HEAPALLOCATE_ON_SETBITS ((STM32F4_LED2) << ON_SETBITS_SHIFT)
#define LED_HEAPALLOCATE_ON_CLRBITS ((STM32F4_LED1|STM32F4_LED3|STM32F4_LED4) << ON_CLRBITS_SHIFT)
#define LED_HEAPALLOCATE_OFF_SETBITS ((STM32F4_LED1) << OFF_SETBITS_SHIFT)
#define LED_HEAPALLOCATE_OFF_CLRBITS ((STM32F4_LED2|STM32F4_LED3|STM32F4_LED4) << OFF_CLRBITS_SHIFT)
#define LED_IRQSENABLED_ON_SETBITS ((STM3210E_LED1|STM3210E_LED2) << ON_SETBITS_SHIFT)
#define LED_IRQSENABLED_ON_CLRBITS ((STM3210E_LED3|STM3210E_LED4) << ON_CLRBITS_SHIFT)
#define LED_IRQSENABLED_OFF_SETBITS ((STM3210E_LED2) << OFF_SETBITS_SHIFT)
#define LED_IRQSENABLED_OFF_CLRBITS ((STM3210E_LED1|STM3210E_LED3|STM3210E_LED4) << OFF_CLRBITS_SHIFT)
#define LED_IRQSENABLED_ON_SETBITS ((STM32F4_LED1|STM32F4_LED2) << ON_SETBITS_SHIFT)
#define LED_IRQSENABLED_ON_CLRBITS ((STM32F4_LED3|STM32F4_LED4) << ON_CLRBITS_SHIFT)
#define LED_IRQSENABLED_OFF_SETBITS ((STM32F4_LED2) << OFF_SETBITS_SHIFT)
#define LED_IRQSENABLED_OFF_CLRBITS ((STM32F4_LED1|STM32F4_LED3|STM32F4_LED4) << OFF_CLRBITS_SHIFT)
#define LED_STACKCREATED_ON_SETBITS ((STM3210E_LED3) << ON_SETBITS_SHIFT)
#define LED_STACKCREATED_ON_CLRBITS ((STM3210E_LED1|STM3210E_LED2|STM3210E_LED4) << ON_CLRBITS_SHIFT)
#define LED_STACKCREATED_OFF_SETBITS ((STM3210E_LED1|STM3210E_LED2) << OFF_SETBITS_SHIFT)
#define LED_STACKCREATED_OFF_CLRBITS ((STM3210E_LED3|STM3210E_LED4) << OFF_CLRBITS_SHIFT)
#define LED_STACKCREATED_ON_SETBITS ((STM32F4_LED3) << ON_SETBITS_SHIFT)
#define LED_STACKCREATED_ON_CLRBITS ((STM32F4_LED1|STM32F4_LED2|STM32F4_LED4) << ON_CLRBITS_SHIFT)
#define LED_STACKCREATED_OFF_SETBITS ((STM32F4_LED1|STM32F4_LED2) << OFF_SETBITS_SHIFT)
#define LED_STACKCREATED_OFF_CLRBITS ((STM32F4_LED3|STM32F4_LED4) << OFF_CLRBITS_SHIFT)
#define LED_INIRQ_ON_SETBITS ((STM3210E_LED1) << ON_SETBITS_SHIFT)
#define LED_INIRQ_ON_SETBITS ((STM32F4_LED1) << ON_SETBITS_SHIFT)
#define LED_INIRQ_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
#define LED_INIRQ_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
#define LED_INIRQ_OFF_CLRBITS ((STM3210E_LED1) << OFF_CLRBITS_SHIFT)
#define LED_INIRQ_OFF_CLRBITS ((STM32F4_LED1) << OFF_CLRBITS_SHIFT)
#define LED_SIGNAL_ON_SETBITS ((STM3210E_LED2) << ON_SETBITS_SHIFT)
#define LED_SIGNAL_ON_SETBITS ((STM32F4_LED2) << ON_SETBITS_SHIFT)
#define LED_SIGNAL_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
#define LED_SIGNAL_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
#define LED_SIGNAL_OFF_CLRBITS ((STM3210E_LED2) << OFF_CLRBITS_SHIFT)
#define LED_SIGNAL_OFF_CLRBITS ((STM32F4_LED2) << OFF_CLRBITS_SHIFT)
#define LED_ASSERTION_ON_SETBITS ((STM3210E_LED4) << ON_SETBITS_SHIFT)
#define LED_ASSERTION_ON_SETBITS ((STM32F4_LED4) << ON_SETBITS_SHIFT)
#define LED_ASSERTION_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
#define LED_ASSERTION_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
#define LED_ASSERTION_OFF_CLRBITS ((STM3210E_LED4) << OFF_CLRBITS_SHIFT)
#define LED_ASSERTION_OFF_CLRBITS ((STM32F4_LED4) << OFF_CLRBITS_SHIFT)
#define LED_PANIC_ON_SETBITS ((STM3210E_LED4) << ON_SETBITS_SHIFT)
#define LED_PANIC_ON_SETBITS ((STM32F4_LED4) << ON_SETBITS_SHIFT)
#define LED_PANIC_ON_CLRBITS ((0) << ON_CLRBITS_SHIFT)
#define LED_PANIC_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
#define LED_PANIC_OFF_CLRBITS ((STM3210E_LED4) << OFF_CLRBITS_SHIFT)
#define LED_PANIC_OFF_CLRBITS ((STM32F4_LED4) << OFF_CLRBITS_SHIFT)
/****************************************************************************
* Private Data
@ -171,22 +171,22 @@ static const uint16_t g_ledbits[8] = @@ -171,22 +171,22 @@ static const uint16_t g_ledbits[8] =
static inline void led_clrbits(unsigned int clrbits)
{
if ((clrbits & STM3210E_LED1) != 0)
if ((clrbits & STM32F4_LED1) != 0)
{
stm32_gpiowrite(GPIO_LED1, false);
}
if ((clrbits & STM3210E_LED2) != 0)
if ((clrbits & STM32F4_LED2) != 0)
{
stm32_gpiowrite(GPIO_LED2, false);
}
if ((clrbits & STM3210E_LED3) != 0)
if ((clrbits & STM32F4_LED3) != 0)
{
stm32_gpiowrite(GPIO_LED3, false);
}
if ((clrbits & STM3210E_LED4) != 0)
if ((clrbits & STM32F4_LED4) != 0)
{
stm32_gpiowrite(GPIO_LED4, false);
}
@ -194,22 +194,22 @@ static inline void led_clrbits(unsigned int clrbits) @@ -194,22 +194,22 @@ static inline void led_clrbits(unsigned int clrbits)
static inline void led_setbits(unsigned int setbits)
{
if ((setbits & STM3210E_LED1) != 0)
if ((setbits & STM32F4_LED1) != 0)
{
stm32_gpiowrite(GPIO_LED1, true);
}
if ((setbits & STM3210E_LED2) != 0)
if ((setbits & STM32F4_LED2) != 0)
{
stm32_gpiowrite(GPIO_LED2, true);
}
if ((setbits & STM3210E_LED3) != 0)
if ((setbits & STM32F4_LED3) != 0)
{
stm32_gpiowrite(GPIO_LED3, true);
}
if ((setbits & STM3210E_LED4) != 0)
if ((setbits & STM32F4_LED4) != 0)
{
stm32_gpiowrite(GPIO_LED4, true);
}

4
nuttx/configs/stm32f4discovery/src/up_pwm.c

@ -80,7 +80,7 @@ @@ -80,7 +80,7 @@
# undef HAVE_PWM
#endif
#if CONFIG_STM32_TIM4_CHANNEL != STM3240G_EVAL_PWMCHANNEL
#if CONFIG_STM32_TIM4_CHANNEL != STM32F4DISCOVERY_PWMCHANNEL
# undef HAVE_PWM
#endif
@ -115,7 +115,7 @@ int pwm_devinit(void) @@ -115,7 +115,7 @@ int pwm_devinit(void)
{
/* Call stm32_pwminitialize() to get an instance of the PWM interface */
pwm = stm32_pwminitialize(STM3240G_EVAL_PWMTIMER);
pwm = stm32_pwminitialize(STM32F4DISCOVERY_PWMTIMER);
if (!pwm)
{
dbg("Failed to get the STM32 PWM lower half\n");

10
nuttx/configs/stm32f4discovery/src/up_spi.c

@ -1,8 +1,8 @@ @@ -1,8 +1,8 @@
/************************************************************************************
* configs/stm3240g_eval/src/up_spi.c
* configs/stm32f4discovery/src/up_spi.c
* arch/arm/src/board/up_spi.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
@ -94,9 +94,9 @@ @@ -94,9 +94,9 @@
void weak_function stm32_spiinitialize(void)
{
stm32_configgpio(GPIO_SPI1_MISO);
stm32_configgpio(GPIO_SPI1_MOSI);
stm32_configgpio(GPIO_SPI1_SCK);
#ifdef CONFIG_STM32_SPI1
stm32_configgpio(GPIO_CS_MEMS);
#endif
}
/****************************************************************************

2
nuttx/configs/stm32f4discovery/src/up_userleds.c

@ -1,5 +1,5 @@ @@ -1,5 +1,5 @@
/****************************************************************************
* configs/stm3240g_eval/src/up_leds.c
* configs/stm32f4discovery/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.

Loading…
Cancel
Save