Add loopback support to STM32 CAN driver; Add apps/examples/can loopback test
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4213 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
parent
60f0ba5fcb
commit
9c6c3a3bbb
ChangeLog
Documentation
arch/arm/src
configs
drivers
include/nuttx
@ -2287,6 +2287,6 @@
|
||||
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).
|
||||
check is incomplete). Add loopback support to the driver.
|
||||
|
||||
|
||||
|
@ -4376,6 +4376,11 @@ build
|
||||
<li>
|
||||
<code>CONFIG_CAN_NPENDINGRTR</code>: The size of the list of pending RTR requests. Default: 4
|
||||
</li>
|
||||
<li>
|
||||
<code>CONFIG_CAN_LOOPBACK</code>: A CAN driver may or may not support a loopback mode for testing.
|
||||
If the driver does support loopback mode, the setting will enable it.
|
||||
(If the driver does not, this setting will have no effect).
|
||||
</li>
|
||||
</ul>
|
||||
|
||||
<h3>SPI driver</h3>
|
||||
|
@ -340,11 +340,6 @@ extern void up_usbuninitialize(void);
|
||||
# define up_usbuninitialize()
|
||||
#endif
|
||||
|
||||
/* CAN **********************************************************************/
|
||||
|
||||
struct can_dev_s; /* Forward reference */
|
||||
extern FAR struct can_dev_s *up_caninitialize(int port);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_check_stack
|
||||
*
|
||||
@ -361,7 +356,6 @@ extern FAR struct can_dev_s *up_caninitialize(int port);
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
|
||||
#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_STACK)
|
||||
extern size_t up_check_stack(void);
|
||||
extern size_t up_check_tcbstack(FAR _TCB);
|
||||
|
@ -354,7 +354,7 @@ static int can_interrupt(int irq, void *context)
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_caninitialize
|
||||
* Name: lpc17_caninitialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize the selected can port
|
||||
@ -367,7 +367,7 @@ static int can_interrupt(int irq, void *context)
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
FAR struct can_dev_s *up_caninitialize(int port)
|
||||
FAR struct can_dev_s *lpc17_caninitialize(int port)
|
||||
{
|
||||
uint32_t regval;
|
||||
irqstate_t flags;
|
||||
|
@ -786,6 +786,25 @@ FAR struct adc_dev_s *stm32_adcinitialize(void);
|
||||
EXTERN FAR struct dac_dev_s *lpc17_dacinitialize(void);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: lpc17_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
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#if defined(CONFIG_CAN) && (defined(CONFIG_LPC17_CAN1) || defined(CONFIG_LPC17_CAN2))
|
||||
struct can_dev_s;
|
||||
EXTERN FAR struct can_dev_s *lpc17_caninitialize(int port);
|
||||
#endif
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
|
@ -60,34 +60,11 @@
|
||||
#include "stm32_internal.h"
|
||||
#include "stm32_can.h"
|
||||
|
||||
#ifdef CONFIG_CAN
|
||||
#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2))
|
||||
|
||||
/****************************************************************************
|
||||
* 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
|
||||
|
||||
/* Delays *******************************************************************/
|
||||
/* Time out for INAK bit */
|
||||
|
||||
@ -762,7 +739,7 @@ static int can_rx0interrupt(int irq, void *context)
|
||||
|
||||
/* Provide the data to the upper half driver */
|
||||
|
||||
ret = can_receive(dev, (uint16_t)CAN_MSG(id, rtr, dlc), data);
|
||||
ret = can_receive(dev, (uint16_t)CAN_HDR(id, rtr, dlc), data);
|
||||
|
||||
/* Release the FIFO0 */
|
||||
|
||||
@ -925,7 +902,7 @@ static int can_bittiming(struct stm32_can_s *priv)
|
||||
canvdbg("TS1: %d TS2: %d BRP: %d\n", ts1, ts2, brp);
|
||||
|
||||
/* Configure bit timing. This also does the the following, less obvious
|
||||
* things:
|
||||
* things. Unless loopback mode is enabled, it:
|
||||
*
|
||||
* - Disables silent mode.
|
||||
* - Disables loopback mode.
|
||||
@ -936,6 +913,10 @@ static int can_bittiming(struct stm32_can_s *priv)
|
||||
|
||||
tmp = ((brp - 1) << CAN_BTR_BRP_SHIFT) | ((ts1 - 1) << CAN_BTR_TS1_SHIFT) |
|
||||
((ts2 - 1) << CAN_BTR_TS2_SHIFT) | ((1 - 1) << CAN_BTR_SJW_SHIFT);
|
||||
#ifdef CONFIG_CAN_LOOPBACK
|
||||
tmp |= (CAN_BTR_LBKM | CAN_BTR_SILM);
|
||||
#endif
|
||||
|
||||
can_putreg(priv, STM32_CAN_BTR_OFFSET, tmp);
|
||||
return OK;
|
||||
}
|
||||
@ -1126,7 +1107,7 @@ static int can_filterinit(struct stm32_can_s *priv)
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_caninitialize
|
||||
* Name: stm32_caninitialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize the selected CAN port
|
||||
@ -1139,7 +1120,7 @@ static int can_filterinit(struct stm32_can_s *priv)
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
FAR struct can_dev_s *up_caninitialize(int port)
|
||||
FAR struct can_dev_s *stm32_caninitialize(int port)
|
||||
{
|
||||
struct can_dev_s *dev = NULL;
|
||||
|
||||
@ -1158,8 +1139,10 @@ FAR struct can_dev_s *up_caninitialize(int port)
|
||||
* file must have been disambiguated in the board.h file.
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_CAN_LOOPBACK
|
||||
stm32_configgpio(GPIO_CAN1_RX);
|
||||
stm32_configgpio(GPIO_CAN1_TX);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
#endif
|
||||
@ -1174,19 +1157,20 @@ FAR struct can_dev_s *up_caninitialize(int port)
|
||||
* file must have been disambiguated in the board.h file.
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_CAN_LOOPBACK
|
||||
stm32_configgpio(GPIO_CAN2_RX);
|
||||
stm32_configgpio(GPIO_CAN2_TX);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
candbg("Unsupported port %d\n", priv->port);
|
||||
candbg("Unsupported port %d\n", port);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
return dev;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_STM32_CAN1 || CONFIG_STM32_CAN2 */
|
||||
#endif /* CONFIG_CAN */
|
||||
#endif /* CONFIG_CAN && (CONFIG_STM32_CAN1 || CONFIG_STM32_CAN2) */
|
||||
|
||||
|
@ -50,17 +50,73 @@
|
||||
/************************************************************************************
|
||||
* 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_CAN) && (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
|
||||
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_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
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
struct can_dev_s;
|
||||
EXTERN FAR struct can_dev_s *stm32_caninitialize(int port);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* CONFIG_CAN && (CONFIG_STM32_CAN1 || CONFIG_STM32_CAN2) */
|
||||
#endif /* __ARCH_ARM_SRC_STM32_STM32_CAN_H */
|
||||
|
@ -641,6 +641,9 @@ defconfig -- This is a configuration file similar to the Linux
|
||||
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. If the driver does support loopback mode, the setting
|
||||
will enable it. (If the driver does not, this setting will have no effect).
|
||||
|
||||
SPI driver
|
||||
|
||||
|
@ -495,6 +495,8 @@ HY-Mini specific Configuration Options
|
||||
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.
|
||||
|
||||
|
@ -583,6 +583,8 @@ STM3210E-EVAL-specific Configuration Options
|
||||
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.
|
||||
|
||||
|
@ -124,6 +124,11 @@ int adc_devinit(void)
|
||||
/* Call stm32_adcinitialize() to get an instance of the ADC interface */
|
||||
|
||||
adc = stm32_adcinitialize(1, g_chanlist, ADC_NCHANNELS);
|
||||
if (adc == NULL)
|
||||
{
|
||||
adbg("ERROR: Failed to get ADC interface\n");
|
||||
return;
|
||||
}
|
||||
|
||||
/* Register the ADC driver at "/dev/adc0" */
|
||||
|
||||
@ -133,7 +138,7 @@ int adc_devinit(void)
|
||||
adbg("adc_register failed: %d\n", ret);
|
||||
}
|
||||
|
||||
return OK;
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_STM32_ADC || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
|
||||
|
@ -524,6 +524,8 @@ STM3240G-EVAL-specific Configuration Options
|
||||
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.
|
||||
|
||||
|
@ -265,14 +265,17 @@ CONFIG_SSI_POLLWAIT=y
|
||||
# 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=n
|
||||
#CONFIG_CAN_FIFOSIZE
|
||||
#CONFIG_CAN_NPENDINGRTR
|
||||
CONFIG_CAN1_BAUD=115200
|
||||
CONFIG_CAN2_BAUD=115200
|
||||
CONFIG_CAN_LOOPBACK=n
|
||||
CONFIG_CAN1_BAUD=700000
|
||||
CONFIG_CAN2_BAUD=700000
|
||||
|
||||
#
|
||||
# STM32F40xxx Ethernet device driver settings
|
||||
|
@ -265,14 +265,17 @@ CONFIG_SSI_POLLWAIT=y
|
||||
# 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=n
|
||||
#CONFIG_CAN_FIFOSIZE
|
||||
#CONFIG_CAN_NPENDINGRTR
|
||||
CONFIG_CAN1_BAUD=115200
|
||||
CONFIG_CAN2_BAUD=115200
|
||||
CONFIG_CAN_LOOPBACK=n
|
||||
CONFIG_CAN1_BAUD=700000
|
||||
CONFIG_CAN2_BAUD=700000
|
||||
|
||||
#
|
||||
# STM32F40xxx Ethernet device driver settings
|
||||
|
@ -54,4 +54,7 @@ ifeq ($(CONFIG_PWM),y)
|
||||
CONFIGURED_APPS += examples/pwm
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CAN),y)
|
||||
CONFIGURED_APPS += examples/can
|
||||
endif
|
||||
|
||||
|
@ -265,14 +265,17 @@ CONFIG_SSI_POLLWAIT=y
|
||||
# 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=n
|
||||
#CONFIG_CAN_FIFOSIZE
|
||||
#CONFIG_CAN_NPENDINGRTR
|
||||
CONFIG_CAN1_BAUD=115200
|
||||
CONFIG_CAN2_BAUD=115200
|
||||
CONFIG_CAN_LOOPBACK=n
|
||||
CONFIG_CAN1_BAUD=700000
|
||||
CONFIG_CAN2_BAUD=700000
|
||||
|
||||
#
|
||||
# STM32F40xxx Ethernet device driver settings
|
||||
|
@ -265,14 +265,17 @@ CONFIG_SSI_POLLWAIT=y
|
||||
# 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=n
|
||||
#CONFIG_CAN_FIFOSIZE
|
||||
#CONFIG_CAN_NPENDINGRTR
|
||||
CONFIG_CAN1_BAUD=115200
|
||||
CONFIG_CAN2_BAUD=115200
|
||||
CONFIG_CAN_LOOPBACK=n
|
||||
CONFIG_CAN1_BAUD=700000
|
||||
CONFIG_CAN2_BAUD=700000
|
||||
|
||||
#
|
||||
# STM32F40xxx Ethernet device driver settings
|
||||
|
@ -50,6 +50,10 @@ ifeq ($(CONFIG_PWM),y)
|
||||
CSRCS += up_pwm.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CAN),y)
|
||||
CSRCS += up_can.c
|
||||
endif
|
||||
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
|
||||
SRCS = $(ASRCS) $(CSRCS)
|
||||
|
@ -48,7 +48,7 @@
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************************************/
|
||||
/* How many SPI modules does this chip support? */
|
||||
|
||||
#if STM32_NSPI < 1
|
||||
@ -62,6 +62,36 @@
|
||||
# undef CONFIG_STM32_SPI3
|
||||
#endif
|
||||
|
||||
/* You can use either CAN1 or CAN2, but you can't use both because they share the same transceiver */
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "The STM3250G-EVAL will only support one of CAN1 and CAN2"
|
||||
#endif
|
||||
|
||||
/* You can't use CAN1 with FSMC:
|
||||
*
|
||||
* PD0 = FSMC_D2 & CAN1_RX
|
||||
* PD1 = FSMC_D3 & CAN1_TX
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_CAN_LOOPBACK
|
||||
# if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_FSMC)
|
||||
# warning "The STM3250G-EVAL will only support one of CAN1 and FSMC"
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* The USB OTG HS ULPI bus is shared with CAN2 bus:
|
||||
*
|
||||
* PB13 = ULPI_D6 & CAN2_TX
|
||||
* PB5 = ULPI_D7 & CAN2_RX
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_CAN_LOOPBACK
|
||||
# if defined(CONFIG_STM32_CAN2) && defined(CONFIG_STM32_OTGHS)
|
||||
# warning "The STM3250G-EVAL will only support one of CAN2 and USB OTG HS"
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* STM3240G-EVAL GPIOs ******************************************************************************/
|
||||
/* LEDs */
|
||||
|
||||
|
@ -91,21 +91,37 @@
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void adc_devinit(void)
|
||||
int adc_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct adc_dev_s *adc;
|
||||
int ret;
|
||||
|
||||
/* Call stm32_adcinitialize() to get an instance of the ADC interface */
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized)
|
||||
{
|
||||
/* Configure the pins as analog inputs for the selected channels */
|
||||
#warning "Missing Logic"
|
||||
|
||||
/* Register the ADC driver at "/dev/adc0" */
|
||||
/* Call stm32_adcinitialize() to get an instance of the ADC interface */
|
||||
#warning "Missing Logic"
|
||||
|
||||
ret = adc_register("/dev/adc0", adc);
|
||||
if (ret < 0)
|
||||
{
|
||||
adbg("adc_register failed: %d\n", ret);
|
||||
/* Register the ADC driver at "/dev/adc0" */
|
||||
|
||||
ret = adc_register("/dev/adc0", adc);
|
||||
if (ret < 0)
|
||||
{
|
||||
adbg("adc_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_STM32_ADC || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
|
||||
|
142
configs/stm3240g-eval/src/up_can.c
Normal file
142
configs/stm3240g-eval/src/up_can.c
Normal file
@ -0,0 +1,142 @@
|
||||
/************************************************************************************
|
||||
* configs/stm3240g-eval/src/up_can.c
|
||||
* arch/arm/src/board/up_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 <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "stm32.h"
|
||||
#include "stm32_can.h"
|
||||
#include "stm3240g-internal.h"
|
||||
|
||||
#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2))
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
|
||||
# undef CONFIG_STM32_CAN2
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_CAN1
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#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 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_STM32_CAN || CONFIG_STM32_CAN2 || CONFIG_STM32_CAN3 */
|
@ -65,12 +65,15 @@ include wireless/Make.defs
|
||||
|
||||
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
|
||||
CSRCS += dev_null.c dev_zero.c loop.c
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
|
||||
CSRCS += ramdisk.c rwbuffer.c
|
||||
endif
|
||||
ifneq ($(CONFIG_CAN),y)
|
||||
|
||||
ifeq ($(CONFIG_CAN),y)
|
||||
CSRCS += can.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_PWM),y)
|
||||
CSRCS += pwm.c
|
||||
endif
|
||||
|
@ -88,14 +88,15 @@
|
||||
|
||||
/* CAN message support */
|
||||
|
||||
#define CAN_MAXDATALEN 8
|
||||
#define CAN_MAXDATALEN 8
|
||||
#define CAN_MAXMSGID 0x07ff
|
||||
|
||||
#define CAN_ID(hdr) ((uint16_t)(hdr) >> 5)
|
||||
#define CAN_RTR(hdr) (((hdr) & 0x0010) != 0)
|
||||
#define CAN_DLC(hdr) ((hdr) & 0x0f)
|
||||
#define CAN_MSGLEN(hdr) (sizeof(struct can_msg_s) - (CAN_MAXDATALEN - CAN_DLC(hdr)))
|
||||
|
||||
#define CAN_MSG(id, rtr, dlc) ((uint16_t)id << 5 | (uint16_t)rtr << 4 | (uint16_t)dlc)
|
||||
#define CAN_HDR(id, rtr, dlc) ((uint16_t)id << 5 | (uint16_t)rtr << 4 | (uint16_t)dlc)
|
||||
|
||||
/* Built-in ioctl commands
|
||||
*
|
||||
|
Loading…
x
Reference in New Issue
Block a user