summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-04-01 14:10:54 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-04-01 14:10:54 +0000
commit9bd404cc67fe1ad52599e3a89036344d78cbdf55 (patch)
treef9ba0087c22ce77836be92bededc9ca2359e5d5a
parente3fe81779352589122b14c80287122aef30a2e14 (diff)
downloadpx4-nuttx-9bd404cc67fe1ad52599e3a89036344d78cbdf55.tar.gz
px4-nuttx-9bd404cc67fe1ad52599e3a89036344d78cbdf55.tar.bz2
px4-nuttx-9bd404cc67fe1ad52599e3a89036344d78cbdf55.zip
Add support for CAN1 and CAN2 to zkit-arm-1769. From M. Kannan
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5808 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/Documentation/NuttX.html27
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h4
-rw-r--r--nuttx/configs/zkit-arm-1769/include/board.h2
-rw-r--r--nuttx/configs/zkit-arm-1769/src/up_can.c50
5 files changed, 61 insertions, 25 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index db7917a23..32da72a42 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4484,3 +4484,6 @@
sleep mode (2013-03-31).
* arch/arm/src/stm32: Add architecure support for the STM32 F427/F437
chips. Contributed by Mike Smith (2014-4-01).
+ * configs/zkit-arm-1769/src/up_can.c: Add support for both CAN1
+ and CAN2. Contributed by M.Kannan (2014-4-01).
+
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index d7b797e83..6ba0c95a0 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: March 15, 2013</p>
+ <p>Last Updated: April 1, 2013</p>
</td>
</tr>
</table>
@@ -2418,8 +2418,10 @@ nsh>
<ul>
<b>STATUS:</b>
This is still a work in progess.
- At present there is a working basic port with OS verification and Nuttshell (<a href="http://www.nuttx.org/Documentation/NuttShell.html">NSH</a>) configurations.
- This is stablilizing nicely now and the next steps will involve getting solid driver support for the SD slot and the LCD on the WaveShare board.
+ At present there is a working basic port with OS verification, Nuttshell (<a href="http://www.nuttx.org/Documentation/NuttShell.html">NSH</a>) configurations, and a graphics test configuration.
+ The NSH configuration includes verfied support for (DMA-based) SD card interface.
+ SDRAM is working.
+ The LCD driver is not functional as of this writing, but is actively underwork and is expected to be available in the NuttX-6.27 release.
</ul>
</td>
</tr>
@@ -2552,6 +2554,25 @@ nsh>
<td><br></td>
<td>
<p>
+ <b>STMicro STM32 F427/437</b>.
+ General architectural support was provided for the F427/437 family in NuttX 4.27.
+ Specific support includes the STM32F427I, STM32F427Z, and STM32F427V chips.
+ This is <i>architecture-only</i> support, meaning that support for the boards with these chips is available, but not support for any publically available boards is included..
+ This support was contributed by Mike Smith.
+ </p>
+ <p>
+ The F427/f37 port adds (1) additional SPI ports, (2) additional UART ports, (3) analog and digital noise filters on the I2C ports, (4) up to 2MB of flash, (5) an additional lower-power mode for the internal voltage regulator, (6) a new prescaling option for timer clock, (7) a larger FSMSC write FIFO, and (8) additional crypto modes (F437 only).
+ </p>
+ </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.
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
index 50f262237..5f20e6b77 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
@@ -67,10 +67,10 @@
#define GPIO_UART0_RXD (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN3)
#define GPIO_AD0p6 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN3)
#define GPIO_I2S_RXCLK_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
-#define GPIO_CAN2_RD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
+#define GPIO_CAN2_RD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
#define GPIO_CAP2p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
#define GPIO_I2S_RXWS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
-#define GPIO_CAN2_TD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
+#define GPIO_CAN2_TD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
#define GPIO_CAP2p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
#define GPIO_I2S_RXSDA_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
#define GPIO_SSP1_SSEL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
diff --git a/nuttx/configs/zkit-arm-1769/include/board.h b/nuttx/configs/zkit-arm-1769/include/board.h
index 54362fc03..63dd4d914 100644
--- a/nuttx/configs/zkit-arm-1769/include/board.h
+++ b/nuttx/configs/zkit-arm-1769/include/board.h
@@ -231,6 +231,8 @@
#define GPIO_CAN1_RD GPIO_CAN1_RD_1
#define GPIO_CAN1_TD GPIO_CAN1_TD_1
+#define GPIO_CAN2_RD GPIO_CAN2_RD_2
+#define GPIO_CAN2_TD GPIO_CAN2_TD_2
#define GPIO_I2C1_SDA GPIO_I2C0_SDA
#define GPIO_I2C1_SCL GPIO_I2C0_SCL
#define GPIO_SSP1_SCK GPIO_SSP1_SCK_1
diff --git a/nuttx/configs/zkit-arm-1769/src/up_can.c b/nuttx/configs/zkit-arm-1769/src/up_can.c
index 0f50cd146..eaec05696 100644
--- a/nuttx/configs/zkit-arm-1769/src/up_can.c
+++ b/nuttx/configs/zkit-arm-1769/src/up_can.c
@@ -5,7 +5,7 @@
* Copyright (C) 2013 Zilogic Systems. All rights reserved.
* Author: Raashid Muhammed <code@zilogic.com>
*
- * Based on configs/olimex-lpc1766stk/src/up_can.c
+ * Based on configs/olimex-lpc1766stk/src/up_can.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -63,21 +63,9 @@
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
+#define CAN_PORT1 1
+#define CAN_PORT2 2
-#if defined(CONFIG_LPC17_CAN1) && defined(CONFIG_LPC17_CAN2)
-# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
-# undef CONFIG_LPC17_CAN2
-#endif
-
-#ifdef CONFIG_LPC17_CAN2
-# warning "CAN2 is not connected on the ZKIT-ARM-1769"
-#endif
-
-#ifdef CONFIG_LPC17_CAN1
-# define CAN_PORT 1
-#else
-# define CAN_PORT 2
-#endif
/* Debug ***************************************************************************/
/* Non-standard debug that may be enabled just for testing CAN */
@@ -121,23 +109,45 @@ int can_devinit(void)
if (!initialized)
{
- /* Call lpc17_caninitialize() to get an instance of the CAN interface */
+#ifdef CONFIG_LPC17_CAN1
+ /* Call lpc17_caninitialize() to get an instance of the CAN1 interface */
- can = lpc17_caninitialize(CAN_PORT);
+ can = lpc17_caninitialize(CAN_PORT1);
if (can == NULL)
{
- candbg("ERROR: Failed to get CAN interface\n");
+ candbg("ERROR: Failed to get CAN1 interface\n");
return -ENODEV;
}
- /* Register the CAN driver at "/dev/can0" */
+ /* Register the CAN1 driver at "/dev/can0" */
ret = can_register("/dev/can0", can);
if (ret < 0)
{
- candbg("ERROR: can_register failed: %d\n", ret);
+ candbg("ERROR: CAN1 register failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+#ifdef CONFIG_LPC17_CAN2
+ /* Call lpc17_caninitialize() to get an instance of the CAN2 interface */
+
+ can = lpc17_caninitialize(CAN_PORT2);
+ if (can == NULL)
+ {
+ candbg("ERROR: Failed to get CAN2 interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN2 driver at "/dev/can1" */
+
+ ret = can_register("/dev/can1", can);
+ if (ret < 0)
+ {
+ candbg("ERROR: CAN2 register failed: %d\n", ret);
return ret;
}
+#endif
/* Now we are initialized */