Table of Contents

Introduction:

This article will explore how to establish a Controller Area Network (CAN) communication interface between an Arduino and an MSP432 microcontroller. CAN is a robust and widely used communication protocol in automotive and industrial applications, known for its reliability and real-time capabilities. By implementing CAN communication, we can facilitate data exchange between different microcontrollers or devices within a network.

Objective:

The objective of this project is to demonstrate bidirectional Controller Area Network (CAN) communication between an Arduino and an MSP432 microcontroller, using a TMS320F28379D microcontroller as a bridge. The project aims to showcase how CAN communication can facilitate data exchange between different microcontrollers within a network, enabling seamless integration and interoperability in embedded systems.

Components Required:

S.N.COMPONENTSQUANTITY
1Arduino UNO1Buy Arduino From Amazon
2MCP2515 CAN Bus Module1Buy MCP2515 CAN Bus Module
3LAUNCHXL-F28379D1Buy F2837d From Evelta
4USB 2.0 Cable – A-Male to Mini-B1Buy USB 2.0 Cable – A-Male to Mini-B
5Breadboard3Buy Breadboard From Amazon
6Jumper Wires1Buy Jumper Wires From Amazon

Setup and Wiring:

In this project, we will connect the MCP2515 CAN Bus Module to the Arduino Nano. Follow the steps below to ensure proper wiring:

MCP2515 CAN Bus Module Connections:

  • VCC to 5V: Connect the VCC pin of the MCP2515 module to the 5V pin on the Arduino Uno to provide power to the module.
  • GND to GND: Connect the GND pin of the MCP2515 module to any GND pin on the Arduino Uno to establish a common ground.
  • CS to Digital Pin 10: Connect the CS (Chip Select) pin of the MCP2515 module to digital Pin 10 on the Arduino Uno. This pin is used to select the MCP2515 for SPI communication.
  • SO to Digital Pin 12 (MISO): Connect the SO (Slave Out) pin of the MCP2515 module to Digital Pin 12 (MISO) on the Arduino Uno. This pin is used for SPI communication to receive data from the MCP2515.
  • SI to Digital Pin 11 (MOSI): Connect the SI (Slave In) pin of the MCP2515 module to Digital Pin 11 (MOSI) on the Arduino Uno. This pin is used for SPI communication to send data to the MCP2515.
  • SCK to Digital Pin 13 (SCK): Connect the SCK (Serial Clock) pin of the MCP2515 module to digital Pin 13 (SCK) on the Arduino Uno. This pin is used for SPI communication to provide the clock signal.
  • INT to Digital Pin 2 (Interrupt Pin): Connect the INT (Interrupt) pin of the MCP2515 module to Digital Pin 2 on the Arduino Uno. This pin is used to receive interrupts from the MCP2515, indicating events such as message reception.
Circuit Connection Diagram Between Arduino and TMS320F28379D

MCP2515 CAN Bus Controller Module

The MCP2515 CAN Bus Controller is a simple Module that supports CAN Protocol version 2.0B and can be used for communication at 1Mbps.

This particular module is based on the MCP2515 CAN Controller IC and TJA1050 CAN Transceiver IC. The MCP2515 IC is a standalone CAN Controller and has an integrated SPI Interface for communication with microcontrollers. Coming to the TJA1050 IC acts as an interface between the MCP2515 CAN Controller IC and the Physical CAN Bus.

The board has an 8 MHz Crystal oscillator. Even the 16 MHz version is also available. A jumper can be attached which will give 120ohm Termination(J1). CAN_H & CAN_L are the two screws where wires can be attached over a distance for communicating with other CAN modules.

MCP2515 IC is the main controller that internally consists of three main subcomponents: The CAN Module, the Control Logic, and the SPI Block. CAN Module is responsible for transmitting and receiving messages on the CAN Bus. Control Logic handles the setup and operation of the MCP2515 by interfacing all the blocks. The SPI Block is responsible for the SPI communication interface. The TJA1050 IC IC is responsible for taking the data from the controller and relaying it onto the bus.

