summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-11 21:44:00 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-11 21:44:00 +0000
commitfb8e18e23e3997e065de381bf9b6b54e0c6f331f (patch)
tree0c3fde628a9f6c055b56564c2bf7fb0040567f04
parent260d6c44c8f61cf6bae4b74291825c1eebd17651 (diff)
downloadpx4-nuttx-fb8e18e23e3997e065de381bf9b6b54e0c6f331f.tar.gz
px4-nuttx-fb8e18e23e3997e065de381bf9b6b54e0c6f331f.tar.bz2
px4-nuttx-fb8e18e23e3997e065de381bf9b6b54e0c6f331f.zip
Add a driver for the SST30VF NOR FLASH parts
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5640 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog1
-rw-r--r--nuttx/Documentation/NuttX.html40
-rw-r--r--nuttx/TODO50
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_gpio.c3
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_usbdev.c29
-rw-r--r--nuttx/drivers/mtd/Kconfig63
-rw-r--r--nuttx/drivers/mtd/Make.defs4
-rw-r--r--nuttx/drivers/mtd/skeleton.c32
-rw-r--r--nuttx/include/nuttx/mtd.h35
9 files changed, 207 insertions, 50 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 79e2723ce..0b23207da 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4177,3 +4177,4 @@
Aimonen.
* configs/stm32f3discovery/nsh/defconfig: Disable SPI. It is nto
used.
+ * drivers/mtd/sst39vf: Add a driver for the SST29VF NOR FLASH parts.
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index b04150e1b..eb0998533 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: February 2, 2013</p>
+ <p>Last Updated: February 11, 2013</p>
</td>
</tr>
</table>
@@ -1679,7 +1679,7 @@ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
<li><a href="#arm920t">ARM920T</a> (1) </li>
<li><a href="#arm926ejs">ARM926EJS</a> (3) </li>
<li><a href="#armcortexm3">ARM Cortex-M3</a> (16)</li>
- <li><a href="#armcortexm4">ARM Cortex-M4</a> (5)</li>
+ <li><a href="#armcortexm4">ARM Cortex-M4</a> (6)</li>
</ul>
<li>Atmel AVR
<ul>
@@ -2143,7 +2143,7 @@ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
<td><br></td>
<td>
<p>
- <b>STMicro STM32F100x</b>.
+ <b>STMicro STM32F100x (STM32 F1 &quot;Value Line&quot;Family)</b>.
Chip support for these STM32 &quot;Value Line&quot; family was contributed by Mike Smith and users have reported that they have successful brought up NuttX on there proprietary boards using this logic.
This logic was extended to support the <i>high density</i> STM32F100RC chips by Freddie Chopin
However, there is <i>no</i> specific board support for this chip families in the NuttX source tree.
@@ -2158,7 +2158,7 @@ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
<td><br></td>
<td>
<p>
- <b>STMicro STM32F103x</b>.
+ <b>STMicro STM32F103x (STM32 F1 Family)</b>.
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.
@@ -2235,7 +2235,7 @@ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
<td><br></td>
<td>
<p>
- <b>STMicro STM32F107x</b>.
+ <b>STMicro STM32F107x (STM32 F1 &quot;Connectivity Line&quot; family)</b>.
Chip support for the STM32 F1 &quot;Connectivity Line&quot; family has been present in NuttX for some time and users have reported that they have successful brought up NuttX on there proprietary boards using this logic.
</p>
<p>
@@ -2270,7 +2270,7 @@ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
<td><br></td>
<td>
<p>
- <b>STMicro STM32F207IG</b>.
+ <b>STMicro STM32F207IG (STM32 F2 family)</b>.
Support for the STMicro STM3220G-EVAL development board was contributed by Gary Teravskis and first released in NuttX-6.16.
</p>
<ul>
@@ -2521,7 +2521,7 @@ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
<td><br></td>
<td>
<p>
- <b>STMicro STM3240G-EVAL</b>.
+ <b>STMicro STM3240G-EVAL (STM32 F4 family)</b>.
This port uses the STMicro STM3240G-EVAL board featuring the STM32F407IGH6 MCU.
Refer to the <a href="http://www.st.com/internet/evalboard/product/252216.jsp">STMicro web site</a> for further information about this board.
</p>
@@ -2563,7 +2563,7 @@ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
<td><br></td>
<td>
<p>
- <b>STMicro STM32F4-Discovery</b>.
+ <b>STMicro STM32F4-Discovery (STM32 F4 family)</b>.
This port uses the STMicro STM32F4-Discovery board featuring the STM32F407VGT6 MCU.
Refer to the <a href="http://www.st.com/internet/evalboard/product/252419.jsp">STMicro web site</a> for further information about this board.
</p>
@@ -2571,7 +2571,29 @@ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
<p>
<b>STATUS:</b>
The basic port for the STM32F4-Discovery was contributed by Mike Smith and was first released in NuttX-6.14.
- Drivers listed for the STM3240G-EVAL may be usable on this plaform as well.
+ All drivers listed for the STM3240G-EVAL are usable on this plaform as well.
+ </p>
+ </ul>
+ </td>
+</tr>
+<tr>
+ <td><br></td>
+ <td><hr></td>
+</tr>
+<tr>
+ <td><br></td>
+ <td>
+ <p>
+ <b>STMicro STM32F3-Discovery (STM32 F3 family)</b>.
+ This port uses the STMicro STM32F3-Discovery board featuring the STM32F303VCT6 MCU (STM32 F3 family).
+ Refer to the <a href="http://www.st.com/internet/evalboard/product/254044.jsp">STMicro web site</a> for further information about this board.
+ </p>
+ <ul>
+ <p>
+ <b>STATUS:</b>
+ The basic port for the STM32F3-Discover was first released in NuttX-6.26.
+ Many of the drivers previously released for the STM32 F1, Value Line, and F2 and F4 may be usable on this plaform as well.
+ New drivers will be required for ADC and I2C which are very different on this platform.
</p>
</ul>
</td>
diff --git a/nuttx/TODO b/nuttx/TODO
index ac2afa775..96472bc8f 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -31,7 +31,7 @@ nuttx/
(0) ARM/LPC43x (arch/arm/src/lpc43xx/)
(3) ARM/STR71x (arch/arm/src/str71x/)
(3) ARM/LM3S6918 (arch/arm/src/lm/)
- (5) ARM/STM32 (arch/arm/src/stm32/)
+ (6) ARM/STM32 (arch/arm/src/stm32/)
(3) AVR (arch/avr)
(0) Intel x86 (arch/x86)
(5) 8051 / MCS51 (arch/8051/)
@@ -696,6 +696,39 @@ o USB (drivers/usbdev, drivers/usbhost)
class drivers. (2) The logic in the STM32 F4 OTG FS device driver
has been extended to provide this data. Updates are still needed
to other drivers.
+
+ Here is an overview of the required changes:
+ New two buffers in driver structure:
+
+ 1. The existing EP0 setup request buffer (ctrlreq, 8 bytes)
+ 2. A new EP0 data buffer to driver state structure (ep0data,
+ max packetsize)
+
+ Add a new state:
+
+ 3. Waiting for EP0 setup OUT data (EP0STATE_SETUP_OUT)
+
+ General logic flow:
+
+ 1. When an EP0 SETUP packet is received:
+ - Read the request into EP0 setup request buffer (ctrlreq,
+ 8 bytes)
+ - If this is an OUT request with data length, set the EP0
+ state to EP0STATE_SETUP_OUT and wait to receive data on
+ EP0.
+ - Otherwise, the SETUP request may be processed now (or,
+ in the case of the F4 driver, at the conclusion of the
+ SETUP phase).
+ 2. When EP0 the EP0 OUT DATA packet is received:
+ - Verify state is EP0STATE_SETUP_OUT
+ - Read the request into the EP0 data buffer (ep0data, max
+ packet size)
+ - Now process the previously buffered SETUP request along
+ with the OUT data.
+ 3. When the setup packet is dispatched to the class driver,
+ the OUT data must be passed as the final parameter in the
+ call.
+
Status: Open
Priority: High for class drivers that need EP0 data. For example, the
CDC/ACM serial driver might need the line coding data (that
@@ -1493,6 +1526,21 @@ o ARM/STM32 (arch/arm/src/stm32/)
Status: Open
Priority: Low
+ Title: USB DRIVER IN STM32F4DISCVORY usbnsh CONFIGURATION
+ Description: The USB device driver is not reliable in the
+ configs/stm32f3discovery/upnsh configuration. When a large
+ volume of serial data is sent (for example, by entering
+ 'help' from the NSH command line), the driver hangs. This
+ looks like an improperly handled output data overrun problem.
+
+ This is a surprising since this same driver has worked with
+ the STM32 F1 for some time using the Mass Storage driver
+ which has considerably higher data rates. So this seems to
+ be some particular issue with the way that the CDC/ACM driver
+ sends data through the driver.
+ Status: Open
+ Priority: Medium High
+
o AVR (arch/avr)
^^^^^^^^^^^^^^
diff --git a/nuttx/arch/arm/src/stm32/stm32_gpio.c b/nuttx/arch/arm/src/stm32/stm32_gpio.c
index a191ee532..d22c38f6c 100644
--- a/nuttx/arch/arm/src/stm32/stm32_gpio.c
+++ b/nuttx/arch/arm/src/stm32/stm32_gpio.c
@@ -54,7 +54,8 @@
#include "chip.h"
#include "stm32_gpio.h"
-#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F40XX)
+#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F30XX) || \
+ defined(CONFIG_STM32_STM32F40XX)
# include "chip/stm32_syscfg.h"
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_usbdev.c b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
index 6036eb3d5..42321bb63 100644
--- a/nuttx/arch/arm/src/stm32/stm32_usbdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
@@ -76,6 +76,10 @@
# define CONFIG_USBDEV_EP0_MAXSIZE 64
#endif
+#ifndef CONFIG_USBDEV_SETUP_MAXDATASIZE
+# define CONFIG_USBDEV_SETUP_MAXDATASIZE CONFIG_USBDEV_EP0_MAXSIZE
+#endif
+
#ifndef CONFIG_USB_PRI
# define CONFIG_USB_PRI NVIC_SYSH_PRIORITY_DEFAULT
#endif
@@ -335,7 +339,6 @@ struct stm32_usbdev_s
/* STM32-specific fields */
- struct usb_ctrlreq_s ctrl; /* Last EP0 request */
uint8_t ep0state; /* State of EP0 (see enum stm32_ep0state_e) */
uint8_t rsmstate; /* Resume state (see enum stm32_rsmstate_e) */
uint8_t nesofs; /* ESOF counter (for resume support) */
@@ -347,6 +350,30 @@ struct stm32_usbdev_s
uint16_t txstatus; /* " " " " " " " " */
uint16_t imask; /* Current interrupt mask */
+ /* E0 SETUP data buffering.
+ *
+ * ctrl:
+ * The 8-byte SETUP request is received on the EP0 OUT endpoint and is
+ * saved.
+ *
+ * ep0data
+ * For OUT SETUP requests, the SETUP data phase must also complete before
+ * the SETUP command can be processed. The pack receipt logic will save
+ * the accompanying EP0 IN data in ep0data[] before the SETUP command is
+ * processed.
+ *
+ * For IN SETUP requests, the DATA phase will occurr AFTER the SETUP
+ * control request is processed. In that case, ep0data[] may be used as
+ * the response buffer.
+ *
+ * ep0datlen
+ * Lenght of OUT DATA received in ep0data[] (Not used with OUT data)
+ */
+
+ struct usb_ctrlreq_s ctrl; /* Last EP0 request */
+ uint8_t ep0data[CONFIG_USBDEV_SETUP_MAXDATASIZE];
+ uint16_t ep0datlen;
+
/* The endpoint list */
struct stm32_ep_s eplist[STM32_NENDPOINTS];
diff --git a/nuttx/drivers/mtd/Kconfig b/nuttx/drivers/mtd/Kconfig
index ae656c474..1449a7125 100644
--- a/nuttx/drivers/mtd/Kconfig
+++ b/nuttx/drivers/mtd/Kconfig
@@ -7,55 +7,60 @@ config MTD_AT24XX
default n
select I2C
+if MTD_AT24XX
+
config AT24XX_SIZE
int "at24xx size(kByte)"
default 64
- depends on MTD_AT24XX
config AT24XX_ADDR
hex "at24xx i2c address"
default 0x50
- depends on MTD_AT24XX
-
+
+endif
+
config MTD_AT45DB
bool "SPI-based AT45DB flash"
default n
select SPI
-
+
+if MTD_AT45DB
+
config AT45DB_FREQUENCY
int "at45db frequency"
default 1000000
- depends on MTD_AT45DB
-
+
config AT45DB_PREWAIT
bool "enables higher performance write logic"
default y
- depends on MTD_AT45DB
config AT45DB_PWRSAVE
bool "enables power save"
default n
- depends on MTD_AT45DB
+
+endif
config MTD_MP25P
bool "SPI-based M25P FLASH"
default n
select SPI
+if MTD_MP25P
+
config MP25P_SPIMODE
int "MP25P SPI mode"
default 0
- depends on MTD_MP25P
config MP25P_MANUFACTURER
hex "MP25P manufacturers ID"
default 0x20
- depends on MTD_MP25P
---help---
Various manufacturers may have produced the parts. 0x20 is the manufacturer ID
for the STMicro MP25x serial FLASH. If, for example, you are using the a Macronix
International MX25 serial FLASH, the correct manufacturer ID would be 0xc2.
+endif
+
config MTD_RAMTRON
bool "SPI-based RAMTRON NVRAM Devices FM25V10"
default n
@@ -72,62 +77,78 @@ config MTD_SST25
default n
select SPI
+if MTD_SST25
+
config SST25_SPIMODE
int "SST25 SPI Mode"
default 0
- depends on MTD_SST25
config SST25_SPIFREQUENCY
int "SST25 SPI Frequency"
default 20000000
- depends on MTD_SST25
config SST25_READONLY
bool "SST25 Read-Only FLASH"
default n
- depends on MTD_SST25
config SST25_SECTOR512
bool "Simulate 512 byte Erase Blocks"
default n
- depends on MTD_SST25
config SST25_SLOWWRITE
bool
default y
- depends on MTD_SST25
config SST25_SLOWREAD
bool
default n
- depends on MTD_SST25
+
+endif
+
+config MTD_SST39FV
+ bool "SST39FV NOR FLASH"
+ default n
+ ---help---
+ Selects 16-bit SST NOR FLASH. This includes support for:
+
+ SST39FV1601/SST39FV1602: 2Mb
+ SST39FV3201/SST39FV3202: 4Mb
+
+if MTD_SST39FV
+
+config SST39VF_BASE_ADDRESS
+ hex "SST39FV bass address"
+ default 0x00000000
+ ---help---
+ This is the address where the SST29VF FLASH can be found in memory.
+
+endif
config MTD_W25
bool "SPI-based W25 FLASH"
default n
select SPI
+if MTD_W25
+
config W25_SPIMODE
int "W25 SPI Mode"
default 0
- depends on MTD_W25
config W25_SPIFREQUENCY
int "W25 SPI Frequency"
default 20000000
- depends on MTD_W25
config W25_READONLY
bool "W25 Read-Only FLASH"
default n
- depends on MTD_W25
config W25_SECTOR512
bool "Simulate 512 byte Erase Blocks"
default n
- depends on MTD_W25
config W25_SLOWREAD
bool
default n
- depends on MTD_W25
+
+endif
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
index 3102f1447..350d055f6 100644
--- a/nuttx/drivers/mtd/Make.defs
+++ b/nuttx/drivers/mtd/Make.defs
@@ -49,6 +49,10 @@ ifeq ($(CONFIG_MTD_SST25),y)
CSRCS += sst25.c
endif
+ifeq ($(CONFIG_MTD_SST39FV),y)
+CSRCS += sst39vf.c
+endif
+
ifeq ($(CONFIG_MTD_W25),y)
CSRCS += w25.c
endif
diff --git a/nuttx/drivers/mtd/skeleton.c b/nuttx/drivers/mtd/skeleton.c
index a2fb98238..15ddac1ef 100644
--- a/nuttx/drivers/mtd/skeleton.c
+++ b/nuttx/drivers/mtd/skeleton.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/mtd/skeleton.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -84,11 +84,12 @@ static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
+/* This structure holds the state of the MTD driver */
static struct skel_dev_s g_skeldev =
{
{ skel_erase, skel_rbead, skel_bwrite, skel_read, skel_ioctl },
- /* Initialization of any other implemenation specific data goes here */
+ /* Initialization of any other implementation specific data goes here */
};
/****************************************************************************
@@ -97,9 +98,14 @@ static struct skel_dev_s g_skeldev =
/****************************************************************************
* Name: skel_erase
+ *
+ * Description:
+ * Erase several blocks, each of the size previously reported.
+ *
****************************************************************************/
-static int skel_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks)
+static int skel_erase(FAR struct mtd_dev_s *dev, off_t startblock,
+ size_t nblocks)
{
FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
@@ -115,6 +121,10 @@ static int skel_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock
/****************************************************************************
* Name: skel_bread
+ *
+ * Description:
+ * Read the specified number of blocks into the user provided buffer.
+ *
****************************************************************************/
static ssize_t skel_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
@@ -136,6 +146,10 @@ static ssize_t skel_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nb
/****************************************************************************
* Name: skel_bwrite
+ *
+ * Description:
+ * Write the specified number of blocks from the user provided buffer.
+ *
****************************************************************************/
static ssize_t skel_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
@@ -157,6 +171,10 @@ static ssize_t skel_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n
/****************************************************************************
* Name: skel_read
+ *
+ * Description:
+ * Read the specified number of bytes to the user provided buffer.
+ *
****************************************************************************/
static ssize_t skel_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
@@ -197,7 +215,7 @@ static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
{
case MTDIOC_GEOMETRY:
{
- FAR struct mtd_geometry_s *geo = (FARstruct mtd_geometry_s *)arg;
+ FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)arg;
if (geo)
{
/* Populate the geometry structure with information need to know
@@ -236,9 +254,9 @@ static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
case MTDIOC_BULKERASE:
{
- /* Erase the entire device */
+ /* Erase the entire device */
- ret = OK;
+ ret = OK;
}
break;
@@ -265,7 +283,7 @@ static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
*
****************************************************************************/
-void skel_initialize(void)
+FAR struct mtd_dev_s *skel_initialize(void)
{
/* Perform initialization as necessary */
diff --git a/nuttx/include/nuttx/mtd.h b/nuttx/include/nuttx/mtd.h
index ff48d313f..db77a8c82 100644
--- a/nuttx/include/nuttx/mtd.h
+++ b/nuttx/include/nuttx/mtd.h
@@ -123,7 +123,8 @@ struct mtd_dev_s
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -145,7 +146,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN int ftl_initialize(int minor, FAR struct mtd_dev_s *mtd);
+int ftl_initialize(int minor, FAR struct mtd_dev_s *mtd);
/****************************************************************************
* Name: flash_eraseall
@@ -156,7 +157,7 @@ EXTERN int ftl_initialize(int minor, FAR struct mtd_dev_s *mtd);
*
****************************************************************************/
-EXTERN int flash_eraseall(FAR const char *driver);
+int flash_eraseall(FAR const char *driver);
/****************************************************************************
* Name: rammtd_initialize
@@ -170,7 +171,7 @@ EXTERN int flash_eraseall(FAR const char *driver);
*
****************************************************************************/
-EXTERN FAR struct mtd_dev_s *rammtd_initialize(FAR uint8_t *start, size_t size);
+FAR struct mtd_dev_s *rammtd_initialize(FAR uint8_t *start, size_t size);
/****************************************************************************
* Name: m25p_initialize
@@ -182,7 +183,7 @@ EXTERN FAR struct mtd_dev_s *rammtd_initialize(FAR uint8_t *start, size_t size);
*
****************************************************************************/
-EXTERN FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev);
+FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev);
/****************************************************************************
* Name: at45db_initialize
@@ -194,7 +195,7 @@ EXTERN FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev);
*
****************************************************************************/
-EXTERN FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *dev);
+FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *dev);
/****************************************************************************
* Name: at24c_initialize
@@ -206,7 +207,7 @@ EXTERN FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *dev);
*
****************************************************************************/
-EXTERN FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev);
+FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev);
/****************************************************************************
* Name: sst25_initialize
@@ -218,7 +219,21 @@ EXTERN FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev);
*
****************************************************************************/
-EXTERN FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev);
+FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev);
+
+/****************************************************************************
+ * Name: sst39vf_initialize
+ *
+ * Description:
+ * Create and initialize an MTD device instance assuming an SST39VF NOR
+ * FLASH device at the configured address in memory. MTD devices are not
+ * registered in the file system, but are created as instances that can
+ * be bound to other functions (such as a block or character driver front
+ * end).
+ *
+ ****************************************************************************/
+
+FAR struct mtd_dev_s *sst39vf_initialize(void);
/****************************************************************************
* Name: w25_initialize
@@ -230,9 +245,9 @@ EXTERN FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev);
*
****************************************************************************/
-EXTERN FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *dev);
+FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *dev);
-EXTERN FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev);
+FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev);
#undef EXTERN
#ifdef __cplusplus