Skip to content

Instantly share code, notes, and snippets.

@pdp7
Last active November 10, 2019 19:44
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save pdp7/8e1765110178f4f65b04d19ac7cb1c4d to your computer and use it in GitHub Desktop.
Save pdp7/8e1765110178f4f65b04d19ac7cb1c4d to your computer and use it in GitHub Desktop.
Macchina SWCAN testing

Hardware

Macchina M2 microcontroller board

PocketBeagle with Macchina P1 cape

MCP2515 connected via SPI

Tests

Test 1: Macchina M2 to Macchina M2

Test 1: Macchina M2 to PocketBeagle with Macchina P1 cape

  • testing with Macchina M2 processor board (microcontroller) sending SWCAN traffic and the PocketBeagle with Macchina P1 cape trying to receive the SWCAN traffic
  • TX Macchina M2 board runs: m2_swcan_tx_example_arduino.ino (see below)
  • connected via ODB-II with 12V power splice and termination resistors
  • Commands to run on PocketBeagle:

enable device tree overlay and reboot:

debian@beaglebone:~$ grep -i mcp2515 /boot/uEnv.txt 
uboot_overlay_addr0=/lib/firmware/PB-MCP2515-SPI1.dtbo

set mode on transceiver M0/M1 pins:

sudo bash -c "echo out > /sys/class/gpio/gpio57/direction"
sudo bash -c "echo 1 > /sys/class/gpio/gpio57/value"
sudo bash -c "echo out > /sys/class/gpio/gpio47/direction"
sudo bash -c "echo 1 > /sys/class/gpio/gpio47/value"

bring up can2:

sudo ip link set can2 type can bitrate 33000 
sudo ifconfig can2 up
ifconfig can2

check stats:

root@beaglebone:~# ip -details -statistics link show can2
6: can2: <NOARP,UP,LOWER_UP,ECHO> mtu 16 qdisc pfifo_fast state UNKNOWN mode DEFAULT group default qlen 10
    link/can  promiscuity 0 
    can <LISTEN-ONLY> state ERROR-ACTIVE restart-ms 0 
	  bitrate 33333 sample-point 0.866 
	  tq 2000 prop-seg 6 phase-seg1 6 phase-seg2 2 sjw 1
	  mcp251x: tseg1 3..16 tseg2 2..8 sjw 1..4 brp 1..64 brp-inc 1
	  clock 4000000
	  re-started bus-errors arbit-lost error-warn error-pass bus-off
	  0          0          0          0          0          0         numtxqueues 1 numrxqueues 1 gso_max_size 65536 gso_max_segs 65535 
    RX: bytes  packets  errors  dropped overrun mcast   
    5990712    1498163  29954   0       29954   0       
    TX: bytes  packets  errors  dropped carrier collsns 
    0          0        0       0       0       0       

check dmesg:

[  189.768461] mcp251x spi1.1 can2: bitrate error 0.1%
[  194.342185] mcp251x_setup(): mcp251x_do_set_bittiming(net)
[  194.347929] CNF: 0x0a 0x9b 0x01
[  194.352749] mcp251x spi1.1: CNF: 0x0a 0x9b 0x01

run candump:

candump -cae can2,0:0,#FFFFFFFF

example output which is incorrect:

  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  077CFADA   [8]  remote request
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  077CFADA   [8]  remote request
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'
  can2  1D57F3A1   [8]  F2 DF EB 6B 91 39 CA 39   '...k.9.9'
  can2  1E87DE3F   [8]  34 D8 BD 75 A7 F5 65 FF   '4..u..e.'

I noticed that the irq for mcp251x driver is using 40% CPU:

 1237 root     -51   0       0      0      0 S 39.8  0.0  28:15.00 irq/80-mcp251x                                