Features and Specification of MCP2515

  • Uses High-speed CAN transceiver TJA1050
  • Dimension: 40×28mm
  • SPI control for expanding Multi CAN bus interface
  • 8MHZ crystal oscillator
  • 120Ω terminal resistance
  • Has an independent key, LED indicator, and Power indicator
  • Supports 1 Mb/s CAN operation
  • Low current standby operation
  • Up to 112 nodes can be connected

a step-by-step guide to executing code interfacing CAN communication with Arduino using the MCP2515 CAN Bus Module:

Source Code for Arduino MCP2515 CAN Communication

Before moving to the coding part of the project, we need to install MCP2515 CAN Bus Library to the Arduino IDE. Download the library from the following link and then add it to the Arduino Library folder.

Arduino MCP2515 CAN interface Library

This CAN-BUS library gives your Arduino CAN-BUS capability with the following features.

  • Implements CAN V2.0B at up to 1 Mb/s
  • SPI Interface up to 10 MHz
  • Standard (11-bit) and extended (29-bit) data and remote frames
  • Two receive buffers with prioritized message storage

The code is divided into two parts one as CAN transmitter code (Arduino Nano) and the other as CAN Receiver code (Arduino UNO).

Step 1: Include Required Libraries

#include <SPI.h>
#include <mcp2515.h>

Step 2: Define Global Variables

struct can_frame canMsg;
MCP2515 mcp2515(10);
  • can_frame canMsg: This structure is used to store CAN messages, including the CAN ID, data length, and data bytes.
  • MCP2515 mcp2515(10): This initializes an MCP2515 object with the CS (Chip Select) pin connected to pin 10 of the Arduino.

Step 3: Setup Function

void setup()
{
  Serial.begin(9600);
  SPI.begin();
  
  mcp2515.reset();
  mcp2515.setBitrate(CAN_500KBPS, MCP_8MHZ);
  mcp2515.setNormalMode();
}
  • Serial.begin(9600): Initializes serial communication with a baud rate of 9600.
  • SPI.begin(): Initializes SPI communication.
  • mcp2515.reset(): Resets the MCP2515 module to its default state.
  • mcp2515.setBitrate(CAN_500KBPS, MCP_8MHZ): Sets the CAN bit rate to 500 kbps and the MCP2515 clock frequency to 8 MHz.
  • mcp2515.setNormalMode(): Sets the MCP2515 module to normal mode, allowing it to send and receive CAN messages.

Verify CAN Communication [Transmitting and Receiving Data]:

To test the CAN communication interface, we will transmit dummy data from the Arduino Nano to simulate a CAN message transmission. Below is the Arduino code that sends a CAN message with dummy data.

Step 1: Example of Arduino code for transmitting dummy data via CAN bus using the MCP2515 module:

Arduino code for transmitting dummy data

#include <SPI.h>
#include <mcp2515.h>

struct can_frame canMsg;

MCP2515 mcp2515(10);

void setup() {
  Serial.begin(9600);
  SPI.begin();
  
  mcp2515.reset();
  mcp2515.setBitrate(CAN_500KBPS, MCP_8MHZ);
  mcp2515.setNormalMode();
  
  // Print CAN bit rate information
  Serial.println("---------------------------------------------");
  Serial.println("Welcome To CAN Communication Interface");
  Serial.println("500 kbps");
  Serial.println("---------------------------------------------");
  delay(5000);

  // Directly send the example packet
  sendExamplePacket();
}

void loop() {
  // No need for further processing in the loop
}

