From 10fa68d97d18d9e51b11e1406385aec1c15cf2b1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 18 Feb 2012 14:02:34 +0000 Subject: CAN ISO-11783 support contributed by Gary Teravskis git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4400 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/stm3210e-eval/README.txt | 18 ++- nuttx/configs/stm3210e-eval/nsh2/appconfig | 6 +- nuttx/configs/stm3210e-eval/nsh2/defconfig | 73 ++++++++++- nuttx/configs/stm3210e-eval/src/Makefile | 4 + .../configs/stm3210e-eval/src/stm3210e-internal.h | 6 + nuttx/configs/stm3210e-eval/src/up_can.c | 134 +++++++++++++++++++++ nuttx/configs/stm3240g-eval/src/up_can.c | 4 +- 7 files changed, 239 insertions(+), 6 deletions(-) create mode 100644 nuttx/configs/stm3210e-eval/src/up_can.c (limited to 'nuttx/configs') diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt index 9b1615f42..e08d0bfa5 100755 --- a/nuttx/configs/stm3210e-eval/README.txt +++ b/nuttx/configs/stm3210e-eval/README.txt @@ -458,7 +458,7 @@ STM3210E-EVAL-specific Configuration Options CONFIG_STM32_I2C1 CONFIG_STM32_I2C2 CONFIG_STM32_USB - CONFIG_STM32_CAN + CONFIG_STM32_CAN1 CONFIG_STM32_BKP CONFIG_STM32_PWR CONFIG_STM32_DAC1 @@ -698,6 +698,22 @@ Where is one of the following: Failure to do this could result in corruption of the SD card format. + The nsh2 contains support for some built-in applications that can be + enabled by make some additional minor changes: + + (1) examples/can. The CAN test example can be enabled by changing the + following settings in nsh2/defconfig: + + CONFIG_CAN=y # Enable CAN "upper-half" driver support + CONFIG_STM32_CAN1=y # Enable STM32 CAN1 "lower-half" driver support + + The default CAN settings may need to change in your board board + configuration: + + CONFIG_CAN_EXTID=y # Support extended IDs + CONFIG_CAN1_BAUD=250000 # Bit rate: 250 KHz + CONFIG_CAN_TSEG1=12 # 80% sample point + CONFIG_CAN_TSEG2=3 nx: --- An example using the NuttX graphics system (NX). This example diff --git a/nuttx/configs/stm3210e-eval/nsh2/appconfig b/nuttx/configs/stm3210e-eval/nsh2/appconfig index fb6bf1a66..ff12c4103 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/appconfig +++ b/nuttx/configs/stm3210e-eval/nsh2/appconfig @@ -2,7 +2,7 @@ # configs/stm3210e-eval/nsh2/appconfig # # Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -48,4 +48,8 @@ CONFIGURED_APPS += examples/nx CONFIGURED_APPS += examples/nxhello CONFIGURED_APPS += examples/usbstorage +# Applications configured as an NX built-in commands +ifeq ($(CONFIG_CAN),y) +CONFIGURED_APPS += examples/can +endif diff --git a/nuttx/configs/stm3210e-eval/nsh2/defconfig b/nuttx/configs/stm3210e-eval/nsh2/defconfig index 369a1fcc8..e7ffc8bc6 100644 --- a/nuttx/configs/stm3210e-eval/nsh2/defconfig +++ b/nuttx/configs/stm3210e-eval/nsh2/defconfig @@ -1,7 +1,7 @@ ############################################################################ # configs/stm3210e-eval/nsh2/defconfig # -# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -115,6 +115,27 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n CONFIG_STM32_JTAG_SW_ENABLE=n +# +# Alternate pin mappings +# +CONFIG_STM32_TIM1_FULL_REMAP=n +CONFIG_STM32_TIM1_PARTIAL_REMAP=n +CONFIG_STM32_TIM2_FULL_REMAP=n +CONFIG_STM32_TIM2_PARTIAL_REMAP_1=n +CONFIG_STM32_TIM2_PARTIAL_REMAP_2=n +CONFIG_STM32_TIM3_FULL_REMAP=n +CONFIG_STM32_TIM3_PARTIAL_REMAP=n +CONFIG_STM32_TIM4_REMAP=n +CONFIG_STM32_USART1_REMAP=n +CONFIG_STM32_USART2_REMAP=n +CONFIG_STM32_USART3_FULL_REMAP=n +CONFIG_STM32_USART3_PARTIAL_REMAP=n +CONFIG_STM32_SPI1_REMAP=n +CONFIG_STM32_SPI3_REMAP=n +CONFIG_STM32_I2C1_REMAP=n +CONFIG_STM32_CAN1_REMAP1=y +CONFIG_STM32_CAN1_REMAP2=n + # # Individual subsystems can be enabled: # AHB: @@ -140,7 +161,8 @@ CONFIG_STM32_UART5=n CONFIG_STM32_I2C1=y CONFIG_STM32_I2C2=n CONFIG_STM32_USB=y -CONFIG_STM32_CAN=n +CONFIG_STM32_CAN1=n +CONFIG_STM32_CAN2=n CONFIG_STM32_BKP=n CONFIG_STM32_PWR=n CONFIG_STM32_DAC=n @@ -239,6 +261,36 @@ CONFIG_STM32_AM240320_DISABLE=n CONFIG_STM32_SPFD5408B_DISABLE=n CONFIG_STM32_R61580_DISABLE=y +# +# STM32F10xxx 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_EXTID - Enables support for the 29-bit extended ID. Default +# Standard 11-bit IDs. +# 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_CAN_LOOPBACK - A CAN driver may or may not support a loopback +# mode for testing. The STM32 CAN driver does support loopback mode. +# 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_TSEG1 - The number of CAN time quanta in segment 1. Default: 6 +# CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7 +# +CONFIG_CAN=n +CONFIG_CAN_EXTID=y +#CONFIG_CAN_FIFOSIZE +#CONFIG_CAN_NPENDINGRTR +CONFIG_CAN_LOOPBACK=n +# ISO-11783 requires the baud to be set to 250K +CONFIG_CAN1_BAUD=250000 +CONFIG_CAN2_BAUD=250000 +# ISO-11783 requires the sample point to be within 75 to 80% +CONFIG_CAN_TSEG1=12 +CONFIG_CAN_TSEG2=3 + # # General build options # @@ -360,6 +412,7 @@ CONFIG_DEBUG_GRAPHICS=n CONFIG_DEBUG_LCD=n CONFIG_DEBUG_USB=n CONFIG_DEBUG_SYMBOLS=n +CONFIG_DEBUG_CAN=n CONFIG_HAVE_CXX=n CONFIG_MM_REGIONS=1 CONFIG_ARCH_LOWPUTC=y @@ -1126,6 +1179,22 @@ CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=n CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n +# Settings for examples/can +# +# CONFIG_CAN - Enables CAN support. +# CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback +# mode for testing. The STM32 CAN driver does support loopback mode. +# CONFIG_NSH_BUILTIN_APPS - Build the CAN test as an NSH built-in function. +# Default: Built as a standalone problem +# +# CONFIG_EXAMPLES_CAN_DEVPATH - The path to the CAN device. Default: /dev/can0 +# CONFIG_EXAMPLES_CAN_NMSGS - If CONFIG_NSH_BUILTIN_APPS +# is defined, then the number of loops is provided on the command line +# and this value is ignored. Otherwise, this number of CAN message is +# collected and the program terminates. Default: If built as an NSH +# built-in, the default is 32. Otherwise messages are sent and received +# indefinitely. + # # Settings for examples/nx # diff --git a/nuttx/configs/stm3210e-eval/src/Makefile b/nuttx/configs/stm3210e-eval/src/Makefile index d7247619a..a4e83483b 100644 --- a/nuttx/configs/stm3210e-eval/src/Makefile +++ b/nuttx/configs/stm3210e-eval/src/Makefile @@ -68,6 +68,10 @@ ifeq ($(CONFIG_I2C_LM75),y) CSRCS += up_lm75.c endif +ifeq ($(CONFIG_CAN),y) +CSRCS += up_can.c +endif + COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) diff --git a/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h b/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h index 25b1da320..5cb5e91af 100644 --- a/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h +++ b/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h @@ -60,6 +60,12 @@ # undef CONFIG_STM32_SPI2 #endif +/* There is only CAN1 on the STM3210E-EVAL board */ + +#if defined(CONFIG_STM32_CAN2) +# warning "The STM3210E-EVAL only supports CAN1" +#endif + /* STM3210E-EVAL GPIOs **************************************************************/ /* LEDs */ diff --git a/nuttx/configs/stm3210e-eval/src/up_can.c b/nuttx/configs/stm3210e-eval/src/up_can.c new file mode 100644 index 000000000..7ca712daf --- /dev/null +++ b/nuttx/configs/stm3210e-eval/src/up_can.c @@ -0,0 +1,134 @@ +/************************************************************************************ + * configs/stm3210e-eval/src/up_can.c + * arch/arm/src/board/up_can.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" + +#include "stm32.h" +#include "stm32_can.h" +#include "stm3210e-internal.h" + +#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ +/* The STM32F103ZE supports only CAN1 */ + +#define CAN_PORT 1 + +/* 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 Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) + { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + if (can == NULL) + { + candbg("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + if (ret < 0) + { + candbg("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif /* CONFIG_CAN && CONFIG_STM32_CAN1 */ diff --git a/nuttx/configs/stm3240g-eval/src/up_can.c b/nuttx/configs/stm3240g-eval/src/up_can.c index 713a5325a..6fcbbb211 100644 --- a/nuttx/configs/stm3240g-eval/src/up_can.c +++ b/nuttx/configs/stm3240g-eval/src/up_can.c @@ -2,7 +2,7 @@ * configs/stm3240g-eval/src/up_can.c * arch/arm/src/board/up_can.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -139,4 +139,4 @@ int can_devinit(void) return OK; } -#endif /* CONFIG_CAN && (CONFIG_STM32_CAN2 || CONFIG_STM32_CAN3) */ +#endif /* CONFIG_CAN && (CONFIG_STM32_CAN1 || CONFIG_STM32_CAN2) */ -- cgit v1.2.3