Initializing SWCAN_RX_Example...
SWcan::setupSW(): speed=33
MCP2515::_init()
Freq: 16 freqMhz: 16000000.00 CAN_Bus_Speed: 33
speed: 33.00 speed: 33.00 NBT: 0.00
BRP: 0 tempBT: 242.42
BRP: 1 tempBT: 121.21
BRP: 2 tempBT: 80.81
BRP: 3 tempBT: 60.61
BRP: 4 tempBT: 48.48
BRP: 5 tempBT: 40.40
BRP: 6 tempBT: 34.63
BRP: 7 tempBT: 30.30
BRP: 8 tempBT: 26.94
BRP: 9 tempBT: 24.24
BRP: 10 tempBT: 22.04
BRP: 11 tempBT: 20.20
BRP: 12 tempBT: 18.65
BRP: 13 tempBT: 17.32
BRP: 14 tempBT: 16.16
BRP: 15 tempBT: 15.15
BRP: 16 tempBT: 14.26
BRP: 17 tempBT: 13.47
BRP: 18 tempBT: 12.76
BRP: 19 tempBT: 12.12
BRP: 20 tempBT: 11.54
BRP: 21 tempBT: 11.02
BRP: 22 tempBT: 10.54
BRP: 23 tempBT: 10.10
BRP: 24 tempBT: 9.70
BRP: 25 tempBT: 9.32
BRP: 26 tempBT: 8.98
BRP: 27 tempBT: 8.66
BRP: 28 tempBT: 8.36
BRP: 29 tempBT: 8.08
BRP: 30 tempBT: 7.82
BRP: 31 tempBT: 7.58
BRP: 32 tempBT: 7.35
BRP: 33 tempBT: 7.13
BRP: 34 tempBT: 6.93
BRP: 35 tempBT: 6.73
BRP: 36 tempBT: 6.55
BRP: 37 tempBT: 6.38
BRP: 38 tempBT: 6.22
BRP: 39 tempBT: 6.06
BRP: 40 tempBT: 5.91
BRP: 41 tempBT: 5.77
BRP: 42 tempBT: 5.64
BRP: 43 tempBT: 5.51
BRP: 44 tempBT: 5.39
BRP: 45 tempBT: 5.27
BRP: 46 tempBT: 5.16
BRP: 47 tempBT: 5.05
BRP: 48 tempBT: 4.95
BRP: 49 tempBT: 4.85
BRP: 50 tempBT: 4.75
BRP: 51 tempBT: 4.66
BRP: 52 tempBT: 4.57
BRP: 53 tempBT: 4.49
BRP: 54 tempBT: 4.41
BRP: 55 tempBT: 4.33
BRP: 56 tempBT: 4.25
BRP: 57 tempBT: 4.18
BRP: 58 tempBT: 4.11
BRP: 59 tempBT: 4.04
BRP: 60 tempBT: 3.97
BRP: 61 tempBT: 3.91
BRP: 62 tempBT: 3.85
BRP: 21 BT: 11 SPT: 7
PRSEG: 3 PHSEG1: 3 PHSEG2: 4SJW=0x
1 BRP=0x15 SAMPLE=0x0 BTLMODE=0x1 TXRTSCTRL=0x0D
CNF1=0x2A CNF2=0x29 CNF3=0x28
write CNF1: 0x15
write CNF2: 0x92
write CNF3: 0x83
write TXRTSCTRL: 0x0D
autoBaud: 0x0 Mode(MODE_LISTEN): 1 Mode(MODE_NORMAL): 1
read CNF3: rtn=0x15 data=0x15
return true
Ready to receive...
ID: 1
Extended: No
Length: 4
0 1 2 3
ID: 1
Extended: No
Length: 4
0 1 2 3
ID: 1
Extended: No
Length: 4
0 1 2 3
ID: 1
Extended: No
Length: 4
0 1 2 3
ID: 1
Extended: No
Length: 4
0 1 2 3
// DEPENDS ON LIBRARY: https://github.com/macchina/Single-Wire-CAN-mcp2515
/*
MCP2515 CAN Interface Using SPI
Author: David Harding
Created: 11/08/2010
Modified: 6/26/12 by RechargeCar Inc.
For further information see:
http://ww1.microchip.com/downloads/en/DeviceDoc/21801e.pdf
http://en.wikipedia.org/wiki/CAN_bus
The MCP2515 Library files also contain important information.
This sketch is configured to work with the 'Macchina' Automotive Interface board
manufactured by RechargeCar Inc. CS_PIN and INT_PIN are specific to this board.
This sketch shows the most basic of steps to send and receive CAN messages.
NOTE!!! If you use this sketch to test on a live system I suggest that you comment out the
send messages lines unless you are certain that they will have no detrimental effect!
This example code is in the public domain.
*/
#include <SPI.h>
#include <MCP2515_sw_can.h>
#include "variant.h"
#include <due_can.h>
// Pin definitions specific to how the MCP2515 is wired up.
#ifdef MACCHINA_M2
#define CS_PIN SPI0_CS3
#define INT_PIN SWC_INT
#else
#define CS_PIN 34
#define INT_PIN 38
#endif
// Create CAN object with pins as defined
SWcan SCAN(CS_PIN, INT_PIN);
void CANHandler() {
SCAN.intHandler();
}
void setup() {
pinMode(LED_BUILTIN, OUTPUT);
SerialUSB.begin(115200);
SerialUSB.println(" SWCAN_RX_Example: setup()");
digitalWrite(LED_BUILTIN, HIGH);
delay(500);
digitalWrite(LED_BUILTIN, LOW);
delay(500);
digitalWrite(LED_BUILTIN, HIGH);
delay(500);
SerialUSB.println("Initializing SWCAN_RX_Example...");
// Set up SPI Communication
// dataMode can be SPI_MODE0 or SPI_MODE3 only for MCP2515
SPI.setClockDivider(SPI_CLOCK_DIV2);
SPI.setDataMode(SPI_MODE0);
SPI.setBitOrder(MSBFIRST);
SPI.begin();
// Initialize MCP2515 CAN controller at the specified speed and clock frequency
// (Note: This is the oscillator attached to the MCP2515, not the Arduino oscillator)
//speed in KHz, clock in MHz
SCAN.setupSW(33);
attachInterrupt(INT_PIN, CANHandler, FALLING);
SCAN.InitFilters(true);
SCAN.mode(3);
SerialUSB.println("Ready to receive...");
pinMode(LED_BUILTIN, OUTPUT);
digitalWrite(LED_BUILTIN, HIGH);
}
byte i = 0;
// CAN message frame (actually just the parts that are exposed by the MCP2515 RX/TX buffers)
CAN_FRAME message;
void loop() {
if (SCAN.GetRXFrame(message)) {
// Print message
SerialUSB.print("ID: ");
SerialUSB.println(message.id, HEX);
SerialUSB.print("Extended: ");
if (message.extended) {
SerialUSB.println("Yes");
} else {
SerialUSB.println("No");
}
SerialUSB.print("Length: ");
SerialUSB.println(message.length, DEC);
for (i = 0; i < message.length; i++) {
SerialUSB.print(message.data.byte[i], HEX);
SerialUSB.print(" ");
}
SerialUSB.println();
SerialUSB.println();
digitalWrite(LED_BUILTIN, LOW);
digitalWrite(LED_BUILTIN, HIGH);
delay(500);
digitalWrite(LED_BUILTIN, LOW);
}
}
// DEPENDS ON LIBRARY: https://github.com/macchina/Single-Wire-CAN-mcp2515
/*
MCP2515 CAN Interface Using SPI
Author: David Harding
Created: 11/08/2010
Modified: 6/26/12 by RechargeCar Inc.
For further information see:
http://ww1.microchip.com/downloads/en/DeviceDoc/21801e.pdf
http://en.wikipedia.org/wiki/CAN_bus
The MCP2515 Library files also contain important information.
This sketch is configured to work with the 'Macchina' Automotive Interface board
manufactured by RechargeCar Inc. CS_PIN and INT_PIN are specific to this board.
This sketch shows the most basic of steps to send and receive CAN messages.
NOTE!!! If you use this sketch to test on a live system I suggest that you comment out the
send messages lines unless you are certain that they will have no detrimental effect!
This example code is in the public domain.
*/
#include <SPI.h>
#include <MCP2515_sw_can.h>
// Pin definitions specific to how the MCP2515 is wired up.
#ifdef MACCHINA_M2
#define CS_PIN SPI0_CS3
#define INT_PIN SWC_INT
#else
#define CS_PIN 34
#define INT_PIN 38
#endif
// Create CAN object with pins as defined
SWcan SCAN(CS_PIN, INT_PIN);
void CANHandler() {
SCAN.intHandler();
}
void setup() {
// turn the LED on (HIGH is the voltage level)
SerialUSB.begin(115200);
pinMode(LED_BUILTIN, OUTPUT);
digitalWrite(LED_BUILTIN, HIGH);
delay(1000);
digitalWrite(LED_BUILTIN, LOW);
delay(1000);
digitalWrite(LED_BUILTIN, HIGH);
delay(1000);
digitalWrite(LED_BUILTIN, LOW);
delay(1000);
SerialUSB.println("Initializing: LED_BUILTIN=");
SerialUSB.println(LED_BUILTIN);
digitalWrite(LED_BUILTIN, HIGH);
// Set up SPI Communication
// dataMode can be SPI_MODE0 or SPI_MODE3 only for MCP2515
SPI.setClockDivider(SPI_CLOCK_DIV2);
SPI.setDataMode(SPI_MODE0);
SPI.setBitOrder(MSBFIRST);
SPI.begin();
// Initialize MCP2515 CAN controller at the specified speed and clock frequency
// (Note: This is the oscillator attached to the MCP2515, not the Arduino oscillator)
//speed in KHz, clock in MHz
SCAN.setupSW(33);
attachInterrupt(INT_PIN, CANHandler, FALLING);
SCAN.InitFilters(true);
SCAN.mode(3); //3 = Normal, 2 = HV Wake up, 1 = High Speed, 0 = Sleep
SerialUSB.println("Ready to transmit...");
}
byte i=0;
// CAN message frame
CAN_FRAME message;
void loop() {
message.id = 0x01;
message.rtr = 0;
message.extended = 0;
message.length = 4;
message.data.byte[0] = 0x00;
message.data.byte[1] = 0x01;
message.data.byte[2] = 0x02;
message.data.byte[3] = 0x03;
SCAN.EnqueueTX(message);
SCAN.mode(2); //use HV Wakeup sending
//SCAN.EnqueueTX(message); //send it
delay(5); //wait a bit to make sure it was sent before ending HV Wake up
SCAN.mode(3); //go back to normal mode
SerialUSB.println("enqueue");
digitalWrite(LED_BUILTIN, HIGH);
delay(500);
digitalWrite(LED_BUILTIN, LOW);
delay(1000);
/*
message.id = 0x02;
message.rtr = 0;
message.extended = 1;
message.length = 6;
message.data.byte[0] = 0x01;
message.data.byte[1] = 0x02;
message.data.byte[2] = 0x03;
message.data.byte[3] = 0x04;
message.data.byte[4] = 0x05;
message.data.byte[5] = 0x06;
SCAN.mode(2); //use HV Wakeup sending
SCAN.EnqueueTX(message); //send it
delay(5); //wait a bit to make sure it was sent before ending HV Wake up
SCAN.mode(3); //go back to normal mode
delay(2000);*/
}
// /home/pdp7/.arduino15/packages/macchina/hardware/sam/0.3.13/libraries/mcp2515/src/MCP2515.cpp
/*
MCP2515.cpp - Library for Microchip MCP2515 CAN Controller
Author: David Harding
Maintainer: RechargeCar Inc (http://rechargecar.com)
Further Modification: Collin Kidder
Created: 11/08/2010
For further information see:
http://ww1.microchip.com/downloads/en/DeviceDoc/21801e.pdf
http://en.wikipedia.org/wiki/CAN_bus
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "Arduino.h"
#include "SPI.h"
#include "MCP2515.h"
#include "MCP2515_defs.h"
SPISettings canSPISettings(1000000, MSBFIRST, SPI_MODE0);
MCP2515::MCP2515(uint8_t CS_Pin, uint8_t INT_Pin) : CAN_COMMON(6) {
pinMode(CS_Pin, OUTPUT);
digitalWrite(CS_Pin,HIGH);
pinMode(INT_Pin,INPUT);
digitalWrite(INT_Pin,HIGH);
_CS = CS_Pin;
_INT = INT_Pin;
savedBaud = 0;
savedFreq = 0;
running = 0;
InitBuffers();
}
//set all buffer counters to zero to reset them
void MCP2515::InitBuffers() {
rx_frame_read_pos = 0;
rx_frame_write_pos = 0;
tx_frame_read_pos = 0;
tx_frame_write_pos = 0;
}
/*
Initialize MCP2515
int CAN_Bus_Speed = transfer speed in kbps (or raw CAN speed in bits per second)
int Freq = MCP2515 oscillator frequency in MHz
int SJW = Synchronization Jump Width Length bits - 1 to 4 (see data sheet)
returns baud rate set
Sending a bus speed of 0 kbps initiates AutoBaud and returns zero if no
baud rate could be determined. There must be two other active nodes on the bus!
*/
int MCP2515::Init(uint32_t CAN_Bus_Speed, uint8_t Freq) {
if(CAN_Bus_Speed>0) {
if(_init(CAN_Bus_Speed, Freq, 1, false)) {
savedBaud = CAN_Bus_Speed;
savedFreq = Freq;
running = 1;
return CAN_Bus_Speed;
}
} else {
int i=0;
uint8_t interruptFlags = 0;
for(i=5; i<1000; i=i+5) {
if(_init(i, Freq, 1, true)) {
// check for bus activity
Write(CANINTF,0);
delay(500); // need the bus to be communicating within this time frame
if(Interrupt()) {
// determine which interrupt flags have been set
interruptFlags = Read(CANINTF);
if(!(interruptFlags & MERRF)) {
// to get here we must have received something without errors
Mode(MODE_NORMAL);
savedBaud = i;
savedFreq = Freq;
running = 1;
return i;
}
}
}
}
}
return 0;
}
int MCP2515::Init(uint32_t CAN_Bus_Speed, uint8_t Freq, uint8_t SJW) {
if(SJW < 1) SJW = 1;
if(SJW > 4) SJW = 4;
if(CAN_Bus_Speed>0) {
if(_init(CAN_Bus_Speed, Freq, SJW, false)) {
savedBaud = CAN_Bus_Speed;
savedFreq = Freq;
running = 1;
return CAN_Bus_Speed;
}
} else {
int i=0;
uint8_t interruptFlags = 0;
for(i=5; i<1000; i=i+5) {
if(_init(i, Freq, SJW, true)) {
// check for bus activity
Write(CANINTF,0);
delay(500); // need the bus to be communicating within this time frame
if(Interrupt()) {
// determine which interrupt flags have been set
interruptFlags = Read(CANINTF);
if(!(interruptFlags & MERRF)) {
// to get here we must have received something without errors
Mode(MODE_NORMAL);
savedBaud = i;
savedFreq = Freq;
running = 1;
return i;
}
}
}
}
}
return 0;
}
bool MCP2515::_init(uint32_t CAN_Bus_Speed, uint8_t Freq, uint8_t SJW, bool autoBaud) {
// Reset MCP2515 which puts it in configuration mode
Reset();
//delay(2);
SerialUSB.println("MCP2515::_init()");
Write(CANINTE,0); //disable all interrupts during init
Write(TXB0CTRL, 0); //reset transmit control
Write(TXB1CTRL, 0); //reset transmit control
Write(TXB2CTRL, 0); //reset transmit control
// Calculate bit timing registers
uint8_t BRP;
float TQ;
uint8_t BT;
float tempBT;
float freqMhz = Freq * 1000000.0;
float bestMatchf = 10.0;
int bestMatchIdx = 10;
float savedBT;
SerialUSB.print("Freq: ");
SerialUSB.print(Freq);
SerialUSB.print(" freqMhz: ");
SerialUSB.print(freqMhz);
SerialUSB.print(" CAN_Bus_Speed: ");
SerialUSB.println(CAN_Bus_Speed);
float speed = CAN_Bus_Speed;
SerialUSB.print(" speed: ");
SerialUSB.print(speed);
if (speed > 5000.0) speed *= 0.001;
SerialUSB.print(" speed: ");
SerialUSB.print(speed);
float NBT = 1.0 / (speed * 1000.0); // Nominal Bit Time - How long a single CAN bit should take
SerialUSB.print(" NBT: ");
SerialUSB.println(NBT);
//Now try each divisor to see which can most closely match the target.
for(BRP=0; BRP < 63; BRP++) {
TQ = 2.0 * (float)(BRP + 1) / (float)freqMhz;
tempBT = NBT / TQ;
SerialUSB.print("BRP: ");
SerialUSB.print(BRP);
SerialUSB.print(" tempBT: ");
SerialUSB.println(tempBT);
BT = (int)tempBT;
if ( (tempBT - BT) < bestMatchf)
{
if (BT > 7 && BT < 25)
{
bestMatchf = (tempBT - BT);
bestMatchIdx = BRP;
savedBT = BT;
}
}
}
BT = savedBT;
BRP = bestMatchIdx;
SerialUSB.print("BRP: ");
SerialUSB.print(BRP);
SerialUSB.print(" BT: ");
SerialUSB.print(BT);
byte SPT = (0.7 * BT); // Sample point
byte PRSEG = (SPT - 1) / 2;
byte PHSEG1 = SPT - PRSEG - 1;
byte PHSEG2 = BT - PHSEG1 - PRSEG - 1;
SerialUSB.print(" SPT: ");
SerialUSB.println(SPT);
SerialUSB.print("PRSEG: ");
SerialUSB.print(PRSEG);
SerialUSB.print(" PHSEG1: ");
SerialUSB.print(PHSEG1);
SerialUSB.print(" PHSEG2: ");
SerialUSB.print(PHSEG2);
// Programming requirements
if(PRSEG + PHSEG1 < PHSEG2)
{
SerialUSB.println("PRSEG + PHSEG1 less than PHSEG2!");
return false;
}
if(PHSEG2 <= SJW)
{
SerialUSB.println("PHSEG2 less than SJW");
return false;
}
uint8_t BTLMODE = 1;
uint8_t SAMPLE = 0;
SerialUSB.println("SJW=0x");
SerialUSB.print(SJW, HEX);
SerialUSB.print(" BRP=0x");
SerialUSB.print(BRP, HEX);
SerialUSB.print(" SAMPLE=0x");
SerialUSB.print(SAMPLE, HEX);
SerialUSB.print(" BTLMODE=0x");
SerialUSB.print(BTLMODE, HEX);
SerialUSB.print(" TXRTSCTRL=0x0");
SerialUSB.println(TXRTSCTRL, HEX);
SerialUSB.print("CNF1=0x");
SerialUSB.print(CNF1, HEX);
SerialUSB.print(" CNF2=0x");
SerialUSB.print(CNF2, HEX);
SerialUSB.print(" CNF3=0x");
SerialUSB.println(CNF3, HEX);
// Set registers
byte data = (((SJW-1) << 6) | BRP);
Write(CNF1, data);
SerialUSB.print("write CNF1: 0x");
SerialUSB.println(data, HEX);
Write(CNF2, ((BTLMODE << 7) | (SAMPLE << 6) | ((PHSEG1-1) << 3) | (PRSEG-1)));
SerialUSB.print("write CNF2: 0x");
SerialUSB.println(((BTLMODE << 7) | (SAMPLE << 6) | ((PHSEG1-1) << 3) | (PRSEG-1)), HEX);
Write(CNF3, (B10000000 | (PHSEG2-1)));
SerialUSB.print("write CNF3: 0x");
SerialUSB.println((B10000000 | (PHSEG2-1)), HEX);
SerialUSB.print("write TXRTSCTRL: 0x0");
SerialUSB.println(TXRTSCTRL, HEX);
Write(TXRTSCTRL,0);
delay(1);
SerialUSB.print("autoBaud: 0x");
SerialUSB.print(autoBaud, HEX);
SerialUSB.print(" Mode(MODE_LISTEN): ");
SerialUSB.print(Mode(MODE_LISTEN));
SerialUSB.print(" Mode(MODE_NORMAL): ");
SerialUSB.println(Mode(MODE_NORMAL));
if(!autoBaud) {
// Return to Normal mode
if(!Mode(MODE_NORMAL))
{
SerialUSB.println("Could not enter normal mode");
return false;
}
} else {
// Set to Listen Only mode
if(!Mode(MODE_LISTEN))
{
SerialUSB.println("Could not enter listen only mode");
return false;
}
}
// Enable all interupts
Write(CANINTE,255);
// Test that we can read back from the MCP2515 what we wrote to it
byte rtn = Read(CNF1);
SerialUSB.print("read CNF3: rtn=0x");
SerialUSB.print(rtn, HEX);
SerialUSB.print(" data=0x");
SerialUSB.println(data, HEX);
if (rtn == data) {
SerialUSB.println("return true");
return true;
} else {
SerialUSB.println("return false");
SerialUSB.println(data, HEX);
SerialUSB.println(rtn, HEX);
return false;
}
SerialUSB.println("end of function, return false");
return false;
}
uint16_t MCP2515::available()
{
int val;
val = rx_frame_read_pos - rx_frame_write_pos;
//Now, because this is a cyclic buffer it is possible that the ordering was reversed
//So, handle that case
if (val < 0) val += 8;
}
int MCP2515::_setFilter(uint32_t id, uint32_t mask, bool extended)
{
uint32_t filterVal;
boolean isExtended;
for (int i = 0; i < 6; i++)
{
GetRXFilter(i, filterVal, isExtended);
if (filterVal == 0) //empty filter. Let's fill it and leave
{
if (i < 2)
{
GetRXMask(MASK0, filterVal);
if (filterVal == 0) filterVal = mask;
filterVal &= mask;
SetRXMask(MASK0, filterVal);
}
else
{
GetRXMask(MASK1, filterVal);
if (filterVal == 0) filterVal = mask;
filterVal &= mask;
SetRXMask(MASK1, filterVal);
}
if (i < 3)
SetRXFilter(FILTER0 + (i * 4), id, extended);
else
SetRXFilter(FILTER3 + ((i-3) * 4), id, extended);
return i;
}
}
//if we got here then there were no free filters. Return value of deaaaaath!
return -1;
}
//we don't exactly have mailboxes, we have filters (6 of them) but it's the same basic idea
int MCP2515::_setFilterSpecific(uint8_t mailbox, uint32_t id, uint32_t mask, bool extended)
{
uint32_t oldMask;
if (mailbox < 2) //MASK0
{
GetRXMask(MASK0, oldMask);
oldMask &= mask;
SetRXMask(MASK0, oldMask);
}
else //MASK1
{
GetRXMask(MASK1, oldMask);
oldMask &= mask;
SetRXMask(MASK0, oldMask);
}
if (mailbox < 3)
SetRXFilter(FILTER0 + (mailbox * 4), id, extended);
else
SetRXFilter(FILTER3 + ((mailbox-3) * 4), id, extended);
}
uint32_t MCP2515::init(uint32_t ul_baudrate)
{
Init(ul_baudrate, 16);
}
uint32_t MCP2515::beginAutoSpeed()
{
Init(0, 16);
}
uint32_t MCP2515::set_baudrate(uint32_t ul_baudrate)
{
Init(ul_baudrate, 16);
}
void MCP2515::setListenOnlyMode(bool state)
{
if (state)
Mode(MODE_LISTEN);
else Mode(MODE_NORMAL);
}
void MCP2515::enable()
{
Mode(MODE_NORMAL);
}
void MCP2515::disable()
{
Mode(MODE_SLEEP);
}
bool MCP2515::sendFrame(CAN_FRAME& txFrame)
{
EnqueueTX(txFrame);
}
bool MCP2515::rx_avail()
{
return available()>0?true:false;
}
uint32_t MCP2515::get_rx_buff(CAN_FRAME &msg)
{
return GetRXFrame(msg);
}
void MCP2515::Reset() {
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_RESET);
digitalWrite(_CS,HIGH);
SPI.endTransaction();
}
uint8_t MCP2515::Read(uint8_t address) {
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_READ);
SPI.transfer(address);
uint8_t data = SPI.transfer(0x00);
digitalWrite(_CS,HIGH);
SPI.endTransaction();
return data;
}
void MCP2515::Read(uint8_t address, uint8_t data[], uint8_t bytes) {
// allows for sequential reading of registers starting at address - see data sheet
uint8_t i;
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_READ);
SPI.transfer(address);
for(i=0;i<bytes;i++) {
data[i] = SPI.transfer(0x00);
}
digitalWrite(_CS,HIGH);
SPI.endTransaction();
}
CAN_FRAME MCP2515::ReadBuffer(uint8_t buffer) {
// Reads an entire RX buffer.
// buffer should be either RXB0 or RXB1
CAN_FRAME message;
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_READ_BUFFER | (buffer<<1));
uint8_t byte1 = SPI.transfer(0x00); // RXBnSIDH
uint8_t byte2 = SPI.transfer(0x00); // RXBnSIDL
uint8_t byte3 = SPI.transfer(0x00); // RXBnEID8
uint8_t byte4 = SPI.transfer(0x00); // RXBnEID0
uint8_t byte5 = SPI.transfer(0x00); // RXBnDLC
message.extended = (byte2 & B00001000);
if(message.extended) {
message.id = (byte1>>3);
message.id = (message.id<<8) | ((byte1<<5) | ((byte2>>5)<<2) | (byte2 & B00000011));
message.id = (message.id<<8) | byte3;
message.id = (message.id<<8) | byte4;
} else {
message.id = ((byte1>>5)<<8) | ((byte1<<3) | (byte2>>5));
}
message.rtr=(byte5 & B01000000);
message.length = (byte5 & B00001111); // Number of data bytes
for(int i=0; i<message.length; i++) {
message.data.byte[i] = SPI.transfer(0x00);
}
digitalWrite(_CS,HIGH);
SPI.endTransaction();
return message;
}
void MCP2515::Write(uint8_t address, uint8_t data) {
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_WRITE);
SPI.transfer(address);
SPI.transfer(data);
digitalWrite(_CS,HIGH);
SPI.endTransaction();
}
void MCP2515::Write(uint8_t address, uint8_t data[], uint8_t bytes) {
// allows for sequential writing of registers starting at address - see data sheet
uint8_t i;
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_WRITE);
SPI.transfer(address);
for(i=0;i<bytes;i++) {
SPI.transfer(data[i]);
}
digitalWrite(_CS,HIGH);
SPI.endTransaction();
}
void MCP2515::SendBuffer(uint8_t buffers) {
// buffers should be any combination of TXB0, TXB1, TXB2 ORed together, or TXB_ALL
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_RTS | buffers);
digitalWrite(_CS,HIGH);
SPI.endTransaction();
}
void MCP2515::LoadBuffer(uint8_t buffer, CAN_FRAME *message) {
// buffer should be one of TXB0, TXB1 or TXB2
if(buffer==TXB0) buffer = 0; //the values we need are 0, 2, 4 TXB1 and TXB2 are already 2 / 4
uint8_t byte1=0; // TXBnSIDH
uint8_t byte2=0; // TXBnSIDL
uint8_t byte3=0; // TXBnEID8
uint8_t byte4=0; // TXBnEID0
uint8_t byte5=0; // TXBnDLC
if(message->extended) {
byte1 = byte((message->id<<3)>>24); // 8 MSBits of SID
byte2 = byte((message->id<<11)>>24) & B11100000; // 3 LSBits of SID
byte2 = byte2 | byte((message->id<<14)>>30); // 2 MSBits of EID
byte2 = byte2 | B00001000; // EXIDE
byte3 = byte((message->id<<16)>>24); // EID Bits 15-8
byte4 = byte((message->id<<24)>>24); // EID Bits 7-0
} else {
byte1 = byte((message->id<<21)>>24); // 8 MSBits of SID
byte2 = byte((message->id<<29)>>24) & B11100000; // 3 LSBits of SID
byte3 = 0; // TXBnEID8
byte4 = 0; // TXBnEID0
}
byte5 = message->length;
if(message->rtr) {
byte5 = byte5 | B01000000;
}
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_LOAD_BUFFER | buffer);
SPI.transfer(byte1);
SPI.transfer(byte2);
SPI.transfer(byte3);
SPI.transfer(byte4);
SPI.transfer(byte5);
for(int i=0;i<message->length;i++) {
SPI.transfer(message->data.byte[i]);
}
digitalWrite(_CS,HIGH);
SPI.endTransaction();
}
uint8_t MCP2515::Status() {
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_STATUS);
uint8_t data = SPI.transfer(0x00);
digitalWrite(_CS,HIGH);
SPI.endTransaction();
return data;
/*
bit 7 - CANINTF.TX2IF
bit 6 - TXB2CNTRL.TXREQ
bit 5 - CANINTF.TX1IF
bit 4 - TXB1CNTRL.TXREQ
bit 3 - CANINTF.TX0IF
bit 2 - TXB0CNTRL.TXREQ
bit 1 - CANINTFL.RX1IF
bit 0 - CANINTF.RX0IF
*/
}
uint8_t MCP2515::RXStatus() {
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_RX_STATUS);
uint8_t data = SPI.transfer(0x00);
digitalWrite(_CS,HIGH);
SPI.endTransaction();
return data;
/*
bit 7 - CANINTF.RX1IF
bit 6 - CANINTF.RX0IF
bit 5 -
bit 4 - RXBnSIDL.EIDE
bit 3 - RXBnDLC.RTR
bit 2 | 1 | 0 | Filter Match
------|---|---|-------------
0 | 0 | 0 | RXF0
0 | 0 | 1 | RXF1
0 | 1 | 0 | RXF2
0 | 1 | 1 | RXF3
1 | 0 | 0 | RXF4
1 | 0 | 1 | RXF5
1 | 1 | 0 | RXF0 (rollover to RXB1)
1 | 1 | 1 | RXF1 (rollover to RXB1)
*/
}
void MCP2515::BitModify(uint8_t address, uint8_t mask, uint8_t data) {
// see data sheet for explanation
SPI.beginTransaction(canSPISettings);
digitalWrite(_CS,LOW);
SPI.transfer(CAN_BIT_MODIFY);
SPI.transfer(address);
SPI.transfer(mask);
SPI.transfer(data);
digitalWrite(_CS,HIGH);
SPI.endTransaction();
}
bool MCP2515::Interrupt() {
return (digitalRead(_INT)==LOW);
}
bool MCP2515::Mode(byte mode) {
/*
mode can be one of the following:
MODE_CONFIG
MODE_LISTEN
MODE_LOOPBACK
MODE_SLEEP
MODE_NORMAL
*/
BitModify(CANCTRL, B11100000, mode);
delay(10); // allow for any transmissions to complete
uint8_t data = Read(CANSTAT); // check mode has been set
return ((data & mode)==mode);
}
/*Initializes all filters to either accept all frames or accept none
//This doesn't need to be called if you want to accept everything
//because that's the default. So, call this with permissive = false
//to state with an accept nothing state and then add acceptance masks/filters
//thereafter
*/
void MCP2515::InitFilters(bool permissive) {
uint32_t value;
uint32_t value32;
if (permissive) {
value = 0;
value32 = 0;
}
else {
value = 0x7FF; //all 11 bits set
value32 = 0x1FFFFFFF; //all 29 bits set
}
SetRXMask(MASK0, value32);
SetRXMask(MASK1, value);
SetRXFilter(FILTER0, value32, 1);
SetRXFilter(FILTER1, value32, 1);
SetRXFilter(FILTER2, value, 0);
SetRXFilter(FILTER3, value, 0);
SetRXFilter(FILTER4, value, 0);
SetRXFilter(FILTER5, value, 0);
}
/*
mask = either MASK0 or MASK1
MaskValue is either an 11 or 29 bit mask value to set
Note that maskes do not store whether they'd be standard or extended. Filters do that. It's a little confusing
*/
void MCP2515::SetRXMask(uint8_t mask, uint32_t MaskValue) {
uint8_t temp_buff[4];
uint8_t oldMode;
oldMode = Read(CANSTAT);
Mode(MODE_CONFIG); //have to be in config mode to change mask
temp_buff[0] = byte((MaskValue << 3) >> 24);
temp_buff[1] = byte((MaskValue << 11) >> 24) & B11100000;
temp_buff[1] |= byte((MaskValue << 14) >> 30);
temp_buff[2] = byte((MaskValue << 16)>>24);
temp_buff[3] = byte((MaskValue << 24)>>24);
Write(mask, temp_buff, 4); //send the four byte mask out to the proper address
Mode(oldMode);
}
/*
filter = FILTER0, FILTER1, FILTER2, FILTER3, FILTER4, FILTER5 (pick one)
FilterValue = 11 or 29 bit filter to use
ext is true if this filter should apply to extended frames or false if it should apply to standard frames.
Do note that, while this function looks a lot like the mask setting function is is NOT identical
It might be able to be though... The setting of EXIDE would probably just be ignored by the mask
*/
void MCP2515::SetRXFilter(uint8_t filter, uint32_t FilterValue, bool ext) {
uint8_t temp_buff[4];
uint8_t oldMode;
oldMode = Read(CANSTAT);
Mode(MODE_CONFIG); //have to be in config mode to change mask
if (ext) { //fill out all 29 bits
temp_buff[0] = byte((FilterValue << 3) >> 24);
temp_buff[1] = byte((FilterValue << 11) >> 24) & B11100000;
temp_buff[1] |= byte((FilterValue << 14) >> 30);
temp_buff[1] |= B00001000; //set EXIDE
temp_buff[2] = byte((FilterValue << 16)>>24);
temp_buff[3] = byte((FilterValue << 24)>>24);
}
else { //make sure to set mask as 11 bit standard mask
temp_buff[0] = byte((FilterValue << 21)>>24);
temp_buff[1] = byte((FilterValue << 29) >> 24) & B11100000;
temp_buff[2] = 0;
temp_buff[3] = 0;
}
Write(filter, temp_buff, 4); //send the four byte mask out to the proper address
Mode(oldMode);
}
void MCP2515::GetRXFilter(uint8_t filter, uint32_t &filterVal, boolean &isExtended)
{
uint8_t temp_buff[4];
uint8_t oldMode;
oldMode = Read(CANSTAT);
Mode(MODE_CONFIG); //have to be in config mode to change mask
Read(filter, temp_buff, 4);
//these 11 bits are used either way and stored the same way either way
filterVal = temp_buff[0] << 3;
filterVal |= temp_buff[1] >> 5;
isExtended = false;
if (temp_buff[1] & B00001000) //extended / 29 bit filter - get the remaining 18 bits we need
{
isExtended = true;
filterVal |= (temp_buff[1] & 3) << 27;
filterVal |= temp_buff[2] << 19;
filterVal |= temp_buff[3] << 11;
}
Mode(oldMode);
}
void MCP2515::GetRXMask(uint8_t mask, uint32_t &filterVal)
{
uint8_t temp_buff[4];
uint8_t oldMode;
oldMode = Read(CANSTAT);
Mode(MODE_CONFIG); //have to be in config mode to change mask
Read(mask, temp_buff, 4);
filterVal = temp_buff[0] << 3;
filterVal |= temp_buff[1] >> 5;
filterVal |= (temp_buff[1] & 3) << 27;
filterVal |= temp_buff[2] << 19;
filterVal |= temp_buff[3] << 11;
Mode(oldMode);
}
//Places the given frame into the receive queue
void MCP2515::EnqueueRX(CAN_FRAME& newFrame) {
uint8_t counter;
rx_frames[rx_frame_write_pos].id = newFrame.id;
rx_frames[rx_frame_write_pos].rtr = newFrame.rtr;
rx_frames[rx_frame_write_pos].extended = newFrame.extended;
rx_frames[rx_frame_write_pos].length = newFrame.length;
for (counter = 0; counter < 8; counter++) rx_frames[rx_frame_write_pos].data.byte[counter] = newFrame.data.byte[counter];
rx_frame_write_pos = (rx_frame_write_pos + 1) % 8;
}
//Places the given frame into the transmit queue
//Well, maybe. If there is currently an open hardware buffer
//it will place it into hardware immediately instead of using
//the software queue
void MCP2515::EnqueueTX(CAN_FRAME& newFrame) {
uint8_t counter;
uint8_t status = Status() & 0b01010100; //mask for only the transmit buffer empty bits
//don't allow sending or queueing of frames if we're not properly initialized
if (running == 0) {
return;
}
if (status != 0b01010100) { //found an open slot
if ((status & 0b00000100) == 0) { //transmit buffer 0 is open
LoadBuffer(TXB0, &newFrame);
SendBuffer(TXB0);
}
else if ((status & 0b00010000) == 0) { //transmit buffer 1 is open
LoadBuffer(TXB1, &newFrame);
SendBuffer(TXB1);
}
else { // must have been buffer 2 then.
LoadBuffer(TXB2, &newFrame);
SendBuffer(TXB2);
}
}
else { //hardware is busy. queue it in software
if (tx_frame_write_pos != tx_frame_read_pos) { //don't add another frame if the buffer is already full
tx_frames[tx_frame_write_pos].id = newFrame.id;
tx_frames[tx_frame_write_pos].rtr = newFrame.rtr;
tx_frames[tx_frame_write_pos].extended = newFrame.extended;
tx_frames[tx_frame_write_pos].length = newFrame.length;
for (counter = 0; counter < 8; counter++) tx_frames[tx_frame_write_pos].data.byte[counter] = newFrame.data.byte[counter];
tx_frame_write_pos = (tx_frame_write_pos + 1) % 8;
}
}
}
bool MCP2515::GetRXFrame(CAN_FRAME &frame) {
uint8_t counter;
if (rx_frame_read_pos != rx_frame_write_pos) {
frame.id = rx_frames[rx_frame_read_pos].id;
frame.rtr = rx_frames[rx_frame_read_pos].rtr;
frame.extended = rx_frames[rx_frame_read_pos].extended;
frame.length = rx_frames[rx_frame_read_pos].length;
for (counter = 0; counter < 8; counter++) frame.data.byte[counter] = rx_frames[rx_frame_read_pos].data.byte[counter];
rx_frame_read_pos = (rx_frame_read_pos + 1) % 8;
return true;
}
else return false;
}
void MCP2515::intHandler(void) {
CAN_FRAME message;
uint32_t ctrlVal;
// determine which interrupt flags have been set
uint8_t interruptFlags = Read(CANINTF);
//Now, acknowledge the interrupts by clearing the intf bits
Write(CANINTF, 0);
if(interruptFlags & RX0IF) {
// read from RX buffer 0
message = ReadBuffer(RXB0);
ctrlVal = Read(RXB0CTRL);
handleFrameDispatch(&message, ctrlVal & 1);
}
if(interruptFlags & RX1IF) {
// read from RX buffer 1
message = ReadBuffer(RXB1);
ctrlVal = Read(RXB1CTRL);
handleFrameDispatch(&message, ctrlVal & 7);
}
if(interruptFlags & TX0IF) {
// TX buffer 0 sent
if (tx_frame_read_pos != tx_frame_write_pos) {
LoadBuffer(TXB0, (CAN_FRAME *)&tx_frames[tx_frame_read_pos]);
SendBuffer(TXB0);
tx_frame_read_pos = (tx_frame_read_pos + 1) % 8;
}
}
if(interruptFlags & TX1IF) {
// TX buffer 1 sent
if (tx_frame_read_pos != tx_frame_write_pos) {
LoadBuffer(TXB1, (CAN_FRAME *)&tx_frames[tx_frame_read_pos]);
SendBuffer(TXB1);
tx_frame_read_pos = (tx_frame_read_pos + 1) % 8;
}
}
if(interruptFlags & TX2IF) {
// TX buffer 2 sent
if (tx_frame_read_pos != tx_frame_write_pos) {
LoadBuffer(TXB2, (CAN_FRAME *)&tx_frames[tx_frame_read_pos]);
SendBuffer(TXB2);
tx_frame_read_pos = (tx_frame_read_pos + 1) % 8;
}
}
if(interruptFlags & ERRIF) {
if (running == 1) { //if there was an error and we had been initialized then try to fix it by reinitializing
running = 0;
//InitBuffers();
//Init(savedBaud, savedFreq);
}
}
if(interruptFlags & MERRF) {
// error handling code
// if TXBnCTRL.TXERR set then transmission error
// if message is lost TXBnCTRL.MLOA will be set
if (running == 1) { //if there was an error and we had been initialized then try to fix it by reinitializing
running = 0;
//InitBuffers();
//Init(savedBaud, savedFreq);
}
}
}
void MCP2515::handleFrameDispatch(CAN_FRAME *frame, int filterHit)
{
CANListener *thisListener;
//First, try to send a callback. If no callback registered then buffer the frame.
if (cbCANFrame[filterHit])
{
(*cbCANFrame[filterHit])(frame);
return;
}
else if (cbGeneral)
{
(*cbGeneral)(frame);
return;
}
else
{
for (int listenerPos = 0; listenerPos < SIZE_LISTENERS; listenerPos++)
{
thisListener = listener[listenerPos];
if (thisListener != NULL)
{
if (thisListener->isCallbackActive(filterHit))
{
thisListener->gotFrame(frame, filterHit);
return;
}
else if (thisListener->isCallbackActive(numFilters)) //global catch-all
{
thisListener->gotFrame(frame, -1);
return;
}
}
}
}
//if none of the callback types caught this frame then queue it in the buffer
EnqueueRX(*frame);
}
// /home/pdp7/.arduino15/packages/macchina/hardware/sam/0.3.13/libraries/Single-Wire-CAN-mcp2515/src/MCP2515_sw_can.cpp
/*
mcp_swcan.h
2017 Copyright (c) Macchina LLC. All right reserved.
Author: Blaž Pongrac B.S., RoboSap, Institute of Technology, Ptuj (www.robosap-institut.eu)
The MIT License (MIT)
Copyright (c) 2017 Macchina LLC.
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
#include "Arduino.h"
#include "SPI.h"
#include <MCP2515_sw_can.h>
#include "MCP2515_defs.h"
//Initalize the two mode pins and also set them to mode 3 which is normal mode
void SWcan::setupSW(unsigned long speed)
{
SerialUSB.print("SWcan::setupSW(): speed=");
SerialUSB.println(speed);
Init(speed, 16);
pinMode(SWC_M0, OUTPUT);
pinMode(SWC_M1, OUTPUT);
digitalWrite(SWC_M0, HIGH);
digitalWrite(SWC_M1, HIGH);
}
void SWcan::mode(byte mode)
{
switch (mode)
{
case 0: // Sleep Mode
digitalWrite(SWC_M0, LOW);
digitalWrite(SWC_M1, LOW);
break;
case 1: // High Speed
digitalWrite(SWC_M0, HIGH);
digitalWrite(SWC_M1, LOW);
break;
case 2: // High Voltage Wake-Up
digitalWrite(SWC_M0, LOW);
digitalWrite(SWC_M1, HIGH);
break;
case 3: // Normal Mode
digitalWrite(SWC_M0, HIGH);
digitalWrite(SWC_M1, HIGH);
break;
default:
break;
}
}
@pdp7
Copy link
Author

pdp7 commented Nov 10, 2019

[   27.141531] mcp251x_can_probe: enter
[   27.331410] mcp251x_can_probe: OVERRIDE freq=clk_get_rate(clk)=16000000
[   27.810754] mcp251x spi1.1 can2: MCP2515 successfully initialized.
[   53.592390] rtl8192cu: Chip version 0x10
[   53.685037] rtl8192cu: Board Type 0
[   53.685205] rtl_usb: rx_max_size 15360, rx_urb_num 8, in_ep 1
[   53.685355] rtl8192cu: Loading firmware rtlwifi/rtl8192cufw_TMSC.bin
[   53.702346] ieee80211 phy0: Selected rate control algorithm 'rtl_rc'
[   53.734454] rtl8192cu: MAC auto ON okay!
[   53.752863] usbcore: registered new interface driver rtl8192cu
[   53.812036] rtl8192cu: Tx queue select: 0x05
[   55.680171] IPv6: ADDRCONF(NETDEV_UP): wlan0: link is not ready
[   87.576861] mcp251x spi1.1 can2: bitrate error 0.1%
[   87.726226] mcp251x_setup(): mcp251x_do_set_bittiming(net)
[   87.735077] CNF: 0x15 0x9b 0x01
[   87.755182] IPv6: ADDRCONF(NETDEV_UP): can2: link is not ready
[   87.755246] IPv6: ADDRCONF(NETDEV_CHANGE): can2: link becomes ready
debian@beaglebone:~$ candump -cae can2,0:0,#FFFFFFFF
  can2  001   [4]  00 01 02 03               '....'


  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
  can2  001   [4]  00 01 02 03               '....'
^Cdebian@beaglebone:~$ 

@pdp7
Copy link
Author

pdp7 commented Nov 10, 2019

The frequency was getting set to 8MHz despite the device tree overlay trying to set it to 16MHz. This change hard codes 16MHz and the driver does correctly receive SWCAN frames from the TX M2 processor board:

diff --git a/drivers/net/can/spi/mcp251x.c b/drivers/net/can/spi/mcp251x.c
index d8c448beab24..ee622ea33954 100644
--- a/drivers/net/can/spi/mcp251x.c
+++ b/drivers/net/can/spi/mcp251x.c
@@ -604,6 +604,8 @@ static int mcp251x_do_set_bittiming(struct net_device *net)
                          (bt->prop_seg - 1));
        mcp251x_write_bits(spi, CNF3, CNF3_PHSEG2_MASK,
                           (bt->phase_seg2 - 1));
+
+       pr_err("CNF: 0x%02x 0x%02x 0x%02x\n", mcp251x_read_reg(spi, CNF1), mcp251x_read_reg(spi, CNF2), mcp251x_read_reg(spi, CNF3));
        dev_dbg(&spi->dev, "CNF: 0x%02x 0x%02x 0x%02x\n",
                mcp251x_read_reg(spi, CNF1),
                mcp251x_read_reg(spi, CNF2),
@@ -615,6 +617,7 @@ static int mcp251x_do_set_bittiming(struct net_device *net)
 static int mcp251x_setup(struct net_device *net, struct mcp251x_priv *priv,
                         struct spi_device *spi)
 {
+       pr_err("mcp251x_setup(): mcp251x_do_set_bittiming(net)\n");
        mcp251x_do_set_bittiming(net);
 
        mcp251x_write_reg(spi, RXBCTRL(0),
@@ -1040,15 +1043,20 @@ static int mcp251x_can_probe(struct spi_device *spi)
        struct mcp251x_priv *priv;
        struct clk *clk;
        int freq, ret;
+       pr_err("mcp251x_can_probe: enter\n");
 
        clk = devm_clk_get(&spi->dev, NULL);
        if (IS_ERR(clk)) {
-               if (pdata)
+               if (pdata) {
+                       pr_err("mcp251x_can_probe: freq=pdata->oscillator_frequency=%d", pdata->oscillator_frequency);
                        freq = pdata->oscillator_frequency;
-               else
+               } else {
                        return PTR_ERR(clk);
+               }
        } else {
-               freq = clk_get_rate(clk);
+               pr_err("mcp251x_can_probe: clk_get_rate(clk)=%d", clk_get_rate(clk));
+               freq = 16000000; //clk_get_rate(clk);
+               pr_err("mcp251x_can_probe: OVERRIDE freq=clk_get_rate(clk)=%d", freq);
        }
 
        /* Sanity check */