void sendExamplePacket() {
  /* Prepare a CAN message with CAN ID 0x18 and data bytes 0x21, 0x32, 0x23, 0x14, 0x45, 
0x26, 0x27, 0x18 */
  canMsg.can_id = 0x18;
  canMsg.can_dlc = 8;
  canMsg.data[0] = 0x21;
  canMsg.data[1] = 0x32;
  canMsg.data[2] = 0x23;
  canMsg.data[3] = 0x14;
  canMsg.data[4] = 0x45;
  canMsg.data[5] = 0x26;
  canMsg.data[6] = 0x27;
  canMsg.data[7] = 0x18;

  // Send the CAN message
  mcp2515.sendMessage(&canMsg);
  
  // Print transmission confirmation
  Serial.println("Message Sent");
}

This code initializes the CAN communication interface, prepares a CAN message with an ID of 0x18 and dummy data bytes, and then sends the message using the MCP2515 CAN controller module.
Upon running the code, you should see the message “Message Sent” printed on the serial monitor, indicating that the dummy data has been successfully transmitted via the CAN bus.

Example of code for receiving data via CAN bus on a TMS320F28379D

In this section, we’ll discuss the setup and code for testing CAN communication using the TMS320F28379D microcontroller. This microcontroller features an inbuilt CAN module, which we’ll utilize to receive CAN messages from the Arduino Nano.

Setup and Wiring:

Connect the MCP2515 CAN Bus Module to the TMS320F28379D LaunchPad as follows:

Circuit Connection Diagram Between Arduino and TMS320F28379D

CAN Module Connections:

CAN High (CANH) and CAN Low (CANL) pins from the TMS320F28379D LaunchPad need to be connected to the respective pins on the MCP2515 module? These pins are typically labelled as CANH and CANL on the module.

Ensure that the TMS320F28379D LaunchPad is powered properly and receiver id should be 0x18

#include "device.h"
#include "driverlib.h"
 
#define MSG_DATA_LENGTH    8   // "Don't care" for a Receive mailbox
#define RX_MSG_OBJ_ID      1   // Use mailbox 1
 
// Globals

uint16_t rxMsgData[8];
volatile uint32_t rxMsgCount = 0;
 
 
void main(void)
{
    Device_init();
    Device_initGPIO();
 
    //
       // Configure GPIO pins for CANTX/CANRX
       //
       GPIO_setPinConfig(DEVICE_GPIO_CFG_CANRXB);
       GPIO_setPinConfig(DEVICE_GPIO_CFG_CANTXB);
 
       //
       // Configure GPIO pin which is toggled upon message reception
       //S
       GPIO_setPinConfig(GPIO_31_GPIO31);
       GPIO_setDirectionMode(31, GPIO_DIR_MODE_OUT);
       GPIO_setPadConfig(31, GPIO_PIN_TYPE_STD);
 
       //
       // Initialize the CAN controller
       //
       CAN_initModule(CANB_BASE);
 
       //
       // Set up the CAN bus bit rate to 500kHz for each module
       // Refer to the Driver Library User Guide for information on how to set
       // tighter timing control. Additionally, consult the device data sheet
       // for more information about the CAN module clocking.
       //
       CAN_setBitRate(CANB_BASE, DEVICE_SYSCLK_FREQ, 500000, 16);
 
       //
       // Initialize the receive message object used for receiving CAN messages.
       // Message Object Parameters:
       //      CAN Module: A
       //      Message Object ID Number: 1
       //      Message Identifier: 0x18
       //      Message Frame: EXTENDED
       //      Message Type: Receive
       //      Message ID Mask: 0x0
       //      Message Object Flags: None
       //      Message Data Length: "Don't care" for a Receive mailbox
       //
       CAN_setupMessageObject(CANB_BASE, RX_MSG_OBJ_ID, 0x18,
                              CAN_MSG_FRAME_STD, CAN_MSG_OBJ_TYPE_RX, 0,
                              CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);
 
       // Start CAN module B operations
        CAN_startModule(CANB_BASE);
 
 
    while(1)
    {
 
        //
        // Poll RxOk bit in CAN_ES register to check completion of Reception
        //
        if(((HWREGH(CANB_BASE + CAN_O_ES) & CAN_ES_RXOK)) == CAN_ES_RXOK)
        {
            //
            // Get the received message
            //
            CAN_readMessage(CANB_BASE, RX_MSG_OBJ_ID, rxMsgData);
            GPIO_togglePin(31);
            rxMsgCount++;
        }
    }
}

With the provided code running on the TMS320F28379D microcontroller, it will continuously monitor the CAN bus for incoming messages. Upon receiving a message, it will toggle a GPIO pin, indicating successful message reception as shown in the below picture.

Step 2: Example of code for transmitting data via CAN bus on a TMS320F28379D microcontroller and receiving it on an Arduino board:

In this test scenario, we will use the TMS320F28379D microcontroller as the transmitter to send CAN messages, and the Arduino Uno will serve as the receiver to receive and process these messages.

TMS320F28379D code for transmitting dummy data:

/*
 * main.c
 *
 *  Created on: 16-Sep-2021
 *      Author: Admin
 */
 
//
#include "F28x_Project.h"
#include "F2837xD_device.h"
#include "F2837xD_Examples.h"
 
 
#include "device.h"
#include "driverlib.h"
 
 
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <math.h>
//
// Defines
//
#define TXCOUNT  100000
#define MSG_DATA_LENGTH    8
#define TX_MSG_OBJ_ID      1
#define TX_MSG_OBJ_ID_2    2
#define TX_MSG_OBJ_ID_3    3
 
uint16_t txMsgData_1[8]={0x01,0x02,0x03,0x04,0x05,0x06,0x07,0x08};
uint16_t txMsgData_2[8]={0X09,0X10,0x11,0x12,0x13,0x14,0x15,0x16};
uint16_t txMsgData_3[8]={0X17,0X18,0x19,0x20,0x21,0x22,0x23,0x24};
 
 
 
 
void main(void)
{
 
    Device_init();
 
    //
    // Initialize GPIO and configure GPIO pins for CANTX/CANRX
    // on module A
    //
    Device_initGPIO();
 
    GPIO_setPinConfig(DEVICE_GPIO_CFG_CANRXB);
    GPIO_setPinConfig(DEVICE_GPIO_CFG_CANTXB);
    CAN_initModule(CANB_BASE);
    CAN_setBitRate(CANB_BASE, DEVICE_SYSCLK_FREQ, 500000, 16);
 
 
    CAN_setupMessageObject(CANB_BASE, TX_MSG_OBJ_ID, 0x11,
                           CAN_MSG_FRAME_STD, CAN_MSG_OBJ_TYPE_TX, 0,
                           CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);
 
 
    CAN_setupMessageObject(CANB_BASE, TX_MSG_OBJ_ID_2, 0x22,
                                 CAN_MSG_FRAME_STD, CAN_MSG_OBJ_TYPE_TX, 0,
                                 CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);
 
    CAN_setupMessageObject(CANB_BASE, TX_MSG_OBJ_ID_3, 0x33,
                                 CAN_MSG_FRAME_STD, CAN_MSG_OBJ_TYPE_TX, 0,
                                 CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);
    CAN_startModule(CANB_BASE);
 
 
         while(1)
 
          {
 
             CAN_sendMessage(CANB_BASE, TX_MSG_OBJ_ID, MSG_DATA_LENGTH, txMsgData_1);
             CAN_sendMessage(CANB_BASE, TX_MSG_OBJ_ID_2, MSG_DATA_LENGTH, txMsgData_2);
             CAN_sendMessage(CANB_BASE, TX_MSG_OBJ_ID_3, MSG_DATA_LENGTH, txMsgData_3);
 
              while(((HWREGH(CANB_BASE + CAN_O_ES) & CAN_ES_TXOK)) ==  CAN_ES_TXOK)
              {
 
              }
 
             DEVICE_DELAY_US(1000000);
 
          }
 
}

This code initializes the TMS320F28379D microcontroller’s CAN module, configures it to transmit CAN messages with dummy data txMsgData_1,txMsgData_2, and txMsgData_3, and continuously sends these messages at regular intervals.

Example of code for receiving data via CAN bus on an Arduino

#include <SPI.h>
#include <mcp2515.h>

struct can_frame canMsg;

MCP2515 mcp2515(10);

void setup() {
  Serial.begin(9600);
  SPI.begin();
  
  mcp2515.reset();
  mcp2515.setBitrate(CAN_500KBPS, MCP_8MHZ);
  mcp2515.setNormalMode();
}

void loop() {
  if (mcp2515.readMessage(&canMsg) == MCP2515::ERROR_OK) {
    Serial.print("Received CAN ID: 0x");
    Serial.print(canMsg.can_id, HEX);
    Serial.print(" Data: ");

    for (int i = 0; i < canMsg.can_dlc; ++i) {
      Serial.print("0x");
      if (canMsg.data[i] < 0x10) {
        Serial.print("0");
      }
      Serial.print(canMsg.data[i], HEX);
      Serial.print(" ");
    }
    Serial.println();
    delayMicroseconds(1000000);
  }
}

This code initializes the MCP2515 CAN controller module on the Arduino Nano to receive CAN messages. It continuously reads incoming messages and prints their ID and data on the serial monitor.

Transmitting Data from Serial to CAN Communication

However, in this specific scenario, instead of transmitting CAN data directly through the MCP2515 module, the Arduino sends CAN messages via serial communication to the TMS320F28379D, which then receives and processes these messages.

Example Of Arduino Code For Transmitting Data Over Serial Communication:

#include <SPI.h>
#include <mcp2515.h>

struct can_frame canMsg;

MCP2515 mcp2515(10);

void setup() {
  Serial.begin(9600);
  SPI.begin();
  
  mcp2515.reset();
  mcp2515.setBitrate(CAN_500KBPS, MCP_8MHZ);
  mcp2515.setNormalMode();
  
  // Print CAN bit rate information
  Serial.println("---------------------------------------------");
  Serial.println("Welcome To CAN Communication Interface");
  Serial.println("500 kbps");
  Serial.println("---------------------------------------------");
  delay(5000);

  // No need to send any CAN messages in the setup function
}


void loop() {
  if (Serial.available() > 0) {
    // If data is available on the serial port, read it and send as a CAN message
    sendSerialDataAsCanMessage();
  }
}

void sendSerialDataAsCanMessage() {
  // Read data from the serial port
  String serialData = Serial.readStringUntil('\n');
  
  // Parse the received data and extract CAN ID and data bytes
  int canId = serialData.substring(0, 2).toInt(); // Assuming the first two characters represent the CAN ID
  int dataBytes[8];
  for (int i = 0; i < 8; i++) {
    dataBytes[i] = serialData.substring(3 + i * 3, 5 + i * 3).toInt(); // Assuming each data byte is separated by a space
  }
  
  // Prepare the CAN message
  canMsg.can_id = canId;
  canMsg.can_dlc = 8;
  for (int i = 0; i < 8; i++) {
    canMsg.data[i] = dataBytes[i];
  }

  // Send the CAN message
  mcp2515.sendMessage(&canMsg);
  
  // Print transmission confirmation
  Serial.println("Message Sent");
}

Explanation About Transmitting Can Messages Via Serial Communication:

  1. The Arduino code is responsible for transmitting CAN messages via serial communication.
  2. Serial communication is initialized with a baud rate of 9600.
  3. The MCP2515 library and SPI communication are set up.
  4. The MCP2515 module is reset, and the CAN bus bit rate is configured to 500 kbps with an 8 MHz crystal oscillator.
  5. The code continuously checks for incoming serial data using Serial.available().
  6. Upon receiving data, it reads the data from the serial port until a newline character is encountered.
  7. The received data, assumed to be in the format “CAN_ID DATA_BYTE_1 DATA_BYTE_2 … DATA_BYTE_8”, is parsed to extract the CAN ID and data bytes.
  8. A CAN message is constructed using the extracted data and sent using the mcp2515.sendMessage() function.
  9. A confirmation message is printed via serial communication to indicate that the CAN message has been sent.

Here’s an example of dummy data that you can use to transmit through the serial communication from the Arduino to the TMS320F28379D

24 21 32 23 14 45 26 27  (In Decimal)

In this example, 24 represents the CAN ID, and 21, 32, 23, 14, 45, 26, 27, and 18 represent the 8 data bytes associated with that CAN ID. You can adjust the CAN ID and data bytes as needed for your specific application. Just make sure to separate the CAN ID and each data byte with a space when sending the data through serial communication.

Example of code for receiving data via CAN bus on a TMS320F28379D

#include "device.h"
#include "driverlib.h"
 
#define MSG_DATA_LENGTH    8   // "Don't care" for a Receive mailbox
#define RX_MSG_OBJ_ID      1   // Use mailbox 1
 
//
// Globals
//
uint16_t rxMsgData[8];
volatile uint32_t rxMsgCount = 0;
 
 
void main(void)
{
    Device_init();
    Device_initGPIO();
 
    //
       // Configure GPIO pins for CANTX/CANRX
       //
       GPIO_setPinConfig(DEVICE_GPIO_CFG_CANRXB);
       GPIO_setPinConfig(DEVICE_GPIO_CFG_CANTXB);
 
       //
       // Configure GPIO pin which is toggled upon message reception
       //S
       GPIO_setPinConfig(GPIO_31_GPIO31);
       GPIO_setDirectionMode(31, GPIO_DIR_MODE_OUT);
       GPIO_setPadConfig(31, GPIO_PIN_TYPE_STD);
 
       //
       // Initialize the CAN controller
       //
       CAN_initModule(CANB_BASE);
 
       //
       // Set up the CAN bus bit rate to 500kHz for each module
       // Refer to the Driver Library User Guide for information on how to set
       // tighter timing control. Additionally, consult the device data sheet
       // for more information about the CAN module clocking.
       //
       CAN_setBitRate(CANB_BASE, DEVICE_SYSCLK_FREQ, 500000, 16);
 
       //
       // Initialize the receive message object used for receiving CAN messages.
       // Message Object Parameters:
       //      CAN Module: A
       //      Message Object ID Number: 1
       //      Message Identifier: 0x18FB47FF
       //      Message Frame: EXTENDED
       //      Message Type: Receive
       //      Message ID Mask: 0x0
       //      Message Object Flags: None
       //      Message Data Length: "Don't care" for a Receive mailbox
       //
       CAN_setupMessageObject(CANB_BASE, RX_MSG_OBJ_ID, 0x18,
                              CAN_MSG_FRAME_EXT, CAN_MSG_OBJ_TYPE_RX, 0,
                              CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);
 
       // Start CAN module B operations
         //
         CAN_startModule(CANB_BASE);
 
 
    while(1)
    {
 
        //
        // Poll RxOk bit in CAN_ES register to check completion of Reception
        //
        if(((HWREGH(CANB_BASE + CAN_O_ES) & CAN_ES_RXOK)) == CAN_ES_RXOK)
        {
            //
            // Get the received message
            //
            CAN_readMessage(CANB_BASE, RX_MSG_OBJ_ID, rxMsgData);
            GPIO_togglePin(31);
            rxMsgCount++;
        }
    }
}

Objective:

The objective of this project is to establish bidirectional communication between two different microcontroller platforms, namely an Arduino and a TMS320F28379D. Specifically, we aim to implement communication via the Controller Area Network (CAN) protocol. In this setup, the Arduino will serve as the transmitter, sending CAN messages through serial communication to the TMS320F28379D, which will act as the receiver. Additionally, the TMS320F28379D will be capable of transmitting CAN messages back to the Arduino.

Arduino Code Explanation:

  • The Arduino code initializes serial communication and the MCP2515 CAN controller.
  • It sets up the MCP2515 to operate at 500 kbps and enters normal mode.
  • In the loop, it continuously checks for incoming CAN messages and serial data.
  • If a CAN message is received, it prints the CAN ID and data bytes.
  • If data is available on the serial port, it reads the data, parses it into CAN ID and data bytes, prepares a CAN message, and sends it.

TMS320F28379D Code Explanation:

  • The TMS320F28379D code initializes the CAN module and GPIO pins for CAN communication.
  • It sets up a message object to receive CAN messages with a specific ID (0x18).
  • In the main loop, it continuously checks for received CAN messages.
  • If a message is received, it reads the data bytes.
  • Additionally, it continuously sends three sets of CAN messages with different IDs and data bytes.
  • It waits for each transmission to complete before sending the next set of messages.

This setup enables bidirectional CAN communication between the Arduino and TMS320F28379D, with the Arduino transmitting CAN messages through serial communication and the TMS320F28379D receiving and transmitting CAN messages through its CAN module.

Benefits of the project:

Enables bidirectional communication between Arduino and TMS320F28379D microcontrollers over a CAN bus.

Facilitates real-time data exchange between different microcontroller platforms.
Provides a versatile platform for building complex control systems and networked devices.

Combined Example Code For An Arduino Transceiver

#include <SPI.h>
#include <mcp2515.h>

struct can_frame canMsg;

MCP2515 mcp2515(10);

void setup() {
  Serial.begin(9600);
  SPI.begin();
  
  mcp2515.reset();
  mcp2515.setBitrate(CAN_500KBPS, MCP_8MHZ);
  mcp2515.setNormalMode();
  
  // Print CAN bit rate information
  Serial.println("---------------------------------------------");
  Serial.println("Welcome To CAN Communication Interface");
  Serial.println("500 kbps");
  Serial.println("---------------------------------------------");
  delay(5000);
}

void loop() {
  // Check for incoming CAN messages
  if (mcp2515.readMessage(&canMsg) == MCP2515::ERROR_OK) {
    // Print received CAN message
    Serial.print("Received CAN ID 0x");
    Serial.print(canMsg.can_id, HEX);
    Serial.print(": ");
    printData(canMsg);
  }

  // Check for incoming data from the serial port
  if (Serial.available() > 0) {
    // If data is available on the serial port, read it and send as a CAN message
    sendSerialDataAsCanMessage();
  }
}

void printData(struct can_frame& msg) {
  // Print received data bytes
  for (int i = 0; i < msg.can_dlc; ++i) {
    // Print each byte in hexadecimal format
    Serial.print("0x");
    if (msg.data[i] < 0x10) {
      Serial.print("0"); // Add leading zero for single-digit hex values
    }
    Serial.print(msg.data[i], HEX);
    Serial.print(" ");
  }
  Serial.println();
}

void sendSerialDataAsCanMessage() {
  // Read data from the serial port
  String serialData = Serial.readStringUntil('\n');
  
  // Parse the received data and extract CAN ID and data bytes
  int canId = serialData.substring(0, 2).toInt(); // Assuming the first two characters represent the CAN ID
  int dataBytes[8];
  for (int i = 0; i < 8; i++) {
    dataBytes[i] = serialData.substring(3 + i * 3, 5 + i * 3).toInt(); // Assuming each data byte is separated by a space
  }
  
  // Prepare the CAN message
  canMsg.can_id = canId;
  canMsg.can_dlc = 8;
  for (int i = 0; i < 8; i++) {
    canMsg.data[i] = dataBytes[i];
  }

  // Send the CAN message
  mcp2515.sendMessage(&canMsg);
  
  // Print transmission confirmation
  Serial.println("Message Sent");
}

Flowchart Diagram for Arduino Transceiver

