Browse Source

Add support for extended (29-bit) CAN IDs

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4319 7fd9a85b-ad96-42d3-883c-3090e2eb8679
sbg
patacongo 13 years ago
parent
commit
b179df901e
  1. 32
      apps/examples/can/can_main.c
  2. 4
      nuttx/ChangeLog
  3. 55
      nuttx/arch/arm/src/lpc17xx/lpc17_can.c
  4. 8
      nuttx/arch/arm/src/stm32/chip/stm32_can.h
  5. 59
      nuttx/arch/arm/src/stm32/stm32_can.c
  6. 2
      nuttx/configs/README.txt
  7. 2
      nuttx/configs/hymini-stm32v/README.txt
  8. 2
      nuttx/configs/lpcxpresso-lpc1768/README.txt
  9. 2
      nuttx/configs/mbed/README.txt
  10. 2
      nuttx/configs/nucleus2g/README.txt
  11. 2
      nuttx/configs/olimex-lpc1766stk/README.txt
  12. 3
      nuttx/configs/olimex-lpc1766stk/nsh/defconfig
  13. 2
      nuttx/configs/stm3210e-eval/README.txt
  14. 3
      nuttx/configs/stm3210e-eval/ostest/defconfig
  15. 3
      nuttx/configs/stm3240g-eval/README.txt
  16. 3
      nuttx/configs/stm3240g-eval/dhcpd/defconfig
  17. 3
      nuttx/configs/stm3240g-eval/nettest/defconfig
  18. 3
      nuttx/configs/stm3240g-eval/nsh/defconfig
  19. 3
      nuttx/configs/stm3240g-eval/ostest/defconfig
  20. 2
      nuttx/configs/stm32f4discovery/README.txt
  21. 3
      nuttx/configs/stm32f4discovery/nsh/defconfig
  22. 3
      nuttx/configs/stm32f4discovery/ostest/defconfig
  23. 18
      nuttx/drivers/can.c
  24. 73
      nuttx/include/nuttx/can.h

32
apps/examples/can/can_main.c