@pdp7
Copy link
Author

pdp7 commented Nov 10, 2019

Wolfgang Grandegger wg@grandegger.com (maintainer:CAN NETWORK DRIVERS)
Marc Kleine-Budde mkl@pengutronix.de (maintainer:CAN NETWORK DRIVERS,commit_signer:16/19=84%,authored:8/19=42%,added_lines:38/107=36%,removed_lines:94/180=52%)
"David S. Miller" davem@davemloft.net (odd fixer:NETWORKING DRIVERS,commit_signer:1/19=5%)
Liam Girdwood lgirdwood@gmail.com (supporter:VOLTAGE AND CURRENT REGULATOR FRAMEWORK)
Mark Brown broonie@kernel.org (supporter:VOLTAGE AND CURRENT REGULATOR FRAMEWORK)
Sean Nyekjaer sean@geanix.com (commit_signer:7/19=37%,added_lines:16/107=15%,removed_lines:9/180=5%)
Andy Shevchenko andriy.shevchenko@linux.intel.com (commit_signer:3/19=16%,authored:3/19=16%,added_lines:19/107=18%,removed_lines:29/180=16%)
"Gustavo A. R. Silva" gustavo@embeddedor.com (commit_signer:2/19=11%,authored:2/19=11%)
Thomas Gleixner tglx@linutronix.de (authored:1/19=5%,removed_lines:15/180=8%)
Weitao Hou houweitaoo@gmail.com (authored:1/19=5%,added_lines:22/107=21%,removed_lines:27/180=15%)
linux-can@vger.kernel.org (open list:CAN NETWORK DRIVERS)
netdev@vger.kernel.org (open list:NETWORKING DRIVERS)
linux-kernel@vger.kernel.org (open list)
pdp7@x1:~/linux$

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment