summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-12 14:07:13 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-12 14:07:13 +0000
commit14c5c981145991a86366544bc11dbb9d410feecf (patch)
tree9fb204b8c6c0c4ecc6bcfcf80b3c6d18d5fc82f7 /nuttx
parente0eb054e9194a0df9b3f81fa74b3fe702505477c (diff)
downloadpx4-nuttx-14c5c981145991a86366544bc11dbb9d410feecf.tar.gz
px4-nuttx-14c5c981145991a86366544bc11dbb9d410feecf.tar.bz2
px4-nuttx-14c5c981145991a86366544bc11dbb9d410feecf.zip
Misc STM32 wildfire and ENC28J60 driver updates
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5133 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/Documentation/NuttX.html21
-rw-r--r--nuttx/configs/fire-stm32v2/README.txt14
-rw-r--r--nuttx/configs/fire-stm32v2/include/board.h2
-rw-r--r--nuttx/configs/fire-stm32v2/nsh/defconfig2
-rw-r--r--nuttx/configs/fire-stm32v2/src/fire-internal.h8
-rw-r--r--nuttx/configs/fire-stm32v2/src/up_spi.c4
-rw-r--r--nuttx/drivers/Kconfig1
-rw-r--r--nuttx/drivers/net/Kconfig8
-rw-r--r--nuttx/drivers/net/enc28j60.c37
10 files changed, 71 insertions, 29 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 174b1cc52..f69cc8d06 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3328,3 +3328,6 @@
simple allocation of DMA I/O buffers. The initiali check-in
is code complete but untested (not event built into the
mm/Makefile yet.
+ * confgs/fire-stm32v2: The board port is basically functional.
+ Not all features have been verified. The ENC28J60 network
+ is not yet functional.
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 287c702d2..e4f2ff6db 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -1734,8 +1734,9 @@
<td>
<p>
<b>STMicro STM32F103x</b>.
- Support for four MCUs and three board configurations are available.
- MCU support includes: STM32F103ZET6, STM32F103RET6, and STM32F103VCT.
+ Support for four MCUs and four board configurations are available.
+ MCU support includes all of the high density and connectivity line families.
+ Board supported is available specifically for: STM32F103ZET6, STM32F103RET6, STM32F103VCT, and STM32F103VET6.
Boards supported include:
</p>
<ol>
@@ -1751,6 +1752,10 @@
A port for the HY-Mini STM32v board. This board is based on the
STM32F103VCT chip. Contributed by Laurent Latil.
</li>
+ <li>
+ This M3 Wildfire development board (STM32F103VET6), version 2.
+ See <a href="http://firestm32.taobao.com">http://firestm32.taobao.com</a> (the current board is version 3).
+ </li>
</ol>
<p>
These ports uses a GNU arm-elf toolchain* under either Linux or Cygwin (with native Windows GNU
@@ -1761,7 +1766,7 @@
<b>STATUS:</b>
</p>
<ul>
- <li>
+ <li><b>Basic Support/Drivers</b>.
The basic STM32 port was released in NuttX version 0.4.12. The basic port includes boot-up
logic, interrupt driven serial console, and system timer interrupts.
The 0.4.13 release added support for SPI, serial FLASH, and USB device.;
@@ -1769,15 +1774,21 @@
Verified configurations are available for NuttX OS test, the NuttShell (NSH) example,
the USB serial device class, and the USB mass storage device class example.
</li>
- <li>
+ <li><b>NetClamps VSN</b>.
Support for the NetClamps VSN was included in version 5.18 of NuttX.
Uros Platise added support for timers, RTC, I2C, FLASH, extended power management
and other features.
</li>
- <li>
+ <li><b>Additional Drivers</b>.
Additional drivers and configurations were added in NuttX 6.13 and later releases for the STM32 F1 and F4.
F1 compatible drivers include an Ethernet driver, ADC driver, DAC driver, PWM driver, IWDG, WWDG, and CAN drivers.
</li>
+ <li><b>M3 Wildfire</b>.
+ Support for the Wildfire board was included in version 6.22 of NuttX.
+ The board port is basically functional.
+ Not all features have been verified.
+ The ENC28J60 network is not yet functional.
+ </li>
</ul>
<p>
<b>Development Environments:</b>
diff --git a/nuttx/configs/fire-stm32v2/README.txt b/nuttx/configs/fire-stm32v2/README.txt
index 694e319da..02485f812 100644
--- a/nuttx/configs/fire-stm32v2/README.txt
+++ b/nuttx/configs/fire-stm32v2/README.txt
@@ -764,3 +764,17 @@ Where <subdir> is one of the following:
Configure the NuttShell (nsh) located at examples/nsh. The nsh configuration
contains support for some built-in applications that can be enabled by making
some additional minor change to the configuration file.
+
+ NOTE: This configuration uses to the mconf configuration tool to control
+ the configuration. See the section entitled "NuttX Configuration Tool"
+ in the top-level README.txt file.
+
+ STATUS: The board port is basically functional. Not all features have been
+ verified. The ENC28J60 network is not yet functional. Networking is
+ enabled by default in this configuration for testing purposes. To use this
+ configuration, the network must currently be disabled. To do this using
+ the mconf configuration tool:
+
+ > make menuconfig
+
+ Then de-select "Networking Support" -> "Networking Support"
diff --git a/nuttx/configs/fire-stm32v2/include/board.h b/nuttx/configs/fire-stm32v2/include/board.h
index 36f09e7a8..9a5d309ab 100644
--- a/nuttx/configs/fire-stm32v2/include/board.h
+++ b/nuttx/configs/fire-stm32v2/include/board.h
@@ -2,7 +2,7 @@
* configs/fire-stm32v2/include/board.h
* include/arch/board/board.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * 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
diff --git a/nuttx/configs/fire-stm32v2/nsh/defconfig b/nuttx/configs/fire-stm32v2/nsh/defconfig
index fda34debe..1a849ad36 100644
--- a/nuttx/configs/fire-stm32v2/nsh/defconfig
+++ b/nuttx/configs/fire-stm32v2/nsh/defconfig
@@ -344,7 +344,7 @@ CONFIG_NETDEVICES=y
# CONFIG_NET_DM90x0 is not set
CONFIG_ENC28J60=y
CONFIG_ENC28J60_NINTERFACES=1
-CONFIG_ENC28J60_SPIMODE=2
+CONFIG_ENC28J60_SPIMODE=0
CONFIG_ENC28J60_FREQUENCY=20000000
# CONFIG_ENC28J60_STATS is not set
# CONFIG_ENC28J60_HALFDUPPLEX is not set
diff --git a/nuttx/configs/fire-stm32v2/src/fire-internal.h b/nuttx/configs/fire-stm32v2/src/fire-internal.h
index ee3c3486f..f51bd0ef9 100644
--- a/nuttx/configs/fire-stm32v2/src/fire-internal.h
+++ b/nuttx/configs/fire-stm32v2/src/fire-internal.h
@@ -192,7 +192,7 @@
*/
#ifndef CONFIG_ENC28J60
-# define GPIO_ENC28J60_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+# define GPIO_FLASH_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
#endif
@@ -214,11 +214,15 @@
# warning "TFT LCD and ENCJ2860 shared PE1"
#endif
+/* CS and Reset are active low. Initial states are not selected and not in
+ * reset (driver does a soft reset).
+ */
+
#ifdef CONFIG_ENC28J60
# define GPIO_ENC28J60_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
# define GPIO_ENC28J60_RESET (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
- GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN1)
+ GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN1)
# define GPIO_ENC28J60_INTR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
GPIO_EXTI|GPIO_PORTE|GPIO_PIN5)
#endif
diff --git a/nuttx/configs/fire-stm32v2/src/up_spi.c b/nuttx/configs/fire-stm32v2/src/up_spi.c
index 329274b7f..b2ef301b6 100644
--- a/nuttx/configs/fire-stm32v2/src/up_spi.c
+++ b/nuttx/configs/fire-stm32v2/src/up_spi.c
@@ -163,11 +163,11 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
#if 0 /* Need to study this */
- if (devid == SPIDEV_FLASH)
+ if (devid == SPIDEV_LCD)
{
/* Set the GPIO low to select and high to de-select */
- stm32_gpiowrite(GPIO_FLASH_CS, !selected);
+ stm32_gpiowrite(GPIO_LCD_CS, !selected);
}
else
#endif
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index c484e0c24..294566d01 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -300,6 +300,7 @@ endif
menuconfig NETDEVICES
bool "Network Device Support"
default n
+ depends on NET
---help---
Network interface drivers. See also include/nuttx/net/net.h
diff --git a/nuttx/drivers/net/Kconfig b/nuttx/drivers/net/Kconfig
index 988b96c94..b5c09bf01 100644
--- a/nuttx/drivers/net/Kconfig
+++ b/nuttx/drivers/net/Kconfig
@@ -36,9 +36,13 @@ config ENC28J60_NINTERFACES
config ENC28J60_SPIMODE
int "SPI mode"
- default 2
+ default 0
---help---
- Controls the SPI mode
+ Controls the SPI mode. The ENC28J60 spec says that it supports SPI
+ mode 0,0 only: "The implementation used on this device supports SPI
+ mode 0,0 only. In addition, the SPI port requires that SCK be at Idle
+ in a low state; selectable clock polarity is not supported."
+ However, sometimes you need to tinker with these things.
config ENC28J60_FREQUENCY
int "SPI frequency"
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index b9d614cd9..d3c735b11 100644
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -83,12 +83,15 @@
* CONFIG_ENC28J60_HALFDUPPLEX - Default is full duplex
*/
-/* The ENC28J60 spec says that is supports SPI mode 0,0 only. However,
- * somtimes you need to tinker with these things.
+/* The ENC28J60 spec says that it supports SPI mode 0,0 only: "The
+ * implementation used on this device supports SPI mode 0,0 only. In
+ * addition, the SPI port requires that SCK be at Idle in a low state;
+ * selectable clock polarity is not supported." However, sometimes you
+ * need to tinker with these things.
*/
#ifndef CONFIG_ENC28J60_SPIMODE
-# define CONFIG_ENC28J60_SPIMODE SPIDEV_MODE2
+# define CONFIG_ENC28J60_SPIMODE SPIDEV_MODE0
#endif
/* CONFIG_ENC28J60_NINTERFACES determines the number of physical interfaces
@@ -370,7 +373,9 @@ static void enc_select(FAR struct enc_driver_s *priv)
if (priv->lockcount > 0)
{
- /* Yes... just increment the lock count */
+ /* Yes... just increment the lock count. In this case, we know
+ * that the bus has already been configured for the ENC28J60.
+ */
DEBUGASSERT(priv->lockcount < 255);
priv->lockcount++;
@@ -382,21 +387,21 @@ static void enc_select(FAR struct enc_driver_s *priv)
DEBUGASSERT(priv->lockcount == 0);
SPI_LOCK(priv->spi, true);
priv->lockcount = 1;
+
+ /* Now make sure that the SPI bus is configured for the ENC28J60 (it
+ * might have gotten configured for a different device while unlocked)
+ */
+
+ SPI_SETMODE(priv->spi, CONFIG_ENC28J60_SPIMODE);
+ SPI_SETBITS(priv->spi, 8);
+#ifdef CONFIG_ENC28J60_FREQUENCY
+ SPI_SETFREQUENCY(priv->spi, CONFIG_ENC28J60_FREQUENCY);
+#endif
}
/* Select ENC28J60 chip. */
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);
-
- /* Now make sure that the SPI bus is configured for the ENC28J60 (it
- * might have gotten configured for a different device while unlocked)
- */
-
- SPI_SETMODE(priv->spi, CONFIG_ENC28J60_SPIMODE);
- SPI_SETBITS(priv->spi, 8);
-#ifdef CONFIG_ENC28J60_FREQUENCY
- SPI_SETFREQUENCY(priv->spi, CONFIG_ENC28J60_FREQUENCY);
-#endif
}
#endif
@@ -667,10 +672,10 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
* 8 dummy bits, and 8 to clock in the PHY/MAC data.
*/
- (void)SPI_SEND(priv->spi, 0); /* Clock in the dummy byte */
+ (void)SPI_SEND(priv->spi, 0); /* Clock in the dummy byte */
}
- rddata = SPI_SEND(priv->spi, 0); /* Clock in the data */
+ rddata = SPI_SEND(priv->spi, 0); /* Clock in the data */
/* De-select ENC28J60 chip */