@ -57,6 +57,12 @@
* Pre-processor Definitions * Pre-processor Definitions
****************************************************************************/ ****************************************************************************/
#ifdef CONFIG_CAN_EXTID
# define MAX_ID (1 << 29)
#else
# define MAX_ID (1 << 11)
#endif
#ifdef CONFIG_NSH_BUILTIN_APPS #ifdef CONFIG_NSH_BUILTIN_APPS
# define MAIN_NAME can_main # define MAIN_NAME can_main
# define MAIN_STRING "can_main: " # define MAIN_STRING "can_main: "
@ -99,12 +105,16 @@ int MAIN_NAME(int argc, char *argv[])
struct can_msg_s rxmsg; struct can_msg_s rxmsg;
size_t msgsize; size_t msgsize;
ssize_t nbytes; ssize_t nbytes;
#ifdef CONFIG_CAN_EXTID
uint32_t msgid;
#else
uint16_t msgid;
#endif
uint8_t msgdata; uint8_t msgdata;
#if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_EXAMPLES_CAN_NMSGS) #if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_EXAMPLES_CAN_NMSGS)
long nmsgs; long nmsgs;
#endif #endif
int msgdlc; int msgdlc;
int msgid;
int fd; int fd;
int errval = 0; int errval = 0;
int ret; int ret;
@ -174,7 +184,13 @@ int MAIN_NAME(int argc, char *argv[])
/* Construct the next TX message */ /* Construct the next TX message */
txmsg.cm_hdr = CAN_HDR(msgid, 0, msgdlc); txmsg.cm_hdr.ch_id = msgid;
txmsg.cm_hdr.ch_rtr = false;
txmsg.cm_hdr.ch_dlc = msgdlc;
#ifdef CONFIG_CAN_EXTID
txmsg.cm_hdr.ch_extid = true;
#endif
for (i = 0; i < msgdlc; i++) for (i = 0; i < msgdlc; i++)
{ {
txmsg.cm_data[i] = msgdata + i; txmsg.cm_data[i] = msgdata + i;
@ -182,7 +198,7 @@ int MAIN_NAME(int argc, char *argv[])
/* Send the TX message */ /* Send the TX message */
msgsize = CAN_MSGLEN(txmsg.cm_hdr); msgsize = CAN_MSGLEN(msgdlc);
nbytes = write(fd, &txmsg, msgsize); nbytes = write(fd, &txmsg, msgsize);
if (nbytes != msgsize) if (nbytes != msgsize)
{ {
@ -204,9 +220,13 @@ int MAIN_NAME(int argc, char *argv[])
/* Verify that the received messages are the same */ /* Verify that the received messages are the same */
if (txmsg.cm_hdr != rxmsg.cm_hdr) if (memcmp(&txmsg.cm_hdr, &rxmsg.cm_hdr, sizeof(struct can_hdr_s)) != 0)
{ {
message("ERROR: Sent header %04x; received header %04x\n", txmsg.cm_hdr, rxmsg.cm_hdr); message("ERROR: Sent header does not match received header:\n");
lib_dumpbuffer("Sent header", (FAR const uint8_t*)&txmsg.cm_hdr,
sizeof(struct can_hdr_s));
lib_dumpbuffer("Received header", (FAR const uint8_t*)&rxmsg.cm_hdr,
sizeof(struct can_hdr_s));
errval = 4; errval = 4;
goto errout_with_dev; goto errout_with_dev;
} }
@ -230,7 +250,7 @@ int MAIN_NAME(int argc, char *argv[])
msgdata += msgdlc; msgdata += msgdlc;
if (++msgid >= 2048) if (++msgid >= MAX_ID)
{ {
msgid = 1; msgid = 1;
} }

4
nuttx/ChangeLog

@ -2382,4 +2382,8 @@
register. register.
* arch/arm/src/lpc17xx/lpc17_can.c: Added "advanced" configuration options * arch/arm/src/lpc17xx/lpc17_can.c: Added "advanced" configuration options
to specify the CAN TSEG1 and TSEG2 clock counts specifically. to specify the CAN TSEG1 and TSEG2 clock counts specifically.
* include/nuttx/can.h and drivers/can.c: Add support for extended (29-bit)
CAN IDs.
* arch/arm/src/lpc17xx/lpc17_can.c: Add support for extended (29-bit) CAN IDs.
* arch/arm/src/stm32/stm32_can.c: Add support for extended (29-bit) CAN IDs.

55
nuttx/arch/arm/src/lpc17xx/lpc17_can.c

@ -745,20 +745,39 @@ 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 int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
{ {
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv; FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
uint32_t tid = CAN_ID(msg->cm_hdr); uint32_t tid = (uint32_t)msg->cm_hdr.ch_id;
uint32_t tfi = CAN_DLC(msg->cm_hdr) << 16; uint32_t tfi = (uint32_t)msg->cm_hdr.ch_dlc << 16;
uint32_t regval; uint32_t regval;
irqstate_t flags; irqstate_t flags;
int ret = OK; int ret = OK;
canvdbg("CAN%d ID: %d DLC: %d\n", canvdbg("CAN%d ID: %d DLC: %d\n", priv->port, msg->cm_hdr.ch_id, msg->cm_hdr.ch_dlc);
priv->port, CAN_ID(msg->cm_hdr), CAN_DLC(msg->cm_hdr));
if (CAN_RTR(msg->cm_hdr)) if (msg->cm_hdr.ch_rtr)
{ {
tfi |= CAN_TFI_RTR; tfi |= CAN_TFI_RTR;
} }
/* Set the FF bit in the TFI register if this message should be sent with
* the extended frame format (and 29-bit extened ID).
*/
#ifdef CONFIG_CAN_EXTID
if (msg->cm_hdr.ch_extid)
{
/* The provided ID should be 29 bits */
DEBUGASSERT((tid & ~CAN_TID_ID29_MASK) == 0);
tfi |= CAN_TFI_FF;
}
else
#endif
{
/* The provided ID should be 11 bits */
DEBUGASSERT((tid & ~CAN_TID_ID11_MASK) == 0);
}
flags = irqsave(); flags = irqsave();
/* Pick a transmit buffer */ /* Pick a transmit buffer */
@ -927,14 +946,11 @@ static bool can_txempty(FAR struct can_dev_s *dev)
static void can_interrupt(FAR struct can_dev_s *dev) static void can_interrupt(FAR struct can_dev_s *dev)
{ {
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv; FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
struct can_hdr_s hdr;
uint32_t data[2]; uint32_t data[2];
uint32_t rfs; uint32_t rfs;
uint32_t rid; uint32_t rid;
uint32_t regval; uint32_t regval;
uint16_t hdr;
uint16_t id;
uint16_t dlc;
uint16_t rtr;
/* Read the interrupt and capture register (also clearing most status bits) */ /* Read the interrupt and capture register (also clearing most status bits) */
@ -956,14 +972,23 @@ static void can_interrupt(FAR struct can_dev_s *dev)
/* Construct the CAN header */ /* Construct the CAN header */
id = rid & CAN_RID_ID11_MASK; hdr.ch_id = rid;
dlc = (rfs & CAN_RFS_DLC_MASK) >> CAN_RFS_DLC_SHIFT; hdr.ch_rtr = ((rfs & CAN_RFS_RTR) != 0);
rtr = ((rfs & CAN_RFS_RTR) != 0); hdr.ch_dlc = (rfs & CAN_RFS_DLC_MASK) >> CAN_RFS_DLC_SHIFT;
hdr = CAN_HDR(id, rtr, dlc); #ifdef CONFIG_CAN_EXTID
hdr.ch_extid = ((rfs & CAN_RFS_FF) != 0);
#else
if ((rfs & CAN_RFS_FF) != 0)
{
canlldbg("ERROR: Received message with extended identifier. Dropped\n");
}
else
#endif
{
/* Process the received CAN packet */ /* Process the received CAN packet */
can_receive(dev, hdr, (uint8_t *)data); can_receive(dev, &hdr, (uint8_t *)data);
}
} }
/* Check for TX buffer 1 complete */ /* Check for TX buffer 1 complete */

8
nuttx/arch/arm/src/stm32/chip/stm32_can.h

@ -367,8 +367,8 @@
#define CAN_TIR_TXRQ (1 << 0) /* Bit 0: Transmit Mailbox Request */ #define CAN_TIR_TXRQ (1 << 0) /* Bit 0: Transmit Mailbox Request */
#define CAN_TIR_RTR (1 << 1) /* Bit 1: Remote Transmission Request */ #define CAN_TIR_RTR (1 << 1) /* Bit 1: Remote Transmission Request */
#define CAN_TIR_IDE (1 << 2) /* Bit 2: Identifier Extension */ #define CAN_TIR_IDE (1 << 2) /* Bit 2: Identifier Extension */
#define CAN_TIR_EXID_SHIFT (3) /* Bit 3-20: Extended Identifier */ #define CAN_TIR_EXID_SHIFT (3) /* Bit 3-31: Extended Identifier */
#define CAN_TIR_EXID_MASK (0x0003ffff << CAN_TIR_EXID_SHIFT) #define CAN_TIR_EXID_MASK (0x1fffffff << CAN_TIR_EXID_SHIFT)
#define CAN_TIR_STID_SHIFT (21) /* Bits 21-31: Standard Identifier */ #define CAN_TIR_STID_SHIFT (21) /* Bits 21-31: Standard Identifier */
#define CAN_TIR_STID_MASK (0x07ff << CAN_TIR_STID_SHIFT) #define CAN_TIR_STID_MASK (0x07ff << CAN_TIR_STID_SHIFT)
@ -406,8 +406,8 @@
#define CAN_RIR_RTR (1 << 1) /* Bit 1: Remote Transmission Request */ #define CAN_RIR_RTR (1 << 1) /* Bit 1: Remote Transmission Request */
#define CAN_RIR_IDE (1 << 2) /* Bit 2: Identifier Extension */ #define CAN_RIR_IDE (1 << 2) /* Bit 2: Identifier Extension */
#define CAN_RIR_EXID_SHIFT (3) /* Bit 3-20: Extended Identifier */ #define CAN_RIR_EXID_SHIFT (3) /* Bit 3-31: Extended Identifier */
#define CAN_RIR_EXID_MASK (0x0003ffff << CAN_RIR_EXID_SHIFT) #define CAN_RIR_EXID_MASK (0x1fffffff << CAN_RIR_EXID_SHIFT)
#define CAN_RIR_STID_SHIFT (21) /* Bits 21-31: Standard Identifier */ #define CAN_RIR_STID_SHIFT (21) /* Bits 21-31: Standard Identifier */
#define CAN_RIR_STID_MASK (0x07ff << CAN_RIR_STID_SHIFT) #define CAN_RIR_STID_MASK (0x07ff << CAN_RIR_STID_SHIFT)

59
nuttx/arch/arm/src/stm32/stm32_can.c

@ -783,8 +783,7 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
int dlc; int dlc;
int txmb; int txmb;
canllvdbg("CAN%d ID: %d DLC: %d\n", canllvdbg("CAN%d ID: %d DLC: %d\n", priv->port, msg->cm_hdr.ch_id, msg->cm_hdr.ch_dlc);
priv->port, CAN_ID(msg->cm_hdr), CAN_DLC(msg->cm_hdr));
/* Select one empty transmit mailbox */ /* Select one empty transmit mailbox */
@ -813,20 +812,29 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
regval &= ~(CAN_TIR_TXRQ | CAN_TIR_RTR | CAN_TIR_IDE | CAN_TIR_EXID_MASK | CAN_TIR_STID_MASK); regval &= ~(CAN_TIR_TXRQ | CAN_TIR_RTR | CAN_TIR_IDE | CAN_TIR_EXID_MASK | CAN_TIR_STID_MASK);
can_putreg(priv, STM32_CAN_TIR_OFFSET(txmb), regval); can_putreg(priv, STM32_CAN_TIR_OFFSET(txmb), regval);
/* Set up the ID. Only standard (11-bit) CAN identifiers are supported /* Set up the ID, standard 11-bit or extended 29-bit. */
* (the STM32 supports extended, 29-bit identifiers, but this method does
* not).
*
* Get the 11-bit identifier from the header bits 0-7 and 13-15.
*/
#ifdef CONFIG_CAN_EXTID
regval &= ~CAN_TIR_EXID_MASK;
if (msg->cm_hdr.ch_extid)
{
DEBUGASSERT(msg->cm_hdr.ch_id < (1 << 29));
regval |= (msg->cm_hdr.ch_id << CAN_TIR_EXID_SHIFT) | CAN_TIR_IDE;
}
else
{
DEBUGASSERT(msg->cm_hdr.ch_id < (1 << 11));
regval |= msg->cm_hdr.ch_id << CAN_TIR_STID_SHIFT;
}
#else
regval &= ~CAN_TIR_STID_MASK; regval &= ~CAN_TIR_STID_MASK;
regval |= (uint32_t)CAN_ID(msg->cm_hdr) << CAN_TIR_STID_SHIFT; regval |= (uint32_t)msg->cm_hdr.ch_id << CAN_TIR_STID_SHIFT;
#endif
can_putreg(priv, STM32_CAN_TIR_OFFSET(txmb), regval); can_putreg(priv, STM32_CAN_TIR_OFFSET(txmb), regval);
/* Set up the DLC */ /* Set up the DLC */
dlc = CAN_DLC(msg->cm_hdr); dlc = msg->cm_hdr.ch_dlc;
regval = can_getreg(priv, STM32_CAN_TDTR_OFFSET(txmb)); regval = can_getreg(priv, STM32_CAN_TDTR_OFFSET(txmb));
regval &= ~(CAN_TDTR_DLC_MASK | CAN_TDTR_TGT); regval &= ~(CAN_TDTR_DLC_MASK | CAN_TDTR_TGT);
regval |= (uint32_t)dlc << CAN_TDTR_DLC_SHIFT; regval |= (uint32_t)dlc << CAN_TDTR_DLC_SHIFT;
@ -989,12 +997,10 @@ static int can_rx0interrupt(int irq, void *context)
{ {
FAR struct can_dev_s *dev = NULL; FAR struct can_dev_s *dev = NULL;
FAR struct stm32_can_s *priv; FAR struct stm32_can_s *priv;
struct can_hdr_s hdr;
uint8_t data[CAN_MAXDATALEN]; uint8_t data[CAN_MAXDATALEN];
uint32_t regval; uint32_t regval;
int npending; int npending;
int id;
int rtr;
int dlc;
int ret; int ret;
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) #if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
@ -1029,9 +1035,21 @@ static int can_rx0interrupt(int irq, void *context)
can_dumpmbregs(priv, "RX0 interrupt"); can_dumpmbregs(priv, "RX0 interrupt");
/* Get the CAN identifier. Only standard 11-bit IDs are supported */ /* Get the CAN identifier. */
regval = can_getreg(priv, STM32_CAN_RI0R_OFFSET); regval = can_getreg(priv, STM32_CAN_RI0R_OFFSET);
#ifdef CONFIG_CAN_EXTID
if ((regval & CAN_RIR_IDE) != 0)
{
hdr.ch_id = (regval & CAN_RIR_EXID_MASK) >> CAN_RIR_EXID_SHIFT;
hdr.ch_extid = true;
}
else
{
hdr.ch_id = (regval & CAN_RIR_STID_MASK) >> CAN_RIR_STID_SHIFT;
hdr.ch_extid = false;
}
#else
if ((regval & CAN_RIR_IDE) != 0) if ((regval & CAN_RIR_IDE) != 0)
{ {
canlldbg("ERROR: Received message with extended identifier. Dropped\n"); canlldbg("ERROR: Received message with extended identifier. Dropped\n");
@ -1039,16 +1057,17 @@ static int can_rx0interrupt(int irq, void *context)
goto errout; goto errout;
} }
id = (regval & CAN_RIR_STID_MASK) >> CAN_RIR_STID_SHIFT; hdr.ch_id = (regval & CAN_RIR_STID_MASK) >> CAN_RIR_STID_SHIFT;
#endif
/* Get the Remote Transmission Request (RTR) */ /* Extract the RTR bit */
rtr = (regval & CAN_RIR_RTR) != 0 ? 1 : 0; hdr.ch_rtr = (regval & CAN_RIR_RTR) != 0 ? true : false;
/* Get the DLC */ /* Get the DLC */
regval = can_getreg(priv, STM32_CAN_RDT0R_OFFSET); regval = can_getreg(priv, STM32_CAN_RDT0R_OFFSET);
dlc = (regval & CAN_RDTR_DLC_MASK) >> CAN_RDTR_DLC_SHIFT; hdr.ch_dlc = (regval & CAN_RDTR_DLC_MASK) >> CAN_RDTR_DLC_SHIFT;
/* Save the message data */ /* Save the message data */
@ -1066,11 +1085,13 @@ static int can_rx0interrupt(int irq, void *context)
/* Provide the data to the upper half driver */ /* Provide the data to the upper half driver */
ret = can_receive(dev, (uint16_t)CAN_HDR(id, rtr, dlc), data); ret = can_receive(dev, &hdr, data);
/* Release the FIFO0 */ /* Release the FIFO0 */
#ifndef CONFIG_CAN_EXTID
errout: errout:
#endif
regval = can_getreg(priv, STM32_CAN_RF0R_OFFSET); regval = can_getreg(priv, STM32_CAN_RF0R_OFFSET);
regval |= CAN_RFR_RFOM; regval |= CAN_RFR_RFOM;
can_putreg(priv, STM32_CAN_RF0R_OFFSET, regval); can_putreg(priv, STM32_CAN_RF0R_OFFSET, regval);

2
nuttx/configs/README.txt

@ -646,6 +646,8 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
CONFIG_STM32_CAN2 must also be defined) 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. CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
Default: 8 Default: 8
CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.

2
nuttx/configs/hymini-stm32v/README.txt

@ -472,6 +472,8 @@ HY-Mini specific Configuration Options
CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
CONFIG_STM32_CAN2 must also be defined) 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. CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
Default: 8 Default: 8
CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.

2
nuttx/configs/lpcxpresso-lpc1768/README.txt

@ -647,6 +647,8 @@ LPCXpresso Configuration Options
LPC17xx specific CAN device driver settings. These settings all LPC17xx specific CAN device driver settings. These settings all
require CONFIG_CAN: require CONFIG_CAN:
CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
Standard 11-bit IDs.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined.
CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number.

2
nuttx/configs/mbed/README.txt

@ -287,6 +287,8 @@ mbed Configuration Options
LPC17xx specific CAN device driver settings. These settings all LPC17xx specific CAN device driver settings. These settings all
require CONFIG_CAN: require CONFIG_CAN:
CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
Standard 11-bit IDs.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined.
CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number.

2
nuttx/configs/nucleus2g/README.txt

@ -399,6 +399,8 @@ Nucleus 2G Configuration Options
LPC17xx specific CAN device driver settings. These settings all LPC17xx specific CAN device driver settings. These settings all
require CONFIG_CAN: require CONFIG_CAN:
CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
Standard 11-bit IDs.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined.
CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number.

2
nuttx/configs/olimex-lpc1766stk/README.txt

@ -696,6 +696,8 @@ Olimex LPC1766-STK Configuration Options
LPC17xx specific CAN device driver settings. These settings all LPC17xx specific CAN device driver settings. These settings all
require CONFIG_CAN: require CONFIG_CAN:
CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
Standard 11-bit IDs.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined. CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined.
CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number. CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number.

3
nuttx/configs/olimex-lpc1766stk/nsh/defconfig

@ -631,6 +631,8 @@ CONFIG_NET_RESOLV_ENTRIES=4
# #
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_LPC17_CAN1 or # CONFIG_CAN - Enables CAN support (one or both of CONFIG_LPC17_CAN1 or
# CONFIG_LPC17_CAN2 must also be defined) # CONFIG_LPC17_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. # CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8 # Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. # CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -641,6 +643,7 @@ CONFIG_NET_RESOLV_ENTRIES=4
# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined. # CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined.
# #
CONFIG_CAN=n CONFIG_CAN=n
CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE #CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR #CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n CONFIG_CAN_LOOPBACK=n

2
nuttx/configs/stm3210e-eval/README.txt

@ -562,6 +562,8 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
CONFIG_STM32_CAN2 must also be defined) 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. CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
Default: 8 Default: 8
CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.

3
nuttx/configs/stm3210e-eval/ostest/defconfig

@ -246,6 +246,8 @@ CONFIG_STM32_R61580_DISABLE=y
# #
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or # CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined) # 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. # CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8 # Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. # CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -258,6 +260,7 @@ CONFIG_STM32_R61580_DISABLE=y
# CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7 # CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
# #
CONFIG_CAN=n CONFIG_CAN=n
CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE #CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR #CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n CONFIG_CAN_LOOPBACK=n

3
nuttx/configs/stm3240g-eval/README.txt

@ -273,6 +273,8 @@ Configuration Options:
CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
CONFIG_STM32_CAN2 must also be defined) 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. CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
Default: 8 Default: 8
CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -656,6 +658,7 @@ Where <subdir> is one of the following:
must be manually enabled by selecting: must be manually enabled by selecting:
CONFIG_CAN=y : Enable the generic CAN infrastructure CONFIG_CAN=y : Enable the generic CAN infrastructure
CONFIG_CAN_EXID=y or n : Enable to support extended ID frames
CONFIG_STM32_CAN1=y : Enable CAN1 CONFIG_STM32_CAN1=y : Enable CAN1
CONFIG_CAN_LOOPBACK=y : Enable CAN loopback mode CONFIG_CAN_LOOPBACK=y : Enable CAN loopback mode

3
nuttx/configs/stm3240g-eval/dhcpd/defconfig

@ -261,6 +261,8 @@ CONFIG_SSI_POLLWAIT=y
# #
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or # CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined) # 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. # CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8 # Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. # CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -271,6 +273,7 @@ CONFIG_SSI_POLLWAIT=y
# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined. # CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
# #
CONFIG_CAN=n CONFIG_CAN=n
CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE #CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR #CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n CONFIG_CAN_LOOPBACK=n

3
nuttx/configs/stm3240g-eval/nettest/defconfig

@ -261,6 +261,8 @@ CONFIG_SSI_POLLWAIT=y
# #
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or # CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined) # 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. # CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8 # Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. # CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -271,6 +273,7 @@ CONFIG_SSI_POLLWAIT=y
# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined. # CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
# #
CONFIG_CAN=n CONFIG_CAN=n
CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE #CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR #CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n CONFIG_CAN_LOOPBACK=n

3
nuttx/configs/stm3240g-eval/nsh/defconfig

@ -261,6 +261,8 @@ CONFIG_SSI_POLLWAIT=y
# #
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or # CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined) # 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. # CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8 # Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. # CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -273,6 +275,7 @@ CONFIG_SSI_POLLWAIT=y
# CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7 # CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
# #
CONFIG_CAN=n CONFIG_CAN=n
CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE #CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR #CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n CONFIG_CAN_LOOPBACK=n

3
nuttx/configs/stm3240g-eval/ostest/defconfig

@ -261,6 +261,8 @@ CONFIG_SSI_POLLWAIT=y
# #
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or # CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined) # 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. # CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8 # Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. # CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -273,6 +275,7 @@ CONFIG_SSI_POLLWAIT=y
# CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7 # CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
# #
CONFIG_CAN=n CONFIG_CAN=n
CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE #CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR #CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n CONFIG_CAN_LOOPBACK=n

2
nuttx/configs/stm32f4discovery/README.txt

@ -402,6 +402,8 @@ stm32f4discovery-specific Configuration Options
CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
CONFIG_STM32_CAN2 must also be defined) 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. CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
Default: 8 Default: 8
CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.

3
nuttx/configs/stm32f4discovery/nsh/defconfig

@ -248,6 +248,8 @@ CONFIG_SPI_EXCHANGE=y
# #
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or # CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined) # 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. # CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8 # Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. # CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -258,6 +260,7 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined. # CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
# #
CONFIG_CAN=n CONFIG_CAN=n
CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE #CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR #CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n CONFIG_CAN_LOOPBACK=n

3
nuttx/configs/stm32f4discovery/ostest/defconfig

@ -261,6 +261,8 @@ CONFIG_SSI_POLLWAIT=y
# #
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or # CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined) # 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. # CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8 # Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. # CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@ -271,6 +273,7 @@ CONFIG_SSI_POLLWAIT=y
# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined. # CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
# #
CONFIG_CAN=n CONFIG_CAN=n
CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE #CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR #CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n CONFIG_CAN_LOOPBACK=n

18
nuttx/drivers/can.c

@ -325,7 +325,7 @@ static ssize_t can_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
/* Will the next message in the FIFO fit into the user buffer? */ /* Will the next message in the FIFO fit into the user buffer? */
FAR struct can_msg_s *msg = &dev->cd_recv.rx_buffer[dev->cd_recv.rx_head]; FAR struct can_msg_s *msg = &dev->cd_recv.rx_buffer[dev->cd_recv.rx_head];
int msglen = CAN_MSGLEN(msg->cm_hdr); int msglen = CAN_MSGLEN(msg->cm_hdr.ch_dlc);
if (nread + msglen > buflen) if (nread + msglen > buflen)
{ {
@ -532,7 +532,7 @@ static ssize_t can_write(FAR struct file *filep, FAR const char *buffer, size_t
*/ */
msg = (FAR struct can_msg_s *)&buffer[nsent]; msg = (FAR struct can_msg_s *)&buffer[nsent];
msglen = CAN_MSGLEN(msg->cm_hdr); msglen = CAN_MSGLEN(msg->cm_hdr.ch_dlc);
memcpy(&fifo->tx_buffer[fifo->tx_tail], msg, msglen); memcpy(&fifo->tx_buffer[fifo->tx_tail], msg, msglen);
/* Increment the tail of the circular buffer */ /* Increment the tail of the circular buffer */
@ -706,7 +706,7 @@ int can_register(FAR const char *path, FAR struct can_dev_s *dev)
* *
************************************************************************************/ ************************************************************************************/
int can_receive(FAR struct can_dev_s *dev, uint16_t hdr, FAR uint8_t *data) int can_receive(FAR struct can_dev_s *dev, FAR struct can_hdr_s *hdr, FAR uint8_t *data)
{ {
FAR struct can_rxfifo_s *fifo = &dev->cd_recv; FAR struct can_rxfifo_s *fifo = &dev->cd_recv;
FAR uint8_t *dest; FAR uint8_t *dest;
@ -714,7 +714,7 @@ int can_receive(FAR struct can_dev_s *dev, uint16_t hdr, FAR uint8_t *data)
int err = -ENOMEM; int err = -ENOMEM;
int i; int i;
canllvdbg("ID: %d DLC: %d\n", CAN_ID(hdr), CAN_DLC(hdr)); canllvdbg("ID: %d DLC: %d\n", hdr->ch_id, hdr->ch_dlc);
/* Check if adding this new message would over-run the drivers ability to enqueue /* Check if adding this new message would over-run the drivers ability to enqueue
* read data. * read data.
@ -743,12 +743,12 @@ int can_receive(FAR struct can_dev_s *dev, uint16_t hdr, FAR uint8_t *data)
* a non-NULL receiving address * a non-NULL receiving address
*/ */
if (msg && CAN_ID(hdr) == rtr->cr_id) if (msg && hdr->ch_id == rtr->cr_id)
{ {
/* We have the response... copy the data to the user's buffer */ /* We have the response... copy the data to the user's buffer */
msg->cm_hdr = hdr; memcpy(&msg->cm_hdr, hdr, sizeof(struct can_hdr_s));
for (i = 0, dest = msg->cm_data; i < CAN_DLC(hdr); i++) for (i = 0, dest = msg->cm_data; i < hdr->ch_dlc; i++)
{ {
*dest++ = *data++; *dest++ = *data++;
} }
@ -770,8 +770,8 @@ int can_receive(FAR struct can_dev_s *dev, uint16_t hdr, FAR uint8_t *data)
{ {
/* Add the new, decoded CAN message at the tail of the FIFO */ /* Add the new, decoded CAN message at the tail of the FIFO */
fifo->rx_buffer[fifo->rx_tail].cm_hdr = hdr; memcpy(&fifo->rx_buffer[fifo->rx_tail].cm_hdr, hdr, sizeof(struct can_hdr_s));
for (i = 0, dest = fifo->rx_buffer[fifo->rx_tail].cm_data; i < CAN_DLC(hdr); i++) for (i = 0, dest = fifo->rx_buffer[fifo->rx_tail].cm_data; i < hdr->ch_dlc; i++)
{ {
*dest++ = *data++; *dest++ = *data++;
} }

73
nuttx/include/nuttx/can.h

@ -54,6 +54,19 @@
/************************************************************************************ /************************************************************************************
* Pre-processor Definitions * Pre-processor Definitions
************************************************************************************/ ************************************************************************************/
/* Configuration ********************************************************************/
/* 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. If the driver does support loopback mode, the setting
* will enable it. (If the driver does not, this setting will have no effect).
*/
/* Default configuration settings that may be overridden in the NuttX configuration /* 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 * file or in the board configuration file. The configured size is limited to 255
@ -90,14 +103,10 @@
/* CAN message support */ /* CAN message support */
#define CAN_MAXDATALEN 8 #define CAN_MAXDATALEN 8
#define CAN_MAXMSGID 0x07ff #define CAN_MAX_MSGID 0x07ff
#define CAN_MAX_EXTMSGID 0x1fffffff
#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_HDR(id, rtr, dlc) ((uint16_t)id << 5 | (uint16_t)rtr << 4 | (uint16_t)dlc) #define CAN_MSGLEN(nbytes) (sizeof(struct can_msg_s) - CAN_MAXDATALEN + (nbytes))
/* Built-in ioctl commands /* Built-in ioctl commands
* *
@ -115,16 +124,29 @@
/************************************************************************************ /************************************************************************************
* Public Types * Public Types
************************************************************************************/ ************************************************************************************/
/* CAN-message Format /* CAN-message Format (without Extended ID suppport)
* *
* One CAN-message consists of a maximum of 10 bytes. A message is composed of at * One based CAN-message is represented with a maximum of 10 bytes. A message is
* least the first 2 bytes (when there are no data bytes). * composed of at least the first 2 bytes (when there are no data bytes present).
* *
* Byte 0: Bits 0-7: Bits 3-10 of the 11-bit CAN identifier * Bytes 0-1: Hold a 16-bit value in host byte order
* Byte 1: Bits 5-7: Bits 0-2 of the 11-bit CAN identifier
* Bit 4: Remote Tranmission Request (RTR)
* Bits 0-3: Data Length Code (DLC) * Bits 0-3: Data Length Code (DLC)
* Bytes 2-10: CAN data * Bit 4: Remote Tranmission Request (RTR)
* Bits 5-15: The 11-bit CAN identifier
*
* Bytes 2-9: CAN data
*
* CAN-message Format (with Extended ID suppport)
*
* One CAN-message consists of a maximum of 13 bytes. A message is composed of at
* least the first 5 bytes (when there are no data bytes).
*
* Bytes 0-3: Hold 11- or 29-bit CAN ID in host byte order
* Byte 4: Bits 0-3: Data Length Code (DLC)
* Bit 4: Remote Tranmission Request (RTR)
* Bit 5: Extended ID indication
* Bits 6-7: Unused
* Bytes 5-12: CAN data
* *
* The struct can_msg_s holds this information in a user-friendly, unpacked form. * The struct can_msg_s holds this information in a user-friendly, unpacked form.
* This is the form that is used at the read() and write() driver interfaces. The * This is the form that is used at the read() and write() driver interfaces. The
@ -132,9 +154,27 @@
* the CAN_MSGLEN macro. * the CAN_MSGLEN macro.
*/ */
#ifdef CONFIG_CAN_EXTID
struct can_hdr_s
{
uint32_t ch_id; /* 11- or 29-bit ID (3-bits unsed) */
uint8_t ch_dlc : 4; /* 4-bit DLC */
uint8_t ch_rtr : 1; /* RTR indication */
uint8_t ch_extid : 1; /* Extended ID indication */
uint8_t ch_unused : 2; /* Unused */
};
#else
struct can_hdr_s
{
uint16_t ch_dlc : 4; /* 4-bit DLC */
uint16_t ch_rtr : 1; /* RTR indication */
uint16_t ch_id : 11; /* 11-bit standard ID */
};
#endif
struct can_msg_s struct can_msg_s
{ {
uint16_t cm_hdr; /* The 16-bit CAN header */ struct can_hdr_s cm_hdr; /* The CAN header */
uint8_t cm_data[CAN_MAXDATALEN]; /* CAN message data (0-8 byte) */ uint8_t cm_data[CAN_MAXDATALEN]; /* CAN message data (0-8 byte) */
}; };
@ -303,7 +343,8 @@ EXTERN int can_register(FAR const char *path, FAR struct can_dev_s *dev);
* *
************************************************************************************/ ************************************************************************************/
EXTERN int can_receive(FAR struct can_dev_s *dev, uint16_t hdr, FAR uint8_t *data); EXTERN int can_receive(FAR struct can_dev_s *dev, FAR struct can_hdr_s *hdr,
FAR uint8_t *data);
/************************************************************************************ /************************************************************************************
* Name: can_txdone * Name: can_txdone

Loading…
Cancel
Save