summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-09-12 15:45:12 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-09-12 15:45:12 -0600
commit659a3c79af1cc0974825f82f2274f2ae07e8f6f2 (patch)
treea36f372213448d29fc91416104fb1440bc77bbc0
parentdbf4924d9ab3aaafe496857cd22045b936826ace (diff)
downloadpx4-nuttx-659a3c79af1cc0974825f82f2274f2ae07e8f6f2.tar.gz
px4-nuttx-659a3c79af1cc0974825f82f2274f2ae07e8f6f2.tar.bz2
px4-nuttx-659a3c79af1cc0974825f82f2274f2ae07e8f6f2.zip
SAMA5: Beginning of EMAC and GMAC register definition header files
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sam_emac.h244
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sam_gmac.h61
-rw-r--r--nuttx/configs/sama5d3x-ek/README.txt60
4 files changed, 366 insertions, 2 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 0b5464710..f40770775 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -5539,4 +5539,7 @@
(2013-9-12).
* arch/arm/src/sama5/sama5_twi.c: Clean up some errors that
only occur with CONFIG_DEBUG_I2C (2013-9-12).
+ * arch/arm/src/sama5/chip/sam_emac.h and sam_gmac.h: Register
+ definition files for the SAMA5 EMAC and GMAC peripherals
+ (incomplete on the initial commit) (2013-9-12).
diff --git a/nuttx/arch/arm/src/sama5/chip/sam_emac.h b/nuttx/arch/arm/src/sama5/chip/sam_emac.h
new file mode 100644
index 000000000..c71ca5c9e
--- /dev/null
+++ b/nuttx/arch/arm/src/sama5/chip/sam_emac.h
@@ -0,0 +1,244 @@
+/************************************************************************************
+ * arch/arm/src/sama5/chip/sam_emac.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_SAMA5_CHIP_SAM_EMAC_H
+#define __ARCH_ARM_SRC_SAMA5_CHIP_SAM_EMAC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/sam_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* EMAC Register Offsets ************************************************************/
+
+#define SAM_EMAC_NCR_OFFSET 0x0000 /* Network Control Register */
+#define SAM_EMAC_NCFGR_OFFSET 0x0004 /* Network Configuration Register */
+#define SAM_EMAC_NSR_OFFSET 0x0008 /* Network Status Register */
+ /* 0x000c-0x0010 Reserved */
+#define SAM_EMAC_TSR_OFFSET 0x0014 /* Transmit Status Register */
+#define SAM_EMAC_RBQP_OFFSET 0x0018 /* Receive Buffer Queue Pointer Register */
+#define SAM_EMAC_TBQP_OFFSET 0x001c /* Transmit Buffer Queue Pointer Register */
+#define SAM_EMAC_RSR_OFFSET 0x0020 /* Receive Status Register */
+#define SAM_EMAC_ISR_OFFSET 0x0024 /* Interrupt Status Register */
+#define SAM_EMAC_IER_OFFSET 0x0028 /* Interrupt Enable Register */
+#define SAM_EMAC_IDR_OFFSET 0x002c /* Interrupt Disable Register */
+#define SAM_EMAC_IMR_OFFSET 0x0030 /* Interrupt Mask Register */
+#define SAM_EMAC_MAN_OFFSET 0x0034 /* Phy Maintenance Register */
+#define SAM_EMAC_PTR_OFFSET 0x0038 /* Pause Time Register */
+#define SAM_EMAC_PFR_OFFSET 0x003c /* Pause Frames Received Register */
+#define SAM_EMAC_FTO_OFFSET 0x0040 /* Frames Transmitted Ok Register */
+#define SAM_EMAC_SCF_OFFSET 0x0044 /* Single Collision Frames Register */
+#define SAM_EMAC_MCF_OFFSET 0x0048 /* Multiple Collision Frames Register */
+#define SAM_EMAC_FRO_OFFSET 0x004c /* Frames Received Ok Register */
+#define SAM_EMAC_FCSE_OFFSET 0x0050 /* Frame Check Sequence Errors Register */
+#define SAM_EMAC_ALE_OFFSET 0x0054 /* Alignment Errors Register */
+#define SAM_EMAC_DTF_OFFSET 0x0058 /* Deferred Transmission Frames Register */
+#define SAM_EMAC_LCOL_OFFSET 0x005c /* Late Collisions Register */
+#define SAM_EMAC_ECOL_OFFSET 0x0060 /* Excessive Collisions Register */
+#define SAM_EMAC_TUND_OFFSET 0x0064 /* Transmit Underrun Errors Register */
+#define SAM_EMAC_CSE_OFFSET 0x0068 /* Carrier Sense Errors Register */
+#define SAM_EMAC_RRE_OFFSET 0x006c /* Receive Resource Errors Register */
+#define SAM_EMAC_ROV_OFFSET 0x0070 /* Receive Overrun Errors Register */
+#define SAM_EMAC_RSE_OFFSET 0x0074 /* Receive Symbol Errors Register */
+#define SAM_EMAC_ELE_OFFSET 0x0078 /* Excessive Length Errors Register */
+#define SAM_EMAC_RJA_OFFSET 0x007c /* Receive Jabbers Register */
+#define SAM_EMAC_USF_OFFSET 0x0080 /* Undersize Frames Register */
+#define SAM_EMAC_STE_OFFSET 0x0084 /* SQE Test Errors Register */
+#define SAM_EMAC_RLE_OFFSET 0x0088 /* Received Length Field Mismatch Register */
+#define SAM_EMAC_HRB_OFFSET 0x0090 /* Hash Register Bottom [31:0] Register */
+#define SAM_EMAC_HRT_OFFSET 0x0094 /* Hash Register Top [63:32] Register */
+#define SAM_EMAC_SA1B_OFFSET 0x0098 /* Specific Address 1 Bottom Register */
+#define SAM_EMAC_SA1T_OFFSET 0x009c /* Specific Address 1 Top Register */
+#define SAM_EMAC_SA2B_OFFSET 0x00a0 /* Specific Address 2 Bottom Register */
+#define SAM_EMAC_SA2T_OFFSET 0x00a4 /* Specific Address 2 Top Register */
+#define SAM_EMAC_SA3B_OFFSET 0x00a8 /* Specific Address 3 Bottom Register */
+#define SAM_EMAC_SA3T_OFFSET 0x00ac /* Specific Address 3 Top Register */
+#define SAM_EMAC_SA4B_OFFSET 0x00b0 /* Specific Address 4 Bottom Register */
+#define SAM_EMAC_SA4T_OFFSET 0x00b4 /* Specific Address 4 Top Register */
+#define SAM_EMAC_TID_OFFSET 0x00b8 /* Type ID Checking Register */
+#define SAM_EMAC_USRIO_OFFSET 0x00c0 /* User Input/Output Register */
+#define SAM_EMAC_WOL_OFFSET 0x00c4 /* Wake on LAN Register */
+ /* 0x00c8-0x00fc Reserved */
+
+/* EMAC Register Addresses **********************************************************/
+
+#define SAM_EMAC_NCR (SAM_EMAC_VBASE+SAM_EMAC_NCR_OFFSET)
+#define SAM_EMAC_NCFGR (SAM_EMAC_VBASE+SAM_EMAC_NCFGR_OFFSET)
+#define SAM_EMAC_NSR (SAM_EMAC_VBASE+SAM_EMAC_NSR_OFFSET)
+#define SAM_EMAC_TSR (SAM_EMAC_VBASE+SAM_EMAC_TSR_OFFSET)
+#define SAM_EMAC_RBQP (SAM_EMAC_VBASE+SAM_EMAC_RBQP_OFFSET)
+#define SAM_EMAC_TBQP (SAM_EMAC_VBASE+SAM_EMAC_TBQP_OFFSET)
+#define SAM_EMAC_RSR (SAM_EMAC_VBASE+SAM_EMAC_RSR_OFFSET)
+#define SAM_EMAC_ISR (SAM_EMAC_VBASE+SAM_EMAC_ISR_OFFSET)
+#define SAM_EMAC_IER (SAM_EMAC_VBASE+SAM_EMAC_IER_OFFSET)
+#define SAM_EMAC_IDR (SAM_EMAC_VBASE+SAM_EMAC_IDR_OFFSET)
+#define SAM_EMAC_IMR (SAM_EMAC_VBASE+SAM_EMAC_IMR_OFFSET)
+#define SAM_EMAC_MAN (SAM_EMAC_VBASE+SAM_EMAC_MAN_OFFSET)
+#define SAM_EMAC_PTR (SAM_EMAC_VBASE+SAM_EMAC_PTR_OFFSET)
+#define SAM_EMAC_PFR (SAM_EMAC_VBASE+SAM_EMAC_PFR_OFFSET)
+#define SAM_EMAC_FTO (SAM_EMAC_VBASE+SAM_EMAC_FTO_OFFSET)
+#define SAM_EMAC_SCF (SAM_EMAC_VBASE+SAM_EMAC_SCF_OFFSET)
+#define SAM_EMAC_MCF (SAM_EMAC_VBASE+SAM_EMAC_MCF_OFFSET)
+#define SAM_EMAC_FRO (SAM_EMAC_VBASE+SAM_EMAC_FRO_OFFSET)
+#define SAM_EMAC_FCSE (SAM_EMAC_VBASE+SAM_EMAC_FCSE_OFFSET)
+#define SAM_EMAC_ALE (SAM_EMAC_VBASE+SAM_EMAC_ALE_OFFSET)
+#define SAM_EMAC_DTF (SAM_EMAC_VBASE+SAM_EMAC_DTF_OFFSET)
+#define SAM_EMAC_LCOL (SAM_EMAC_VBASE+SAM_EMAC_LCOL_OFFSET)
+#define SAM_EMAC_ECOL (SAM_EMAC_VBASE+SAM_EMAC_ECOL_OFFSET)
+#define SAM_EMAC_TUND (SAM_EMAC_VBASE+SAM_EMAC_TUND_OFFSET)
+#define SAM_EMAC_CSE (SAM_EMAC_VBASE+SAM_EMAC_CSE_OFFSET)
+#define SAM_EMAC_RRE (SAM_EMAC_VBASE+SAM_EMAC_RRE_OFFSET)
+#define SAM_EMAC_ROV (SAM_EMAC_VBASE+SAM_EMAC_ROV_OFFSET)
+#define SAM_EMAC_RSE (SAM_EMAC_VBASE+SAM_EMAC_RSE_OFFSET)
+#define SAM_EMAC_ELE (SAM_EMAC_VBASE+SAM_EMAC_ELE_OFFSET)
+#define SAM_EMAC_RJA (SAM_EMAC_VBASE+SAM_EMAC_RJA_OFFSET)
+#define SAM_EMAC_USF (SAM_EMAC_VBASE+SAM_EMAC_USF_OFFSET)
+#define SAM_EMAC_STE (SAM_EMAC_VBASE+SAM_EMAC_STE_OFFSET)
+#define SAM_EMAC_RLE (SAM_EMAC_VBASE+SAM_EMAC_RLE_OFFSET)
+#define SAM_EMAC_HRB (SAM_EMAC_VBASE+SAM_EMAC_HRB_OFFSET)
+#define SAM_EMAC_HRT (SAM_EMAC_VBASE+SAM_EMAC_HRT_OFFSET)
+#define SAM_EMAC_SA1B (SAM_EMAC_VBASE+SAM_EMAC_SA1B_OFFSET)
+#define SAM_EMAC_SA1T (SAM_EMAC_VBASE+SAM_EMAC_SA1T_OFFSET)
+#define SAM_EMAC_SA2B (SAM_EMAC_VBASE+SAM_EMAC_SA2B_OFFSET)
+#define SAM_EMAC_SA2T (SAM_EMAC_VBASE+SAM_EMAC_SA2T_OFFSET)
+#define SAM_EMAC_SA3B (SAM_EMAC_VBASE+SAM_EMAC_SA3B_OFFSET)
+#define SAM_EMAC_SA3T (SAM_EMAC_VBASE+SAM_EMAC_SA3T_OFFSET)
+#define SAM_EMAC_SA4B (SAM_EMAC_VBASE+SAM_EMAC_SA4B_OFFSET)
+#define SAM_EMAC_SA4T (SAM_EMAC_VBASE+SAM_EMAC_SA4T_OFFSET)
+#define SAM_EMAC_TID (SAM_EMAC_VBASE+SAM_EMAC_TID_OFFSET)
+#define SAM_EMAC_USRIO (SAM_EMAC_VBASE+SAM_EMAC_USRIO_OFFSET)
+#define SAM_EMAC_WOL (SAM_EMAC_VBASE+SAM_EMAC_WOL_OFFSET)
+
+/* EMAC Register Bit Definitions ****************************************************/
+
+/* Network Control Register */
+#define EMAC_NCR_
+/* Network Configuration Register */
+#define EMAC_NCFGR_
+/* Network Status Register */
+#define EMAC_NSR_
+/* Transmit Status Register */
+#define EMAC_TSR_
+/* Receive Buffer Queue Pointer Register */
+#define EMAC_RBQP_
+/* Transmit Buffer Queue Pointer Register */
+#define EMAC_TBQP_
+/* Receive Status Register */
+#define EMAC_RSR_
+/* Interrupt Status Register */
+#define EMAC_ISR_
+/* Interrupt Enable Register */
+#define EMAC_IER_
+/* Interrupt Disable Register */
+#define EMAC_IDR_
+/* Interrupt Mask Register */
+#define EMAC_IMR_
+/* Phy Maintenance Register */
+#define EMAC_MAN_
+/* Pause Time Register */
+#define EMAC_PTR_
+/* Pause Frames Received Register */
+#define EMAC_PFR_
+/* Frames Transmitted Ok Register */
+#define EMAC_FTO_
+/* Single Collision Frames Register */
+#define EMAC_SCF_
+/* Multiple Collision Frames Register */
+#define EMAC_MCF_
+/* Frames Received Ok Register */
+#define EMAC_FRO_
+/* Frame Check Sequence Errors Register */
+#define EMAC_FCSE_
+/* Alignment Errors Register */
+#define EMAC_ALE_
+/* Deferred Transmission Frames Register */
+#define EMAC_DTF_
+/* Late Collisions Register */
+#define EMAC_LCOL_
+/* Excessive Collisions Register */
+#define EMAC_ECOL_
+/* Transmit Underrun Errors Register */
+#define EMAC_TUND_
+/* Carrier Sense Errors Register */
+#define EMAC_CSE_
+/* Receive Resource Errors Register */
+#define EMAC_RRE_
+/* Receive Overrun Errors Register */
+#define EMAC_ROV_
+/* Receive Symbol Errors Register */
+#define EMAC_RSE_
+/* Excessive Length Errors Register */
+#define EMAC_ELE_
+/* Receive Jabbers Register */
+#define EMAC_RJA_
+/* Undersize Frames Register */
+#define EMAC_USF_
+/* SQE Test Errors Register */
+#define EMAC_STE_
+/* Received Length Field Mismatch Register */
+#define EMAC_RLE_
+/* Hash Register Bottom [31:0] Register */
+#define EMAC_HRB_
+/* Hash Register Top [63:32] Register */
+#define EMAC_HRT_
+/* Specific Address 1 Bottom Register */
+#define EMAC_SA1B_
+/* Specific Address 1 Top Register */
+#define EMAC_SA1T_
+/* Specific Address 2 Bottom Register */
+#define EMAC_SA2B_
+/* Specific Address 2 Top Register */
+#define EMAC_SA2T_
+/* Specific Address 3 Bottom Register */
+#define EMAC_SA3B_
+/* Specific Address 3 Top Register */
+#define EMAC_SA3T_
+/* Specific Address 4 Bottom Register */
+#define EMAC_SA4B_
+/* Specific Address 4 Top Register */
+#define EMAC_SA4T_
+/* Type ID Checking Register */
+#define EMAC_TID_
+/* User Input/Output Register */
+#define EMAC_USRIO_
+/* Wake on LAN Register */
+#define EMAC_WOL_
+
+#endif /* __ARCH_ARM_SRC_SAMA5_CHIP_SAM_EMAC_H */
diff --git a/nuttx/arch/arm/src/sama5/chip/sam_gmac.h b/nuttx/arch/arm/src/sama5/chip/sam_gmac.h
new file mode 100644
index 000000000..a3a86a775
--- /dev/null
+++ b/nuttx/arch/arm/src/sama5/chip/sam_gmac.h
@@ -0,0 +1,61 @@
+/************************************************************************************
+ * arch/arm/src/sama5/chip/sam_gmac.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_SAMA5_CHIP_SAM_GMAC_H
+#define __ARCH_ARM_SRC_SAMA5_CHIP_SAM_GMAC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/sam_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* GMAC Register Offsets ************************************************************/
+
+#define SAM_GMAC_
+
+/* GMAC Register Addresses *********************************************************/
+
+#define SAM_GMAC_
+
+/* GMAC Register Bit Definitions ***************************************************/
+
+#define GMAC_
+
+#endif /* __ARCH_ARM_SRC_SAMA5_CHIP_SAM_GMAC_H */
diff --git a/nuttx/configs/sama5d3x-ek/README.txt b/nuttx/configs/sama5d3x-ek/README.txt
index 6913b1f23..feb105314 100644
--- a/nuttx/configs/sama5d3x-ek/README.txt
+++ b/nuttx/configs/sama5d3x-ek/README.txt
@@ -1802,6 +1802,55 @@ Configurations
CONFIG_I2CTOOL_MAXBUS=2 : TWI2 has the maximum bus number 2
CONFIG_I2CTOOL_DEFFREQ=100000 : Pick a consistent frequency
+ The I2C tool has extensive help that can be accessed as follows:
+
+ nsh> i2c help
+ Usage: i2c <cmd> [arguments]
+ Where <cmd> is one of:
+
+ Show help : ?
+ List busses : bus
+ List devices : dev [OPTIONS] <first> <last>
+ Read register : get [OPTIONS] [<repititions>]
+ Show help : help
+ Write register: set [OPTIONS] <value> [<repititions>]
+ Verify access : verf [OPTIONS] [<value>] [<repititions>]
+
+ Where common "sticky" OPTIONS include:
+ [-a addr] is the I2C device address (hex). Default: 03 Current: 03
+ [-b bus] is the I2C bus number (decimal). Default: 0 Current: 0
+ [-r regaddr] is the I2C device register address (hex). Default: 00 Current: 00
+ [-w width] is the data width (8 or 16 decimal). Default: 8 Current: 8
+ [-s|n], send/don't send start between command and data. Default: -n Current: -n
+ [-i|j], Auto increment|don't increment regaddr on repititions. Default: NO Current: NO
+ [-f freq] I2C frequency. Default: 100000 Current: 100000
+
+ NOTES:
+ o Arguments are "sticky". For example, once the I2C address is
+ specified, that address will be re-used until it is changed.
+
+ WARNING:
+ o The I2C dev command may have bad side effects on your I2C devices.
+ Use only at your own risk.
+
+ As an eample, the I2C dev comman can be used to list all devices
+ responding on TWI0 (the default) like this:
+
+ nsh> i2c dev 0x03 0x77
+ 0 1 2 3 4 5 6 7 8 9 a b c d e f
+ 00: -- -- -- -- -- -- -- -- -- -- -- -- --
+ 10: -- -- -- -- -- -- -- -- -- -- 1a -- -- -- -- --
+ 20: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
+ 30: -- -- -- -- -- -- -- -- -- 39 -- -- -- 3d -- --
+ 40: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
+ 50: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
+ 60: 60 -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
+ 70: -- -- -- -- -- -- -- --
+ nsh>
+
+ Address 0x1a is the WM8904. Address 0x39 is the SIL9022A. I am
+ not sure what is at address 0x3d and 0x60
+
STATUS:
PCK FREQUENCY
2013-7-19: This configuration (as do the others) run at 396MHz.
@@ -1855,9 +1904,16 @@ Configurations
UDPHS
2013-9-5: The UDPHS driver is basically functional.
- AT24 SERIAL EEPROM
+ I2C
2013-9-12: I have been unusuccessful getting the external serial
- EEPROM to work.
+ AT24 EEPROM to work. I am pretty sure that this is a problem with
+ my external AT24 board (the TWI0 bus hangs when the AT24 is plugged
+ in). I will skip the AT24 integration since it is not on the critical
+ path at the moment.
+ 2013-9-12: The I2C tool, however, seems to work well. It succesfully
+ enumerates the devices on the bus and successfully exchanges a few
+ commands. The real test of the come later when a real I2C device is
+ integrated.
ostest:
This configuration directory, performs a simple OS test using