UML Diagram for Arduino Transceiver

Combined Example Code For A TMS320F28379D Transceiver

#include "F28x_Project.h"
#include "F2837xD_device.h"
#include "F2837xD_Examples.h"


#include "device.h"
#include "driverlib.h"


#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <math.h>
//
// Defines
//
#define TXCOUNT  100000
#define MSG_DATA_LENGTH    8
#define TX_MSG_OBJ_ID      1
#define TX_MSG_OBJ_ID_2    2
#define TX_MSG_OBJ_ID_3    3

#define RX_MSG_OBJ_ID      4   // Use mailbox 1
//24 21 32 23 14 45 26 27 18
uint16_t rxMsgData[8];
volatile uint32_t rxMsgCount = 0;

uint16_t txMsgData_1[8]={0x01,0x02,0x03,0x04,0x05,0x06,0x07,0x08};
uint16_t txMsgData_2[8]={0X09,0X10,0x11,0x12,0x13,0x14,0x15,0x16};
uint16_t txMsgData_3[8]={0X17,0X18,0x19,0x20,0x21,0x22,0x23,0x24};




void main(void)
{

    Device_init();

    //
    // Initialize GPIO and configure GPIO pins for CANTX/CANRX
    // on module A
    //
    Device_initGPIO();

    GPIO_setPinConfig(DEVICE_GPIO_CFG_CANRXB);
    GPIO_setPinConfig(DEVICE_GPIO_CFG_CANTXB);
    CAN_initModule(CANB_BASE);
    CAN_setBitRate(CANB_BASE, DEVICE_SYSCLK_FREQ, 500000, 16);

    CAN_setupMessageObject(CANB_BASE, RX_MSG_OBJ_ID, 0x18,
                           CAN_MSG_FRAME_STD, CAN_MSG_OBJ_TYPE_RX, 0,
                           CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);

    CAN_setupMessageObject(CANB_BASE, TX_MSG_OBJ_ID, 0x11,
                           CAN_MSG_FRAME_EXT, CAN_MSG_OBJ_TYPE_TX, 0,
                           CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);


    CAN_setupMessageObject(CANB_BASE, TX_MSG_OBJ_ID_2, 0x22,
                           CAN_MSG_FRAME_EXT, CAN_MSG_OBJ_TYPE_TX, 0,
                           CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);

    CAN_setupMessageObject(CANB_BASE, TX_MSG_OBJ_ID_3, 0x33,
                           CAN_MSG_FRAME_EXT, CAN_MSG_OBJ_TYPE_TX, 0,
                           CAN_MSG_OBJ_NO_FLAGS, MSG_DATA_LENGTH);



    CAN_startModule(CANB_BASE);


    while(1)

    {

        //
        // Poll RxOk bit in CAN_ES register to check completion of Reception
        //
        if(((HWREGH(CANB_BASE + CAN_O_ES) & CAN_ES_RXOK)) == CAN_ES_RXOK)
        {
            //
            // Get the received message
            //
            CAN_readMessage(CANB_BASE, RX_MSG_OBJ_ID, rxMsgData);
//            GPIO_togglePin(31);
            rxMsgCount++;
        }

        CAN_sendMessage(CANB_BASE, TX_MSG_OBJ_ID, MSG_DATA_LENGTH, txMsgData_1);
        CAN_sendMessage(CANB_BASE, TX_MSG_OBJ_ID_2, MSG_DATA_LENGTH, txMsgData_2);
        CAN_sendMessage(CANB_BASE, TX_MSG_OBJ_ID_3, MSG_DATA_LENGTH, txMsgData_3);

        while(((HWREGH(CANB_BASE + CAN_O_ES) & CAN_ES_TXOK)) ==  CAN_ES_TXOK)
        {

        }

        DEVICE_DELAY_US(1000000);

    }

}

Output Images

By Devilal

Leave a Reply

Your email address will not be published. Required fields are marked *