summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-09-12 09:47:31 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-09-12 09:47:31 -0600
commit3d9119730bf374ffa1409d0d491d4cdd55deca1a (patch)
tree1b663b33710888528b193ea01da85a99d1826a3c
parent527a8b61f84554d93f565a24317bf69602045006 (diff)
downloadpx4-nuttx-3d9119730bf374ffa1409d0d491d4cdd55deca1a.tar.gz
px4-nuttx-3d9119730bf374ffa1409d0d491d4cdd55deca1a.tar.bz2
px4-nuttx-3d9119730bf374ffa1409d0d491d4cdd55deca1a.zip
SAMA5D3x-EK: Add support for (external) AT 24C512 EEPROM
-rw-r--r--nuttx/configs/sama5d3x-ek/Kconfig50
-rw-r--r--nuttx/configs/sama5d3x-ek/README.txt79
-rw-r--r--nuttx/configs/sama5d3x-ek/src/Makefile8
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_at24.c157
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_at25.c15
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_nsh.c21
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h72
7 files changed, 377 insertions, 25 deletions
diff --git a/nuttx/configs/sama5d3x-ek/Kconfig b/nuttx/configs/sama5d3x-ek/Kconfig
index 1480a2076..d5a669557 100644
--- a/nuttx/configs/sama5d3x-ek/Kconfig
+++ b/nuttx/configs/sama5d3x-ek/Kconfig
@@ -43,19 +43,19 @@ config SAMA5_NOR_START
will, instead, immediately start the program in NOR FLASH.
config SAMA5_AT25_AUTOMOUNT
- bool "AT25 auto-mount"
+ bool "AT25 serial FLASH auto-mount"
default n
depends on NSH_ARCHINIT && SAMA5_SPI0 && MTD_AT25
---help---
Automatically initialize the AT25 SPI FLASH driver when NSH starts.
choice
- prompt "AT25 configuration"
+ prompt "AT25 serial FLASH configuration"
default SAMA5_AT25_FTL
depends on SAMA5_AT25_AUTOMOUNT
config SAMA5_AT25_FTL
- bool "Create AT25 block driver"
+ bool "Create AT25 Serial FLASH block driver"
---help---
Create the MTD driver for the AT25 and "wrap" the AT25 is a standard
block driver that could then, for example, be mounted using FAT or
@@ -63,7 +63,7 @@ config SAMA5_AT25_FTL
be no wear-leveling.
config SAMA5_AT25_NXFFS
- bool "Create AT25 NXFFS file system"
+ bool "Create AT25 serial FLASH NXFFS file system"
depends on FS_NXFFS
---help---
Create the MTD driver for the AT25 and and mount the AT25 device as
@@ -71,4 +71,46 @@ config SAMA5_AT25_NXFFS
NXFFS is that it can be very slow.
endchoice
+
+config SAMA5_AT24_AUTOMOUNT
+ bool "AT24 Serial EEPROM auto-mount"
+ default n
+ depends on NSH_ARCHINIT && SAMA5_TWI0 && MTD_AT24XX
+ ---help---
+ Automatically initialize the AT24 SPI EEPROM driver when NSH starts.
+
+ The Serial EEPROM was mounted on an external adaptor board and
+ connected to the SAMA5D3x-EK thusly:
+
+ - VCC -- VCC
+ - GND -- GND
+ - TWCK0(PA31) -- SCL
+ - TWD0(PA30) -- SDA
+
+ By default, PA30 and PA31 are SWJ-DP pins, it can be used as a pin
+ for TWI peripheral in the end application.
+
+choice
+ prompt "AT24 serial EPPROM configuration"
+ default SAMA5_AT24_FTL
+ depends on SAMA5_AT24_AUTOMOUNT
+
+config SAMA5_AT24_FTL
+ bool "Create AT24 block driver"
+ ---help---
+ Create the MTD driver for the AT24 and "wrap" the AT24 is a standard
+ block driver that could then, for example, be mounted using FAT or
+ any other file system. Any file system may be used, but there will
+ be no wear-leveling.
+
+config SAMA5_AT24_NXFFS
+ bool "Create AT24 NXFFS file system"
+ depends on FS_NXFFS
+ ---help---
+ Create the MTD driver for the AT24 and and mount the AT24 device as
+ a wear-leveling, NuttX FLASH file system (NXFFS). The downside of
+ NXFFS is that it can be very slow.
+
+endchoice
+
endif
diff --git a/nuttx/configs/sama5d3x-ek/README.txt b/nuttx/configs/sama5d3x-ek/README.txt
index 6b8bb11f1..25e785f6e 100644
--- a/nuttx/configs/sama5d3x-ek/README.txt
+++ b/nuttx/configs/sama5d3x-ek/README.txt
@@ -625,8 +625,9 @@ AT24 Serial EEPROM
A AT24C512 Serial EEPPROM was used for tested I2C. There are other I2C/TWI
devices on-board, but the serial EEPROM is the simplest test.
- The Serial EEPROM was mounted on an external adaptor board and connected to
- the SAMA5D3x-EK thusly:
+ There is, however, no AT24 EEPROM on board the SAMA5D3x-EK: The Serial
+ EEPROM was mounted on an external adaptor board and connected to the
+ SAMA5D3x-EK thusly:
- VCC -- VCC
- GND -- GND
@@ -1465,18 +1466,18 @@ Configurations
order to enable the AT25 FLASH chip select.
You can then format the AT25 FLASH for a FAT file system and mount
- the file system at /mnt/sdcard using these NSH commands:
+ the file system at /mnt/at25 using these NSH commands:
nsh> mkfatfs /dev/mtdblock0
- nsh> mount -t vfat /dev/mtdblock0 /mnt/sdcard
+ nsh> mount -t vfat /dev/mtdblock0 /mnt/at25
Then you an use the FLASH as a normal FAT file system:
- nsh> echo "This is a test" >/mnt/sdcard/atest.txt
- nsh> ls -l /mnt/sdcard
- /mnt/sdcard:
+ nsh> echo "This is a test" >/mnt/at25/atest.txt
+ nsh> ls -l /mnt/at25
+ /mnt/at25:
-rw-rw-rw- 16 atest.txt
- nsh> cat /mnt/sdcard/atest.txt
+ nsh> cat /mnt/at25/atest.txt
This is a test
9. Enabling HSMCI support. The SAMA5D3x-EK provides a two SD memory card
@@ -1708,6 +1709,68 @@ Configurations
asynchronous with the trace output and, hence, difficult to
interpret.
+ 13. AT24 Serial EEPROM. A AT24C512 Serial EEPPROM was used for tested
+ I2C. There are other I2C/TWI devices on-board, but the serial
+ EEPROM is the simplest test.
+
+ There is, however, no AT24 EEPROM on board the SAMA5D3x-EK: The
+ serial EEPROM was mounted on an external adaptor board and
+ connected to the SAMA5D3x-EK thusly:
+
+ - VCC -- VCC
+ - GND -- GND
+ - TWCK0(PA31) -- SCL
+ - TWD0(PA30) -- SDA
+
+ By default, PA30 and PA31 are SWJ-DP pins, it can be used as a pin
+ for TWI peripheral in the end application.
+
+ The following configuration settings were used:
+
+ System Type -> SAMA5 Peripheral Support
+ CONFIG_SAMA5_TWI0=y : Enable TWI0
+
+ System Type -> TWI device driver options
+ SAMA5_TWI0_FREQUENCY=100000 : Select a TWI frequency
+
+ Device Drivers -> I2C Driver Support
+ CONFIG_I2C=y : Enable I2C support
+ CONFIG_I2C_TRANSFER=y : Driver supports the transfer() method
+ CONFIG_I2C_WRITEREAD=y : Driver supports the writeread() method
+
+ Device Drivers -> Memory Technology Device (MTD) Support
+ CONFIG_MTD=y : Enable MTD support
+ CONFIG_MTD_AT24XX=y : Enable the AT24 driver
+ CONFIG_AT24XX_SIZE=512 : Specifies the AT 24C512 part
+ CONFIG_AT24XX_ADDR=0x53 : AT24 I2C address
+
+ Application Configuration -> NSH Library
+ CONFIG_NSH_ARCHINIT=y : NSH board-initialization
+
+ File systems
+ CONFIG_NXFFS=y : Enables the NXFFS file system
+ CONFIG_NXFFS_PREALLOCATED=y : Required
+ : Other defaults are probably OK
+
+ Board Selection
+ CONFIG_SAMA5_AT24_AUTOMOUNT=y : Mounts AT24 for NSH
+ CONFIG_SAMA5_AT24_NXFFS=y : Mount the AT24 using NXFFS
+
+ You can then format the AT25 FLASH for a FAT file system and mount
+ the file system at /mnt/at24 using these NSH commands:
+
+ nsh> mkfatfs /dev/mtdblock0
+ nsh> mount -t vfat /dev/mtdblock0 /mnt/at24
+
+ Then you an use the FLASH as a normal FAT file system:
+
+ nsh> echo "This is a test" >/mnt/at24/atest.txt
+ nsh> ls -l /mnt/at24
+ /mnt/at24:
+ -rw-rw-rw- 16 atest.txt
+ nsh> cat /mnt/at24/atest.txt
+ This is a test
+
STATUS:
2013-7-19: This configuration (as do the others) run at 396MHz.
The SAMA5D3 can run at 536MHz. I still need to figure out the
diff --git a/nuttx/configs/sama5d3x-ek/src/Makefile b/nuttx/configs/sama5d3x-ek/src/Makefile
index b23b290d1..29209f68a 100644
--- a/nuttx/configs/sama5d3x-ek/src/Makefile
+++ b/nuttx/configs/sama5d3x-ek/src/Makefile
@@ -67,8 +67,16 @@ CSRCS += nor_main.c
endif
ifeq ($(CONFIG_MTD_AT25),y)
+ifeq ($(CONFIG_SAMA5_SPI0),y)
CSRCS += sam_at25.c
endif
+endif
+
+ifeq ($(CONFIG_MTD_AT24XX),y)
+ifeq ($(CONFIG_SAMA5_TWI0),y)
+CSRCS += sam_at24.c
+endif
+endif
ifeq ($(CONFIG_SAMA5_HSMCI0),y)
CSRCS += sam_hsmci.c
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_at24.c b/nuttx/configs/sama5d3x-ek/src/sam_at24.c
new file mode 100644
index 000000000..fbcefbc26
--- /dev/null
+++ b/nuttx/configs/sama5d3x-ek/src/sam_at24.c
@@ -0,0 +1,157 @@
+/****************************************************************************
+ * config/sama5d3x-ek/src/sam_at24.c
+ *
+ * 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
+ * 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.
+ *
+ ****************************************************************************/
+
+/* AT24 Serial EEPROM
+ *
+ * A AT24C512 Serial EEPPROM was used for tested I2C. There are other I2C/TWI
+ * devices on-board, but the serial EEPROM is the simplest test.
+ *
+ * There is, however, no AT24 EEPROM on board the SAMA5D3x-EK: The Serial
+ * EEPROM was mounted on an external adaptor board and connected to the
+ * SAMA5D3x-EK thusly:
+ *
+ * - VCC -- VCC
+ * - GND -- GND
+ * - TWCK0(PA31) -- SCL
+ * - TWD0(PA30) -- SDA
+ *
+ * By default, PA30 and PA31 are SWJ-DP pins, it can be used as a pin for TWI
+ * peripheral in the end application.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/mount.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/i2c.h>
+#include <nuttx/mtd.h>
+#include <nuttx/fs/nxffs.h>
+
+#include "sama5d3x-ek.h"
+
+#ifdef HAVE_AT24
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_at24_initialize
+ *
+ * Description:
+ * Initialize and configure the AT24 serial EEPROM
+ *
+ ****************************************************************************/
+
+int sam_at24_initialize(int minor)
+{
+ FAR struct i2c_dev_s *i2c;
+ FAR struct mtd_dev_s *mtd;
+ static bool initialized = false;
+ int ret;
+
+ /* Have we already initialized? */
+
+ if (!initialized)
+ {
+ /* No.. Get the I2C bus driver */
+
+ i2c = up_i2cinitialize(AT24_BUS);
+ if (!i2c)
+ {
+ fdbg("ERROR: Failed to initialize I2C port %d\n", AT24_BUS);
+ return -ENODEV;
+ }
+
+ /* Now bind the I2C interface to the AT24 I2C EEPROM driver */
+
+ mtd = at24c_initialize(i2c);
+ if (!mtd)
+ {
+ fdbg("ERROR: Failed to bind I2C port %d to the AT24 EEPROM driver\n");
+ return -ENODEV;
+ }
+
+#if defined(CONFIG_SAMA5_AT24_FTL)
+ /* And finally, use the FTL layer to wrap the MTD driver as a block driver */
+
+ ret = ftl_initialize(AT24_MINOR, mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Initialize the FTL layer\n");
+ return ret;
+ }
+
+#elif defined(CONFIG_SAMA5_AT24_NXFFS)
+ /* Initialize to provide NXFFS on the MTD interface */
+
+ ret = nxffs_initialize(mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: NXFFS initialization failed: %d\n", -ret);
+ return ret;
+ }
+
+ /* Mount the file system at /mnt/at24 */
+
+ ret = mount(NULL, "/mnt/at24", "nxffs", 0, NULL);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to mount the NXFFS volume: %d\n", errno);
+ return ret;
+ }
+#endif
+ /* Now we are intialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif /* HAVE_AT24 */
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_at25.c b/nuttx/configs/sama5d3x-ek/src/sam_at25.c
index 11f1b886d..680c11c0f 100644
--- a/nuttx/configs/sama5d3x-ek/src/sam_at25.c
+++ b/nuttx/configs/sama5d3x-ek/src/sam_at25.c
@@ -46,14 +46,11 @@
#include <errno.h>
#include <debug.h>
-#ifdef CONFIG_SAMA5_SPI0
-# include <nuttx/spi/spi.h>
-# include <nuttx/mtd.h>
-# include <nuttx/fs/nxffs.h>
-
-# include "sam_spi.h"
-#endif
+#include <nuttx/spi/spi.h>
+#include <nuttx/mtd.h>
+#include <nuttx/fs/nxffs.h>
+#include "sam_spi.h"
#include "sama5d3x-ek.h"
#ifdef HAVE_AT25
@@ -70,7 +67,7 @@
* Name: sam_at25_initialize
*
* Description:
- * Initialize and configure the AT25 SPI Flash
+ * Initialize and configure the AT25 serial FLASH
*
****************************************************************************/
@@ -106,7 +103,7 @@ int sam_at25_initialize(int minor)
#if defined(CONFIG_SAMA5_AT25_FTL)
/* And finally, use the FTL layer to wrap the MTD driver as a block driver */
- ret = ftl_initialize(CONFIG_NSH_MMCSDMINOR, mtd);
+ ret = ftl_initialize(AT25_MINOR, mtd);
if (ret < 0)
{
fdbg("ERROR: Initialize the FTL layer\n");
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_nsh.c b/nuttx/configs/sama5d3x-ek/src/sam_nsh.c
index 833241086..27c72158a 100644
--- a/nuttx/configs/sama5d3x-ek/src/sam_nsh.c
+++ b/nuttx/configs/sama5d3x-ek/src/sam_nsh.c
@@ -86,14 +86,14 @@
int nsh_archinitialize(void)
{
-#if defined(HAVE_AT25) || defined(HAVE_HSMCI) || defined(HAVE_USBHOST) || \
- defined(HAVE_USBMONITOR)
+#if defined(HAVE_AT25) || defined(HAVE_AT24) || defined(HAVE_HSMCI) || \
+ defined(HAVE_USBHOST) || defined(HAVE_USBMONITOR)
int ret;
#endif
+#ifdef HAVE_AT25
/* Initialize the AT25 driver */
-#ifdef HAVE_AT25
ret = sam_at25_initialize(AT25_MINOR);
if (ret < 0)
{
@@ -102,8 +102,21 @@ int nsh_archinitialize(void)
}
#endif
+#ifdef HAVE_AT24
+ /* Initialize the AT24 driver */
+
+ ret = sam_at24_initialize(AT24_MINOR);
+ if (ret < 0)
+ {
+ message("ERROR: sam_at24_initialize failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
#ifdef HAVE_HSMCI
#ifdef CONFIG_SAMA5_HSMCI0
+ /* Initialize the HSMCI0 driver */
+
ret = sam_hsmci_initialize(HSMCI0_SLOTNO, HSMCI0_MINOR);
if (ret < 0)
{
@@ -114,6 +127,8 @@ int nsh_archinitialize(void)
#endif
#ifdef CONFIG_SAMA5_HSMCI1
+ /* Initialize the HSMCI1 driver */
+
ret = sam_hsmci_initialize(HSMCI1_SLOTNO, HSMCI1_MINOR);
if (ret < 0)
{
diff --git a/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h b/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
index 7138bb726..2dd506c37 100644
--- a/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
+++ b/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
@@ -56,6 +56,7 @@
/* Configuration ************************************************************/
#define HAVE_HSMCI 1
+#define HAVE_AT24 1
#define HAVE_AT25 1
#define HAVE_USBHOST 1
#define HAVE_USBDEV 1
@@ -101,6 +102,10 @@
* us what to do with it by setting one of these.
*/
+#ifndef CONFIG_FS_NXFFS
+# undef CONFIG_SAMA5_AT25_NXFFS
+#endif
+
#if !defined(CONFIG_SAMA5_AT25_FTL) && !defined(CONFIG_SAMA5_AT25_NXFFS)
# undef HAVE_AT25
#endif
@@ -111,12 +116,65 @@
# undef CONFIG_SAMA5_AT25_NXFFS
#endif
+/* AT24 Serial EEPROM
+ *
+ * A AT24C512 Serial EEPPROM was used for tested I2C. There are other I2C/TWI
+ * devices on-board, but the serial EEPROM is the simplest test.
+ *
+ * There is, however, no AT24 EEPROM on board the SAMA5D3x-EK: The Serial
+ * EEPROM was mounted on an external adaptor board and connected to the
+ * SAMA5D3x-EK thusly:
+ *
+ * - VCC -- VCC
+ * - GND -- GND
+ * - TWCK0(PA31) -- SCL
+ * - TWD0(PA30) -- SDA
+ *
+ * By default, PA30 and PA31 are SWJ-DP pins, it can be used as a pin for TWI
+ * peripheral in the end application.
+ */
+
+#define AT24_BUS 0
+
+#if !defined(CONFIG_MTD_AT24XX) || !defined(CONFIG_SAMA5_TWI0)
+# undef HAVE_AT24
+#endif
+
+/* Can't support AT25 features if mountpoints are disabled or if we were not
+ * asked to mount the AT25 part
+ */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_SAMA5_AT24_AUTOMOUNT)
+# undef HAVE_AT24
+#endif
+
+/* If we are going to mount the AT25, then they user must also have told
+ * us what to do with it by setting one of these.
+ */
+
+#ifndef CONFIG_FS_NXFFS
+# undef CONFIG_SAMA5_AT24_NXFFS
+#endif
+
+#if !defined(CONFIG_SAMA5_AT24_FTL) && !defined(CONFIG_SAMA5_AT24_NXFFS)
+# undef HAVE_AT24
+#endif
+
+#if defined(CONFIG_SAMA5_AT24_FTL) && defined(CONFIG_SAMA5_AT24_NXFFS)
+# warning Both CONFIG_SAMA5_AT24_FTL and CONFIG_SAMA5_AT24_NXFFS are set
+# warning Ignoring CONFIG_SAMA5_AT24_NXFFS
+# undef CONFIG_SAMA5_AT24_NXFFS
+#endif
+
/* Assign minor device numbers. We will also use MINOR number 0 for the AT25.
* It should appear as /dev/mtdblock0
*/
#ifdef HAVE_AT25
# define AT25_MINOR 0
+# define AT24_MINOR 1
+#else
+# define AT24_MINOR 0
#endif
/* MMC/SD minor numbers: The NSH device minor extended is extened to support
@@ -440,7 +498,7 @@ void sam_sdram_config(void);
* Name: sam_at25_initialize
*
* Description:
- * Initialize and configure the AT25 SPI Flash
+ * Initialize and configure the AT25 serial FLASH
*
****************************************************************************/
@@ -449,6 +507,18 @@ int sam_at25_initialize(int minor);
#endif
/****************************************************************************
+ * Name: sam_at24_initialize
+ *
+ * Description:
+ * Initialize and configure the AT24 serial EEPROM
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_AT24
+int sam_at24_initialize(int minor);
+#endif
+
+/****************************************************************************
* Name: sam_hsmci_initialize
*
* Description: