summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html60
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/Make.defs13
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs6
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_can.c761
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pwm.c2
-rw-r--r--nuttx/configs/README.txt9
-rwxr-xr-xnuttx/configs/hymini-stm32v/README.txt14
-rwxr-xr-xnuttx/configs/stm3210e-eval/README.txt11
-rwxr-xr-xnuttx/configs/stm3240g-eval/README.txt11
-rwxr-xr-xnuttx/configs/stm3240g-eval/dhcpd/defconfig18
-rwxr-xr-xnuttx/configs/stm3240g-eval/nettest/defconfig18
-rwxr-xr-xnuttx/configs/stm3240g-eval/nsh/defconfig18
-rwxr-xr-xnuttx/configs/stm3240g-eval/ostest/defconfig18
-rw-r--r--nuttx/drivers/Makefile7
-rw-r--r--nuttx/drivers/can.c29
-rw-r--r--nuttx/include/nuttx/can.h23
17 files changed, 986 insertions, 34 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 061be118e..288bf2029 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2286,5 +2286,7 @@
* drivers/mtd/mp25x.c: Add ability to use different SPI modes and different
manufacturers codes. Fix a error in the wait for not busy (submitted by
Mohammad Elwakeel.
+ * arch/arm/src/stm32/stm32_can.c. Add a low-level STM32 CAN driver. (Initial
+ check is incomplete).
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index 293b7d683..f68dc3d79 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -12,7 +12,7 @@
<h1><big><font color="#3c34ec">
<i>NuttX RTOS Porting Guide</i>
</font></big></h1>
- <p>Last Updated: December 19, 2011</p>
+ <p>Last Updated: December 21, 2011</p>
</td>
</tr>
</table>
@@ -127,7 +127,8 @@
<a href="#usbhostdrivers">6.3.9 USB Host-Side Drivers</a><br>
<a href="#usbdevdrivers">6.3.10 USB Device-Side Drivers</a><br>
<a href="#analogdrivers">6.3.11 Analog (ADC/DAC) Drivers</a><br>
- <a href="#pwmdrivers">6.3.12 PWM Drivers</a>
+ <a href="#pwmdrivers">6.3.12 PWM Drivers</a><br>
+ <a href="#candrivers">6.3.13 CAN Drivers</a>
</ul>
<a href="#pwrmgmt">6.4 Power Management</a>
<ul>
@@ -3212,23 +3213,55 @@ extern void up_ledoff(int led);
A &quot;lower half&quot;, platform-specific driver that implements the low-level timer controls to implement the PWM functionality.
</li>
</ol>
-
+<p>
+ Files supporting PWM can be found in the following locations:
+</p>
<ul>
- <li>
+ <li><b>Interface Definition</b>.
The header file for the NuttX PWM driver reside at <code>include/nuttx/pwm.h</code>.
This header file includes both the application level interface to the PWM driver as well as the interface between the &quot;upper half&quot; and &quot;lower half&quot; drivers.
The PWM module uses a standard character driver framework.
However, since the PWM driver is a devices control interface and not a data transfer interface,
the majority of the functionality available to the application is implemented in driver ioctl calls.
</li>
- <li>
+ <li><b>&quot;Upper Half&quot; Driver</b>.
The generic, &quot;upper half&quot; PWM driver resides at <code>drivers/pwm.c</code>.
</li>
- <li>
- Platform-specific PWM drivers reside in <code>arch/</code><i>&lt;architecture&gt;</i><code>/src/</code><i>&lt;chip&gt;</i> directory for the specific processor <i>&lt;architecture&gt;</i> and for the specific <i>&lt;chip&gt;</i> analog peripheral devices.
+ <li><b>&quot;Lower Half&quot; Drivers</b>.
+ Platform-specific PWM drivers reside in <code>arch/</code><i>&lt;architecture&gt;</i><code>/src/</code><i>&lt;chip&gt;</i> directory for the specific processor <i>&lt;architecture&gt;</i> and for the specific <i>&lt;chip&gt;</i> PWM peripheral devices.
</li>
</ul>
+<h3><a name="candrivers">6.3.13 CAN Drivers</a></h3>
+<p>
+ NuttX supports only a very low-level CAN driver.
+ This driver supports only the data exchange and does not include any high-level CAN protocol.
+ The NuttX CAN driver is split into two parts:
+</p>
+<ol>
+ <li>
+ An &quot;upper half&quot;, generic driver that provides the comman CAN interface to application level code, and
+ </li>
+ <li>
+ A &quot;lower half&quot;, platform-specific driver that implements the low-level timer controls to implement the CAN functionality.
+ </li>
+</ol>
+<p>
+ Files supporting CAN can be found in the following locations:
+</p>
+<ul>
+ <li><b>Interface Definition</b>.
+ The header file for the NuttX CAN driver reside at <code>include/nuttx/can.h</code>.
+ This header file includes both the application level interface to the CAN driver as well as the interface between the &quot;upper half&quot; and &quot;lower half&quot; drivers.
+ The CAN module uses a standard character driver framework.
+ </li>
+ <li><b>&quot;Upper Half&quot; Driver</b>.
+ The generic, &quot;upper half&quot; CAN driver resides at <code>drivers/can.c</code>.
+ </li>
+ <li><b>&quot;Lower Half&quot; Drivers</b>.
+ Platform-specific CAN drivers reside in <code>arch/</code><i>&lt;architecture&gt;</i><code>/src/</code><i>&lt;chip&gt;</i> directory for the specific processor <i>&lt;architecture&gt;</i> and for the specific <i>&lt;chip&gt;</i> CAN peripheral devices.
+ </li>
+</ul>
<h2><a name="pwrmgmt">6.4 Power Management</a></h2>
@@ -4332,6 +4365,19 @@ build
</li>
</ul>
+<h3>CAN driver</h3>
+<ul>
+ <li>
+ <code>CONFIG_CAN</code>: Enables CAN support
+ </li>
+ <li>
+ <code>CONFIG_CAN_FIFOSIZE</code>: The size of the circular buffer of CAN messages. Default: 8
+ </li>
+ <li>
+ <code>CONFIG_CAN_NPENDINGRTR</code>: The size of the list of pending RTR requests. Default: 4
+ </li>
+</ul>
+
<h3>SPI driver</h3>
<ul>
<li>
diff --git a/nuttx/arch/arm/src/lpc17xx/Make.defs b/nuttx/arch/arm/src/lpc17xx/Make.defs
index 34591e531..56aef87fd 100755
--- a/nuttx/arch/arm/src/lpc17xx/Make.defs
+++ b/nuttx/arch/arm/src/lpc17xx/Make.defs
@@ -2,7 +2,7 @@
# arch/arm/src/lpc17xx/Make.defs
#
# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
@@ -57,10 +57,9 @@ endif
# Required LPC17xx files
CHIP_ASRCS =
-CHIP_CSRCS = lpc17_allocateheap.c lpc17_can.c lpc17_clockconfig.c \
- lpc17_clrpend.c lpc17_gpio.c lpc17_i2c.c lpc17_idle.c lpc17_irq.c \
- lpc17_lowputc.c lpc17_serial.c lpc17_spi.c lpc17_ssp.c lpc17_start.c \
- lpc17_timerisr.c
+CHIP_CSRCS = lpc17_allocateheap.c lpc17_clockconfig.c lpc17_clrpend.c \
+ lpc17_gpio.c lpc17_i2c.c lpc17_idle.c lpc17_irq.c lpc17_lowputc.c \
+ lpc17_serial.c lpc17_spi.c lpc17_ssp.c lpc17_start.c lpc17_timerisr.c
# Configuration-dependent LPC17xx files
@@ -90,6 +89,10 @@ CHIP_CSRCS += lpc17_ethernet.c
endif
endif
+ifeq ($(CONFIG_CAN),y)
+CHIP_CSRCS += lpc17_can.c
+endif
+
ifeq ($(CONFIG_LPC17_ADC),y)
CHIP_CSRCS += lpc17_adc.c
endif
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index d877516ab..0d046ebc3 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -2,7 +2,7 @@
# arch/arm/src/stm32/Make.defs
#
# Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
@@ -87,6 +87,10 @@ ifeq ($(CONFIG_PWM),y)
CHIP_CSRCS += stm32_pwm.c
endif
+ifeq ($(CONFIG_CAN),y)
+CHIP_CSRCS += stm32_can.c
+endif
+
ifeq ($(CONFIG_DEBUG),y)
CHIP_CSRCS += stm32_dumpgpio.c
endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_can.c b/nuttx/arch/arm/src/stm32/stm32_can.c
new file mode 100755
index 000000000..404bf4a1a
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_can.c
@@ -0,0 +1,761 @@
+/************************************************************************************
+ * arch/arm/src/stm32/stm32_can.c
+ *
+ * Copyright (C) 2011 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.
+ *
+ ************************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+#include <nuttx/arch.h>
+#include <nuttx/can.h>
+
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "os_internal.h"
+
+#include "chip.h"
+#include "stm32_internal.h"
+#include "stm32_can.h"
+
+#ifdef CONFIG_CAN
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+/* Up to 2 CAN interfaces are supported */
+
+#if STM32_NCAN < 2
+# undef CONFIG_STM32_CAN2
+#endif
+
+#if STM32_NCAN < 1
+# undef CONFIG_STM32_CAN1
+#endif
+
+#if defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2)
+
+/* CAN BAUD */
+
+#if defined(CONFIG_STM32_CAN1) && !defined(CONFIG_CAN1_BAUD)
+# error "CONFIG_CAN1_BAUD is not defined"
+#endif
+
+#if defined(CONFIG_STM32_CAN2) && !defined(CONFIG_CAN2_BAUD)
+# error "CONFIG_CAN2_BAUD is not defined"
+#endif
+
+/* Debug ********************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct stm32_can_s
+{
+ uint8_t port; /* CAN port number (1 or 2) */
+ uint8_t cantx; /* CAN TX IRQ number */
+ uint8_t canrx0; /* CAN RX FIFO 0 IRQ number */
+ uint8_t canrx1; /* CAN RX FIFO 1 IRQ number */
+ uint8_t cansce; /* CAN RX0 Status change error (SCE) IRQ number */
+ uint32_t baud; /* Configured baud */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* CAN driver methods */
+
+static void can_reset(FAR struct can_dev_s *dev);
+static int can_setup(FAR struct can_dev_s *dev);
+static void can_shutdown(FAR struct can_dev_s *dev);
+static void can_rxint(FAR struct can_dev_s *dev, bool enable);
+static void can_txint(FAR struct can_dev_s *dev, bool enable);
+static int can_ioctl(FAR struct can_dev_s *dev, int cmd, unsigned long arg);
+static int can_remoterequest(FAR struct can_dev_s *dev, uint16_t id);
+static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg);
+static bool can_txempty(FAR struct can_dev_s *dev);
+
+/* CAN interrupt handling */
+
+static int can_txinterrupt(int irq, void *context);
+static int can_rx0interrupt(int irq, void *context);
+static int can_rx1interrupt(int irq, void *context);
+static int can_sceinterrupt(int irq, void *context);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct can_ops_s g_canops =
+{
+ .co_reset = can_reset,
+ .co_setup = can_setup,
+ .co_shutdown = can_shutdown,
+ .co_rxint = can_rxint,
+ .co_txint = can_txint,
+ .co_ioctl = can_ioctl,
+ .co_remoterequest = can_remoterequest,
+ .co_send = can_send,
+ .co_txempty = can_txempty,
+};
+
+#ifdef CONFIG_STM32_CAN1
+static struct stm32_can_s g_can1priv =
+{
+ .port = 1,
+#if defined(CONFIG_STM32_STM32F10XX) && !defined(CONFIG_STM32_CONNECTIVITY_LINE)
+ .cantx = STM32_IRQ_USBHPCANTX,
+ .canrx0 = STM32_IRQ_USBLPCANRX0,
+#else
+ .cantx = STM32_IRQ_CAN1TX,
+ .canrx0 = STM32_IRQ_CAN1RX0,
+#endif
+ .canrx1 = STM32_IRQ_CAN1RX1,
+ .cansce = STM32_IRQ_CAN1SCE,
+ .baud = CONFIG_CAN1_BAUD,
+};
+
+static struct can_dev_s g_can1dev =
+{
+ .cd_ops = &g_canops,
+ .cd_priv = &g_can1priv,
+};
+#endif
+
+#ifdef CONFIG_STM32_CAN2
+static struct stm32_can_s g_can2priv =
+{
+ .port = 2,
+ .cantx = STM32_IRQ_CAN2TX,
+ .canrx0 = STM32_IRQ_CAN2RX0,
+ .canrx1 = STM32_IRQ_CAN2RX1,
+ .cansce = STM32_IRQ_CAN2SCE,
+ .baud = CONFIG_CAN2_BAUD,
+};
+
+static struct can_dev_s g_can2dev =
+{
+ .cd_ops = &g_canops,
+ .cd_priv = &g_can2priv,
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: can_reset
+ *
+ * Description:
+ * Reset the CAN device. Called early to initialize the hardware. This
+ * function is called, before can_setup() and on error conditions.
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void can_reset(FAR struct can_dev_s *dev)
+{
+ FAR struct stm32_can_s *priv = dev->cd_priv;
+ irqstate_t flags;
+
+ /* Disable interrupts momentary to stop any ongoing CAN event processing */
+
+ flags = irqsave();
+
+#ifdef CONFIG_STM32_CAN1
+ if (priv->port == 1)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+#ifdef CONFIG_STM32_CAN2
+ if (priv->port == 2)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+ {
+ candbg("Unsupport port %d\n", priv->port);
+ }
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: can_setup
+ *
+ * Description:
+ * Configure the CAN. This method is called the first time that the CAN
+ * device is opened. This will occur when the port is first opened.
+ * This setup includes configuring and attaching CAN interrupts.
+ * All CAN interrupts are disabled upon return.
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int can_setup(FAR struct can_dev_s *dev)
+{
+ FAR struct stm32_can_s *priv = dev->cd_priv;
+ int ret;
+
+ /* Attach all CAN interrupts */
+
+ ret = irq_attach(priv->cantx, can_txinterrupt);
+ if (ret < 0)
+ {
+ candbg("Failed to attach CAN%d TX IRQ (%d)", priv->port, priv->cantx);
+ return ret;
+ }
+
+ ret = irq_attach(priv->canrx0, can_rx0interrupt);
+ if (ret < 0)
+ {
+ candbg("Failed to attach CAN%d RX0 IRQ (%d)", priv->port, priv->canrx0);
+ return ret;
+ }
+
+ ret = irq_attach(priv->canrx1, can_rx1interrupt);
+ if (ret < 0)
+ {
+ candbg("Failed to attach CAN%d RX1 IRQ (%d)", priv->port, priv->canrx1);
+ return ret;
+ }
+
+ ret = irq_attach(priv->cansce, can_sceinterrupt);
+ if (ret < 0)
+ {
+ candbg("Failed to attach CAN%d SCE IRQ (%d)", priv->port, priv->cansce);
+ return ret;
+ }
+
+ /* Enable all interrupts at the NVIC. Interrupts are still disabled in
+ * the CAN module. Since we coming out of reset here, there should be
+ */
+
+ up_enable_irq(priv->cantx);
+ up_enable_irq(priv->canrx0);
+ up_enable_irq(priv->canrx1);
+ up_enable_irq(priv->cansce);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: can_shutdown
+ *
+ * Description:
+ * Disable the CAN. This method is called when the CAN device is closed.
+ * This method reverses the operation the setup method.
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void can_shutdown(FAR struct can_dev_s *dev)
+{
+ FAR struct stm32_can_s *priv = dev->cd_priv;
+
+ /* Disable all interrupts */
+
+ up_disable_irq(priv->cantx);
+ up_disable_irq(priv->canrx0);
+ up_disable_irq(priv->canrx1);
+ up_disable_irq(priv->cansce);
+
+ /* Detach all interrupts */
+
+ irq_detach(priv->cantx);
+ irq_detach(priv->canrx0);
+ irq_detach(priv->canrx1);
+ irq_detach(priv->cansce);
+
+ /* And reset the hardware */
+
+ can_reset(dev);
+}
+
+/****************************************************************************
+ * Name: can_rxint
+ *
+ * Description:
+ * Call to enable or disable RX interrupts.
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void can_rxint(FAR struct can_dev_s *dev, bool enable)
+{
+ FAR struct stm32_can_s *priv = dev->cd_priv;
+
+#ifdef CONFIG_STM32_CAN1
+ if (priv->port == 1)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+#ifdef CONFIG_STM32_CAN2
+ if (priv->port == 2)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+ {
+ candbg("Unsupport port %d\n", priv->port);
+ }
+}
+
+/****************************************************************************
+ * Name: can_txint
+ *
+ * Description:
+ * Call to enable or disable TX interrupts.
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void can_txint(FAR struct can_dev_s *dev, bool enable)
+{
+ FAR struct stm32_can_s *priv = dev->cd_priv;
+
+#ifdef CONFIG_STM32_CAN1
+ if (priv->port == 1)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+#ifdef CONFIG_STM32_CAN2
+ if (priv->port == 2)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+ {
+ candbg("Unsupport port %d\n", priv->port);
+ }
+}
+
+/****************************************************************************
+ * Name: can_ioctl
+ *
+ * Description:
+ * All ioctl calls will be routed through this method
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int can_ioctl(FAR struct can_dev_s *dev, int cmd, unsigned long arg)
+{
+ /* No CAN ioctls are supported */
+
+ return -ENOTTY;
+}
+
+/****************************************************************************
+ * Name: can_remoterequest
+ *
+ * Description:
+ * Send a remote request
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int can_remoterequest(FAR struct can_dev_s *dev, uint16_t id)
+{
+#warning "Missing logic"
+ return -ENOSYS;
+}
+
+/****************************************************************************
+ * Name: can_send
+ *
+ * Description:
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
+{
+ FAR struct stm32_can_s *priv = dev->cd_priv;
+
+#ifdef CONFIG_STM32_CAN1
+ if (priv->port == 1)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+#ifdef CONFIG_STM32_CAN2
+ if (priv->port == 2)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+ {
+ candbg("Unsupport port %d\n", priv->port);
+ return -EINVAL;
+ }
+
+#warning "Missing logic"
+ return OK;
+}
+
+/****************************************************************************
+ * Name: can_txempty
+ *
+ * Description:
+ * Return true if all message have been sent. If for example, the CAN
+ * hardware implements FIFOs, then this would mean the transmit FIFO is
+ * empty. This method is called when the driver needs to make sure that
+ * all characters are "drained" from the TX hardware before calling
+ * co_shutdown().
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static bool can_txempty(FAR struct can_dev_s *dev)
+{
+ FAR struct stm32_can_s *priv = dev->cd_priv;
+
+#ifdef CONFIG_STM32_CAN1
+ if (priv->port == 1)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+#ifdef CONFIG_STM32_CAN2
+ if (priv->port == 2)
+ {
+#warning "Missing logic"
+ }
+ else
+#endif
+ {
+ candbg("Unsupport port %d\n", priv->port);
+ return true;
+ }
+
+#warning "Missing logic"
+ return true;
+}
+
+/****************************************************************************
+ * Name: can_txinterrupt
+ *
+ * Description:
+ * CAN TX interrupt handler
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int can_txinterrupt(int irq, void *context)
+{
+ FAR struct stm32_can_s *priv;
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+ if (g_can1priv.cantx == irq)
+ {
+ priv = &g_can1priv;
+ }
+ else if (g_can2priv.cantx == irq)
+ {
+ priv = &g_can2priv;
+ }
+ else
+ {
+ PANIC(OSERR_UNEXPECTEDISR);
+ }
+#elif defined(CONFIG_STM32_CAN1)
+ priv = &g_can1priv;
+#else /* defined(CONFIG_STM32_CAN2) */
+ priv = &g_can2priv;
+#endif
+
+#warning "Missing logic"
+ return OK;
+}
+
+/****************************************************************************
+ * Name: can_rx0interrupt
+ *
+ * Description:
+ * CAN RX FIFO 0 interrupt handler
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int can_rx0interrupt(int irq, void *context)
+{
+ FAR struct stm32_can_s *priv;
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+ if (g_can1priv.canrx0 == irq)
+ {
+ priv = &g_can1priv;
+ }
+ else if (g_can2priv.canrx0 == irq)
+ {
+ priv = &g_can2priv;
+ }
+ else
+ {
+ PANIC(OSERR_UNEXPECTEDISR);
+ }
+#elif defined(CONFIG_STM32_CAN1)
+ priv = &g_can1priv;
+#else /* defined(CONFIG_STM32_CAN2) */
+ priv = &g_can2priv;
+#endif
+
+#warning "Missing logic"
+ return OK;
+}
+
+/****************************************************************************
+ * Name: can_rx1interrupt
+ *
+ * Description:
+ * CAN FIFO 1 interrupt handler
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int can_rx1interrupt(int irq, void *context)
+{
+ FAR struct stm32_can_s *priv;
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+ if (g_can1priv.canrx1 == irq)
+ {
+ priv = &g_can1priv;
+ }
+ else if (g_can2priv.canrx1 == irq)
+ {
+ priv = &g_can2priv;
+ }
+ else
+ {
+ PANIC(OSERR_UNEXPECTEDISR);
+ }
+#elif defined(CONFIG_STM32_CAN1)
+ priv = &g_can1priv;
+#else /* defined(CONFIG_STM32_CAN2) */
+ priv = &g_can2priv;
+#endif
+
+#warning "Missing logic"
+ return OK;
+}
+
+/****************************************************************************
+ * Name: can_sceinterrupt
+ *
+ * Description:
+ * CAN Status Change Error (SCE) interrupt handler
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int can_sceinterrupt(int irq, void *context)
+{
+ FAR struct stm32_can_s *priv;
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+ if (g_can1priv.cansce == irq)
+ {
+ priv = &g_can1priv;
+ }
+ else if (g_can2priv.cansce == irq)
+ {
+ priv = &g_can2priv;
+ }
+ else
+ {
+ PANIC(OSERR_UNEXPECTEDISR);
+ }
+#elif defined(CONFIG_STM32_CAN1)
+ priv = &g_can1priv;
+#else /* defined(CONFIG_STM32_CAN2) */
+ priv = &g_can2priv;
+#endif
+
+#warning "Missing logic"
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_caninitialize
+ *
+ * Description:
+ * Initialize the selected CAN port
+ *
+ * Input Parameter:
+ * Port number (for hardware that has mutiple CAN interfaces)
+ *
+ * Returned Value:
+ * Valid CAN device structure reference on succcess; a NULL on failure
+ *
+ ****************************************************************************/
+
+FAR struct can_dev_s *up_caninitialize(int port)
+{
+ struct can_dev_s *dev = NULL;
+
+#ifdef CONFIG_STM32_CAN1
+ if( port == 1 )
+ {
+ dev = &g_can1dev;
+ }
+ else
+#endif
+#ifdef CONFIG_STM32_CAN2
+ if ( port ==2 )
+ {
+ dev = &g_can2dev;
+ }
+ else
+#endif
+ {
+ candbg("Unsupport port %d\n", priv->port);
+ return NULL;
+ }
+
+#warning "Missing logic"
+ return dev;
+}
+
+#endif /* CONFIG_STM32_CAN1 || CONFIG_STM32_CAN2 */
+#endif /* CONFIG_CAN */
+
diff --git a/nuttx/arch/arm/src/stm32/stm32_pwm.c b/nuttx/arch/arm/src/stm32/stm32_pwm.c
index 99d2e310c..fb3323d7e 100644
--- a/nuttx/arch/arm/src/stm32/stm32_pwm.c
+++ b/nuttx/arch/arm/src/stm32/stm32_pwm.c
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/stm32_pwm.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index a85348bab..90302fff6 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -633,6 +633,15 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_RTC_ALARM - Enable if the RTC hardware supports setting of an
alarm. A callback function will be executed when the alarm goes off
+ CAN driver
+
+ CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+ CONFIG_STM32_CAN2 must also be defined)
+ CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+ Default: 8
+ CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+ Default: 4
+
SPI driver
CONFIG_SPI_OWNBUS - Set if there is only one active device
diff --git a/nuttx/configs/hymini-stm32v/README.txt b/nuttx/configs/hymini-stm32v/README.txt
index 016604d88..ccb3850e2 100755
--- a/nuttx/configs/hymini-stm32v/README.txt
+++ b/nuttx/configs/hymini-stm32v/README.txt
@@ -486,8 +486,18 @@ HY-Mini specific Configuration Options
4-bit transfer mode.
CONFIG_MMCSD_HAVECARDDETECT - Select if SDIO driver card detection
is 100% accurate (it is on the HY-MiniSTM32V)
-
-
+
+ HY-MiniSTM32V CAN Configuration
+
+ CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+ CONFIG_STM32_CAN2 must also be defined)
+ CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+ Default: 8
+ CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+ Default: 4
+ CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+ CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+
HY-MiniSTM32V LCD Hardware Configuration (SSD1289 controler)
CONFIG_NX_LCDDRIVER - To be defined to include LCD driver
diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt
index f8868373f..e5f2541d8 100755
--- a/nuttx/configs/stm3210e-eval/README.txt
+++ b/nuttx/configs/stm3210e-eval/README.txt
@@ -575,6 +575,17 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default:
4-bit transfer mode.
+ STM3210E-EVAL CAN Configuration
+
+ CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+ CONFIG_STM32_CAN2 must also be defined)
+ CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+ Default: 8
+ CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+ Default: 4
+ CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+ CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+
STM3210E-EVAL LCD Hardware Configuration
CONFIG_LCD_LANDSCAPE - Define for 320x240 display "landscape"
diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
index a7e49a73a..8813ac821 100755
--- a/nuttx/configs/stm3240g-eval/README.txt
+++ b/nuttx/configs/stm3240g-eval/README.txt
@@ -481,6 +481,17 @@ STM3240G-EVAL-specific Configuration Options
CONFIG_STM32_ETH_PTP - Precision Time Protocol (PTP). Not supported
but some hooks are indicated with this condition.
+ STM3240G-EVAL CAN Configuration
+
+ CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+ CONFIG_STM32_CAN2 must also be defined)
+ CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+ Default: 8
+ CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+ Default: 4
+ CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+ CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+
STM3240G-EVAL LCD Hardware Configuration
Configurations
diff --git a/nuttx/configs/stm3240g-eval/dhcpd/defconfig b/nuttx/configs/stm3240g-eval/dhcpd/defconfig
index 3675f5b85..a0ba27c0b 100755
--- a/nuttx/configs/stm3240g-eval/dhcpd/defconfig
+++ b/nuttx/configs/stm3240g-eval/dhcpd/defconfig
@@ -257,6 +257,24 @@ CONFIG_SSI_POLLWAIT=y
#CONFIG_SSI_TXLIMIT=4
#
+# STM32F40xxx specific CAN device driver settings
+#
+# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+# CONFIG_STM32_CAN2 must also be defined)
+# CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+# Default: 8
+# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+# Default: 4
+# CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+#
+CONFIG_CAN=n
+#CONFIG_CAN_FIFOSIZE
+#CONFIG_CAN_NPENDINGRTR
+CONFIG_CAN1_BAUD=115200
+CONFIG_CAN2_BAUD=115200
+
+#
# STM32F40xxx Ethernet device driver settings
#
# CONFIG_STM32_PHYADDR - The 5-bit address of the PHY on the board
diff --git a/nuttx/configs/stm3240g-eval/nettest/defconfig b/nuttx/configs/stm3240g-eval/nettest/defconfig
index 6884ad3d7..afcd39512 100755
--- a/nuttx/configs/stm3240g-eval/nettest/defconfig
+++ b/nuttx/configs/stm3240g-eval/nettest/defconfig
@@ -257,6 +257,24 @@ CONFIG_SSI_POLLWAIT=y
#CONFIG_SSI_TXLIMIT=4
#
+# STM32F40xxx specific CAN device driver settings
+#
+# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+# CONFIG_STM32_CAN2 must also be defined)
+# CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+# Default: 8
+# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+# Default: 4
+# CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+#
+CONFIG_CAN=n
+#CONFIG_CAN_FIFOSIZE
+#CONFIG_CAN_NPENDINGRTR
+CONFIG_CAN1_BAUD=115200
+CONFIG_CAN2_BAUD=115200
+
+#
# STM32F40xxx Ethernet device driver settings
#
# CONFIG_STM32_PHYADDR - The 5-bit address of the PHY on the board
diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig
index 8acd5de7c..72ab549ef 100755
--- a/nuttx/configs/stm3240g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3240g-eval/nsh/defconfig
@@ -257,6 +257,24 @@ CONFIG_SSI_POLLWAIT=y
#CONFIG_SSI_TXLIMIT=4
#
+# STM32F40xxx specific CAN device driver settings
+#
+# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+# CONFIG_STM32_CAN2 must also be defined)
+# CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+# Default: 8
+# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+# Default: 4
+# CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+#
+CONFIG_CAN=n
+#CONFIG_CAN_FIFOSIZE
+#CONFIG_CAN_NPENDINGRTR
+CONFIG_CAN1_BAUD=115200
+CONFIG_CAN2_BAUD=115200
+
+#
# STM32F40xxx Ethernet device driver settings
#
# CONFIG_STM32_PHYADDR - The 5-bit address of the PHY on the board
diff --git a/nuttx/configs/stm3240g-eval/ostest/defconfig b/nuttx/configs/stm3240g-eval/ostest/defconfig
index 2b51d88c7..e0b696dfe 100755
--- a/nuttx/configs/stm3240g-eval/ostest/defconfig
+++ b/nuttx/configs/stm3240g-eval/ostest/defconfig
@@ -257,6 +257,24 @@ CONFIG_SSI_POLLWAIT=y
#CONFIG_SSI_TXLIMIT=4
#
+# STM32F40xxx specific CAN device driver settings
+#
+# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+# CONFIG_STM32_CAN2 must also be defined)
+# CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+# Default: 8
+# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+# Default: 4
+# CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+#
+CONFIG_CAN=n
+#CONFIG_CAN_FIFOSIZE
+#CONFIG_CAN_NPENDINGRTR
+CONFIG_CAN1_BAUD=115200
+CONFIG_CAN2_BAUD=115200
+
+#
# STM32F40xxx Ethernet device driver settings
#
# CONFIG_STM32_PHYADDR - The 5-bit address of the PHY on the board
diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
index b76a04a8c..a6fcbe1f0 100644
--- a/nuttx/drivers/Makefile
+++ b/nuttx/drivers/Makefile
@@ -2,7 +2,7 @@
# drivers/Makefile
#
# Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
@@ -64,10 +64,13 @@ include usbhost/Make.defs
include wireless/Make.defs
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
- CSRCS += dev_null.c dev_zero.c loop.c can.c
+ CSRCS += dev_null.c dev_zero.c loop.c
ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
CSRCS += ramdisk.c rwbuffer.c
endif
+ifneq ($(CONFIG_CAN),y)
+ CSRCS += can.c
+endif
ifeq ($(CONFIG_PWM),y)
CSRCS += pwm.c
endif
diff --git a/nuttx/drivers/can.c b/nuttx/drivers/can.c
index fc70678a7..532eef592 100644
--- a/nuttx/drivers/can.c
+++ b/nuttx/drivers/can.c
@@ -1,8 +1,8 @@
/****************************************************************************
* drivers/can.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2009, 2011 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
@@ -34,10 +34,6 @@
****************************************************************************/
/****************************************************************************
- * Compilation Switches
- ****************************************************************************/
-
-/****************************************************************************
* Included Files
****************************************************************************/
@@ -60,9 +56,27 @@
#include <arch/irq.h>
+#ifdef CONFIG_CAN
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+/* Debug ********************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/* Timing Definitions *******************************************************/
#define HALF_SECOND_MSEC 500
#define HALF_SECOND_USEC 500000L
@@ -619,7 +633,7 @@ int can_register(FAR const char *path, FAR struct can_dev_s *dev)
/* Register the CAN device */
- dbg("Registering %s\n", path);
+ canvdbg("Registering %s\n", path);
return register_driver(path, &g_canops, 0666, dev);
}
@@ -768,3 +782,4 @@ int can_txdone(FAR struct can_dev_s *dev)
return ret;
}
+#endif /* CONFIG_CAN */
diff --git a/nuttx/include/nuttx/can.h b/nuttx/include/nuttx/can.h
index 8b438ffda..f87c2eac4 100644
--- a/nuttx/include/nuttx/can.h
+++ b/nuttx/include/nuttx/can.h
@@ -1,8 +1,8 @@
/************************************************************************************
* include/nuttx/can.h
*
- * Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008, 2009, 2011 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
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __NUTTX_CAN_H
-#define __NUTTX_CAN_H
+#ifndef _INCLUDE_NUTTX_CAN_H
+#define _INCLUDE_NUTTX_CAN_H
/************************************************************************************
* Included Files
@@ -46,14 +46,18 @@
#include <stdint.h>
#include <stdbool.h>
#include <semaphore.h>
+
#include <nuttx/fs.h>
+#ifdef CONFIG_CAN
+
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Default configuration settings that may be overridden in the board configuration.
- * file. The configured size is limited to 255 to fit into a uint8_t.
+/* Default configuration settings that may be overridden in the NuttX configuration
+ * file or in the board configuration file. The configured size is limited to 255
+ * to fit into a uint8_t.
*/
#if !defined(CONFIG_CAN_FIFOSIZE)
@@ -165,8 +169,8 @@ struct can_ops_s
/* Configure the CAN. This method is called the first time that the CAN
* device is opened. This will occur when the port is first opened.
- * This setup includes configuring and attaching CAN interrupts. Interrupts
- * are all disabled upon return.
+ * This setup includes configuring and attaching CAN interrupts. All CAN
+ * interrupts are disabled upon return.
*/
CODE int (*co_setup)(FAR struct can_dev_s *dev);
@@ -305,4 +309,5 @@ EXTERN int can_txdone(FAR struct can_dev_s *dev);
}
#endif
-#endif /* __NUTTX_CAN_H */
+#endif /* CONFIG_CAN */
+#endif /* _INCLUDE_NUTTX_CAN_H */