FlexCAN_T4 - FlexCAN for Teensy 4

Not using mailboxes, am I ?
I'm just sniffing the bus and catching whatever I can see with this code. I did use mailboxes in my previous code but didn't feel knowledgeable enough working with them.

I need some fundamental learning in how this works, you have any recommendations on self studies for dummies, I did read your readme txt but to complicated for me to grasp ;)
 
Mailboxes are there even though you use FIFO or not, depends how advanced the configuration is set by the user. FIFO technically can't tell you how many are in queue (1-6), only yes or no, typically same response from a read(msg) return. You can only count mailboxes but it will be a waste of performance doing that all the time
 
Hello,
i have an issue with remote frames.

Ilm sending to my CAN bus REMOTE FRAME like this:

rtr_saleae.jpg

Output from Teensy serial is like this:

T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 39291 ID: 111 IDHIT: 0 Buffer: 32 32 32 32
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 48703 ID: 111 IDHIT: 0 Buffer: 36 36 36 36
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 14637 ID: 111 IDHIT: 0 Buffer: 38 38 38 38
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 39113 ID: 111 IDHIT: 0 Buffer: 3A 3A 3A 3A
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 58097 ID: 111 IDHIT: 0 Buffer: 3C 3C 3C 3C
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 23018 ID: 111 IDHIT: 0 Buffer: 3D 3D 3D 3D
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 28493 ID: 111 IDHIT: 0 Buffer: 3F 3F 3F 3F
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 57963 ID: 111 IDHIT: 0 Buffer: 41 41 41 41
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 5900 ID: 111 IDHIT: 0 Buffer: 42 42 42 42
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 52489 ID: 111 IDHIT: 0 Buffer: 55 55 55 55
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 17426 ID: 111 IDHIT: 0 Buffer: 57 57 57 57
T4: MB 1 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 27397 ID: 111 IDHIT: 0 Buffer: 59 59 59 59

It's looks like the library doesn't recognize correctly RTR byte. When the RTR byte is set in CAN frame then the buffer length should be set to 0.

Another CAN sniffer connected to my bus recognize Remote Frame correctly.
 
Sending RTR frames is on my todo list. Receptions should be fine though. I am currently working on the legacy DMA FIFO (only available on CAN3) and will circle back to RTR afterwards. Just to confirm, it's transmit only the issue correct? RX should be fine.
 
I'm sending remote frame from another device, Teensy just receive messages. I don't try to send remote frame from Teensy yet.
 
DMA support is now added as well as remote frame transmit support. Reception of remote frames works fine as is from what I see, they goto your callback where you handle the data needed to send the frame reply back

Ive tested teensy 4 to teensy 4, the data on remote frames by hardware doesnt use data bytes, but the length does work. Changing the length to 0 and sending a frame now shows correctly accross teensy.

Sender:
Code:
  static uint32_t t2 = millis();
  if ( millis() - t2 > 900 ) {
    t2 = millis();
    static uint8_t id = 1;
    CAN_message_t msg;
    id++;
    if ( id > 10 ) id = 1;
    msg.id = id;
    msg.len = 0;
    msg.flags.remote = 1;
    msg.buf[0] = 1;
    msg.buf[1] = 2;
    msg.buf[2] = 3;
    msg.buf[3] = 4;
    msg.buf[4] = 5;
    msg.buf[5] = 6;
    msg.buf[6] = 7;
    msg.buf[7] = 8;
    Can0.write(msg);
  }

Receiver:
Code:
MB 99  LEN: 0 EXT: 0 TS: 23303 ID: 1 IDHIT: 0 REMOTE: 1 Buffer:
 
I can confirm that sending RTR is working correctly.

But still can't receive RTR correctly from Teensy as a receiver:

Here is my example code:

Code:
#include <FlexCAN_T4.h>

FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> Can1;

void setup() {
  Serial.begin(115200);

  Can1.begin();
  Can1.setBaudRate(500000); 

  Can1.setMB(MB10,RX,STD);

  Can1.setMBFilter(REJECT_ALL);
  Can1.setMBFilter(MB10, 0x111);

  Can1.enhanceFilter(MB10);
  
  Can1.enableMBInterrupts();
  Can1.onReceive(MB10, canSniffer);

  Can1.mailboxStatus();
}

void loop() {
  Can1.events();

  static uint32_t t = millis();
  if ( millis() - t > 100 ) {
    t = millis();
    static uint8_t id = 1;
    CAN_message_t msg;
    id++;
    if ( id > 10 ) id = 1;
    msg.id = id;
    msg.len = 0;
    msg.flags.remote = 1;
    msg.buf[0] = 1;
    msg.buf[1] = 2;
    msg.buf[2] = 3;
    msg.buf[3] = 4;
    msg.buf[4] = 5;
    msg.buf[5] = 6;
    msg.buf[6] = 7;
    msg.buf[7] = 8;
    Can1.write(msg);
  }

}

void canSniffer(const CAN_message_t &msg) { // global callback
  Serial.print("T4: "); 
  Serial.print("MB ");
  Serial.print(msg.mb); 
  Serial.print(" OVERRUN: "); 
  Serial.print(msg.flags.overrun); 
  Serial.print(" BUS "); 
  Serial.print(msg.bus); 
  Serial.print(" LEN: "); 
  Serial.print(msg.len); 
  Serial.print(" EXT: "); 
  Serial.print(msg.flags.extended); 
  Serial.print(" REMOTE: "); 
  Serial.print(msg.flags.remote); 
  Serial.print(" TS: "); 
  Serial.print(msg.timestamp); 
  Serial.print(" ID: "); 
  Serial.print(msg.id, HEX); 
  Serial.print(" IDHIT: "); 
  Serial.print(msg.idhit); 
  Serial.print(" Buffer: "); 
  for ( uint8_t i = 0; i < msg.len; i++ ) { 
    Serial.print(msg.buf[i], HEX); 
    Serial.print(" "); 
  } 
  Serial.println();
}


Output from serial:
Code:
FIFO Disabled
	Mailboxes:
		MB0 code: RX_EMPTY	(Standard Frame)
		MB1 code: RX_EMPTY	(Standard Frame)
		MB2 code: RX_EMPTY	(Standard Frame)
		MB3 code: RX_EMPTY	(Standard Frame)
		MB4 code: RX_EMPTY	(Extended Frame)
		MB5 code: RX_EMPTY	(Extended Frame)
		MB6 code: RX_EMPTY	(Extended Frame)
		MB7 code: RX_EMPTY	(Extended Frame)
		MB8 code: TX_INACTIVE
		MB9 code: TX_INACTIVE
		MB10 code: RX_EMPTY	(Standard Frame)
		MB11 code: TX_INACTIVE
		MB12 code: TX_INACTIVE
		MB13 code: TX_INACTIVE
		MB14 code: TX_INACTIVE
		MB15 code: TX_INACTIVE
T4: MB 10 OVERRUN: 0 BUS 1 LEN: 8 EXT: 0 REMOTE: 0 TS: 30331 ID: 111 IDHIT: 0 Buffer: 93 22 C8 4C 93 EE F1 B0        // DLC: 8
T4: MB 10 OVERRUN: 0 BUS 1 LEN: 8 EXT: 0 REMOTE: 0 TS: 56917 ID: 111 IDHIT: 0 Buffer: 93 22 C8 4C 93 EE F1 B0        // DLC: 8
T4: MB 10 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 33384 ID: 111 IDHIT: 0 Buffer: 93 22 C8 4C                          // DLC: 4
T4: MB 10 OVERRUN: 0 BUS 1 LEN: 4 EXT: 0 REMOTE: 0 TS: 21609 ID: 111 IDHIT: 0 Buffer: 93 22 C8 4C                          // DLC: 4

Buffer value is random on every Teensy reboot.
 
Yes i know, the buffer data of RTR requests are unused, even if the buffer is populated (they are filled) the hardware doesnt actually transfer them, the length is to be used when the RTR response is to be given, the data bytes are never seen on reception from a RTR request

The Remote Frame is just like the Data Frame, with two important differences:

it is explicitly marked as a Remote Frame (the RTR bit in the Arbitration Field is recessive), and
there is no Data Field.

The data field is irrelevant in a remote request frame, therefore it is unused. You are simply reading stale data from mailbox area that isn't written by the SMB during arbitration, and technically, the remote frame data shouldnt need to be seen or used, but in reception it prints it out like any other frame, so that leads to confusion on how remote frames work, so if you see an RTR of 4 bytes, usually you'd respond with the same ID frame, and 4 bytes DLC data, as a normal, non-remote CAN frame

I could clear the buffer area of a remote request frames (0), but I feel an additional conditional statement would be unnecessary overhead for frame captures
 
Last edited:
Hi tonton81,

I have a (possibly dumb) question. Can we send a 29-bit extended id message over CAN 2.0? I'm inclined to say no myself, and I have some data from a test we did.

Our scenario is we have a BMS that is hard-coded to receive CAN in 29-bit (it's the only system on the car that requires this).

In the test we took the designated extended CAN 2.0 ID of "1839F380" and set it as the message ID on CAN 2.0.

Observing this message on the bus showed the id truncated to "380." The reading the value at the BMS also confirms this truncation.

I believe our only recourse is to move the bus to CAN.FD--which we have avoided so far because of FMEA (Failure Mode Effects & Analysis) showed that the pins on under-side could be a potential failure point.

Though we could use a pogo-pin on the PCB to avoid this issue.

Anyways, to restate the question: are we overlooking the proper way to send extended ids via CAN 2.0?

Thank you,
Dearborn Electric Racing

Code:
#include "FlexCAN_T4.h"
FlexCAN_T4 <CAN2, RX_SIZE_256, TX_SIZE_16> Can0;

struct message {
  CAN_message_t msg;
} b;

void canSniff(const CAN_message_t &msg) {
  Serial.print("MB "); Serial.print(msg.mb);
  Serial.print("  OVERRUN: "); Serial.print(msg.flags.overrun);
  Serial.print("  LEN: "); Serial.print(msg.len);
  Serial.print(" EXT: "); Serial.print(msg.flags.extended);
  Serial.print(" TS: "); Serial.print(msg.timestamp);
  Serial.print(" ID: "); Serial.print(msg.id, HEX);
  Serial.print(" Buffer: ");
  for ( uint8_t i = 0; i < msg.len; i++ ) {
    Serial.print(msg.buf[i], HEX); Serial.print(" ");
  } Serial.println();
}


void setup(void) {
  Serial.begin(115200); delay(400);
  pinMode(6, OUTPUT); digitalWrite(6, LOW); // enable transceiver
  Can0.begin();
  Can0.setClock(CLK_60MHz);
  Can0.setBaudRate(500000);
  Can0.setMaxMB(16); // up to 64 max for T4, not important in FIFO mode, unless you want to use additional mailboxes with FIFO
  Can0.enableFIFO();
  Can0.enableFIFOInterrupt();
  Can0.onReceive(canSniff);
  Can0.mailboxStatus();
}

void loop() {
  Can0.events();

  static uint32_t timeout = millis();
  if ( millis() - timeout > 2 ) { // send random frame every 2ms
    b.msg.id = 0x1839F380;
    
    b.msg.buf[0] = 0;
    b.msg.buf[1] = 20; // fake temp data
    b.msg.buf[2] = 50; // fake temp data
    b.msg.buf[3] = 25; // fake temp data
    b.msg.buf[4] = 72; // fake temp data
    b.msg.buf[5] = 0;
    b.msg.buf[6] = 0;
    b.msg.buf[7] = 0;
    
    Can0.write(b.msg);
    timeout = millis();
    canSniff(b.msg);
  }
}
 
Please use msg.flags.extended = 1;
This flag notified the transmit mailbox that it's an extended frame, otherwise it will be truncated as a standard ID by default. I tested just now to confirm extended frame is working correctly :)
 
Hi,

I seem to have come across an issue with identifying the mailbox a message is recieved on.
It works fine with polling mailboxes (FD.read(msg)) but when using ISRs it apparently fails to identify which mailbox the message came from and defaults to 0.

I have a bigger section of code that I found the issue in, but I created this from scratch using code provided in the "beta_sample.ino" and the "readme.md" of https://github.com/tonton81/FlexCAN_T4
Code:
#include <FlexCAN_T4.h>

FlexCAN_T4FD<CAN3, RX_SIZE_256, TX_SIZE_16> FD;

bool useInterrupts = true;

void setup(void) {
  Serial.begin(115200); delay(500);
  
  FD.begin();
  CANFD_timings_t config;
  config.clock = CLK_60MHz;
  config.baudrate = 500000;
  config.baudrateFD = 1000000;
  config.propdelay = 190;
  config.bus_length = 1;
  config.sample = 70;
  FD.setRegions(64);
  FD.setBaudRate(config);
  
  if (useInterrupts) {  // set interrupts if bool enabled
    FD.enableMBInterrupts();
  }
  
  FD.onReceive(canSniff);  // set callback
  
  FD.mailboxStatus();
}

void loop() {
  if (Serial.available()) {
    Serial.read();
    Serial.read();
    useInterrupts = !useInterrupts;
    if (useInterrupts) {  // if switching to ISR ON
      FD.enableMBInterrupts();
    }
    else{  // if switching ISR OFF
      FD.enableMBInterrupts(0);
    }
  }

  if (useInterrupts) {  // run ISR check
    FD.events();
  }
  else {  // poll random mailbox
    CANFD_message_t msg;
    if ( FD.read(msg) ) {
      printMsg(msg);
    }
  }
  delay(50);
}

void canSniff(const CANFD_message_t &msg) {
  printMsg(msg);
}

void printMsg(CANFD_message_t msg){
  Serial.print("MB: "); Serial.print(msg.mb);
  Serial.print("  ID: 0x"); Serial.print(msg.id, HEX );
  Serial.print("  EXT: "); Serial.print(msg.flags.extended );
  Serial.print("  LEN: "); Serial.print(msg.len);
  Serial.print(" DATA: ");
  for ( uint8_t i = 0; i < 8; i++ ) {
    Serial.print(msg.buf[i]); Serial.print(" ");
  }
  Serial.print("  TS: "); Serial.println(msg.timestamp);
}

I haven't been able to work out if the ISR is only reading from MB0 and is therefore reporting msg.mb correctly or if it's as I previously suggested, but I'm not experienced with creating libraries so haven't been able to answer my own questions.

Hope this is sufficient for you to investigate the problem (even if the error is entirely my own!)
Dom
 
It will read from all mailboxes, but if you dont write fast enough only MB0 will be populated, in terms of efficientcy, unless your blasting frames they wont roll over to the next mailbox unless the first mailbox isnt read as fast in time. The ISR is VERY fast, and only there is your message queued, it empties the MB0 as fast as possible into the queue where you can read it after using events() and prepares the mailbox fot next reception. While that happens, the SMB is holding (if any) the next message, when the ISR exits the SMB drops it into the same MB0 since its again available.

Delays work in polling because your taking your time reading mailboxes so they overflow to next ones.

The behaviour is expected :)
 
Python Library to access CAN BUS via USB with Teensy40

I created a Python package which allows to send and receive CAN Frames. It also uses tonton81's library and I wanted to share it with you. Of course there is still room for improvements but it can already be really usefull in its current state.

I already did some penetration-test by sending more than 1.000.000 Frames from one device to another and comparing the received and sent data. It works quiet well.

GitHub link: https://github.com/code2love/Can4Python

 
Last edited:
Looks interesting. Does the install run on a PC,Mac or Linux ? What about when running the example ?
 
Hi skpang,

Currently it is only available for Windows, but it should not be hard to create an Linux branch (only windows dependency is hid.c).

The example in the screenshoot shows the python cli while two CanInterfaces are connected to the PC. I open both as CAN 2.0 Devices and then I send a CAN Message from Device 0 to Device 1.
 
I can't see any screenshoots.

Is there anyway to get a pre-build version ? I don't have Visual studio or Visual C++ installed. In fact, I'm using a Mac.
 
ISR MB issues

It will read from all mailboxes, but if you dont write fast enough only MB0 will be populated, in terms of efficientcy, unless your blasting frames they wont roll over to the next mailbox unless the first mailbox isnt read as fast in time. The ISR is VERY fast, and only there is your message queued, it empties the MB0 as fast as possible into the queue where you can read it after using events() and prepares the mailbox fot next reception. While that happens, the SMB is holding (if any) the next message, when the ISR exits the SMB drops it into the same MB0 since its again available.

Delays work in polling because your taking your time reading mailboxes so they overflow to next ones.

The behaviour is expected

Okay yes, that makes sense :)
However im dropping frames and no other mailboxes are being used when using the ISR.

To test this I'm using a ramp on CAN ID 1 with a time period of 1s and values from 255->1. There are also 2 other CAN frames that I'm currently ignoring, but using all 3 at 1000 fr/s to produce a 75% busload (worst case scenario) with the delay spikes (to simulate my data saving method).
However all the messages are coming out of the same mailbox with dropped frames for the time during the delay.
I switched the mailbox configuration to MB0 & MB1 as TX so MB2 is the first RX mb (just to make sure that this wasn't the problem)
This is the output I got:
Code:
mb: 2	id=1 val: 211
mb: 2
mb: 2
mb: 2
mb: 2
mb: 2	id=1 val: 210
mb: 2
mb: 2	id=1 val: 210
mb: 2
mb: 2
mb: 2
SPIKE == 500ms delay
mb: 2
mb: 2
mb: 2	id=1 val: 104
mb: 2
mb: 2	id=1 val: 104
mb: 2
mb: 2	id=1 val: 104
mb: 2
mb: 2
mb: 2
mb: 2
mb: 2	id=1 val: 103

I appreciate that 500ms is a very long delay, it will be more like 20ms on a really slow save, but I was expecting something like:
Code:
SPIKE == 500ms delay
mb: 2
mb: 3
mb: 4
mb: 5
mb: 6
etc
Any help would be fantastic, I just need to not drop any frames while I save the data!
 
Do you have a sketch i can load to run your example? Or one how i can see is how it is setup?

This is a cutdown version using only the FlexCAN_T4 library
Code:
#include <FlexCAN_T4.h>

FlexCAN_T4<CAN2, RX_SIZE_256, TX_SIZE_16> Can2;

void saveData() {
  // save data - delay: max ~20ms, avg ~20us
  // 500ms max spike to try to force mailbox filling
  long a = random(0, 1000);
  if (a > 975) {  // 2.5% chance of delay spike
    Serial.println("SPIKE == 500ms delay");
    delay(500);
  }
  else {
    delayMicroseconds(20);
  }
}

void setup() {
  // put your setup code here, to run once:
  Serial.begin(115200);
  while (!Serial) {
  }
  Serial.println("Press any key to start");
  while (!Serial.available()) {
    Serial.read();  // remove endl
  }
  Serial.println("Starting");

  Can2.begin();
  Can2.setMB(MB0, TX);
  Can2.setMB(MB1, TX);
  Can2.setMB(MB2, RX, STD);
  Can2.setMB(MB3, RX, STD);
  Can2.setMB(MB4, RX, STD);
  Can2.setMB(MB5, RX, STD);
  Can2.setMB(MB6, RX, STD);
  Can2.setMB(MB7, RX, STD);
  Can2.setMB(MB8, RX, STD);
  Can2.setMB(MB9, RX, EXT);
  Can2.setMB(MB10, RX, EXT);
  Can2.setMB(MB11, RX, EXT);
  Can2.setMB(MB12, RX, EXT);
  Can2.setMB(MB13, RX, EXT);
  Can2.setMB(MB14, RX, EXT);
  Can2.setMB(MB15, RX, EXT);
  Can2.setClock(CLK_60MHz);
  Can2.setBaudRate(500000);
  Can2.enableMBInterrupts();
  Can2.onReceive(can2Callback);
  Can2.mailboxStatus();
}

void loop() {
  Can2.events();
  saveData();
}

void can2Callback(const CAN_message_t &msg) {
  Serial.print("mb: "); Serial.print(msg.mb);
  if(msg.id==1){
    Serial.print("\tid=1 val: "); Serial.print(msg.buf[0]);
  }
  Serial.println();
  // function to store data for saving
}

Im running the CAN network off of a Vector VN7640 at 75% busload with 3 messages each with one generated signal - using a ramp as it's very easy to see when you're dropping a lot of frames. I imagine any CAN network will work as I get the same results when varying load and messages sent.
 
Thank you, after an observation with your code I caught a bug when configuring the TX mailboxes, the imask bit setting crashed the controller because it wasn't handled in ISR, so ISR never exited, works fine now This only affected setting transmit mailboxes using setMB(), patch was updated on github, still trying to figure out what i should see as output with your code, so far I see this:

Code:
SPIKE == 500ms delay

mb: 2

SPIKE == 500ms delay

mb: 2

SPIKE == 500ms delay

mb: 2	id=1 val: 1

SPIKE == 500ms delay

SPIKE == 500ms delay

mb: 2

SPIKE == 500ms delay

mb: 2

SPIKE == 500ms delay

Other sketch i am sending ids 1->20 looping

if i change msg.mb to msg.id I do see all frames here 1->20 in order, at 10ms sends

if your asking why its only from MB2 and delays wont work, its because the ISR drops it into the queue and frees the mailbox for the next SMB transfer, the loop delay does not block that behaviour. The overflow, if fast enough will roll to the next mailbox. What you are seeing is your queues probably filling up faster than you read them in the events(), and if the ISR is filling the queue while you are delaying the events(), then your queues would overflow and then you'll miss frames. events() can be ran inside teensyThreads or IntervalTimer in case your using blocking code.

Theres, however, a direct user handling method tailored for external libraries, if you prefer to handle the data immediately without reading it from a queue. Put this in your sketch:

Code:
void ext_output1(const CAN_message_t &msg) { 
}

It's a background direct callback, nothing to add in setup(). All frames are sent there directly, even if they are queued.
 
Last edited:
Ahh I'm glad you found that

if your asking why its only from MB2 and delays wont work, its because the ISR drops it into the queue and frees the mailbox for the next SMB transfer, the loop delay does not block that behaviour. The overflow, if fast enough will roll to the next mailbox. What you are seeing is your queues probably filling up faster than you read them in the events(), and if the ISR is filling the queue while you are delaying the events(), then your queues would overflow and then you'll miss frames. events() can be ran inside teensyThreads or IntervalTimer in case your using blocking code.

Right, so with ISRs as I understand them, immediately interrupt the running code to execute the callback then continue with the previously running code. Therefore a delay() would just be suspended while the ISR is executed and the mailbox is cleared as the messages come through meaning they all end up passing through the same mailbox.

But I was under the impression with the can.events(), that the 'interrupt' is essentially just a flag to say a message has arrived, and the ISR doesn't begin until can.events() is called, in which case a delay() should cause more and more mailboxes to fill up as they have to wait for the duration of delay() until the ISR can empty each mailbox with a flag set.

Is this the correct way of thinking about it, or have I missed something?



I'm trying to log 3 CAN networks at once (a lot of data!) so I have buffers set up to store several frames until I have enough to do a chunk of writing to SD card. The problem I've encountered is that this SD write usually takes 20-30us but can take up to 30ms (~400 frames at max busload). To solve this I'm trying to implement this all with TeensyThreads.h but will still need a bit of a buffer for during a time slice of SD writing. This is where I'd hoped the mailboxes would start to fill up and I could come and empty them as soon as I'd finished or paused in writing to the SD card (hopepfully before the mailboxes overflowed!)

Hopefully that makes it clearer, I'm still not sure if that's going to work so any recommendations would be welcome :)



Theres, however, a direct user handling method tailored for external libraries, if you prefer to handle the data immediately without reading it from a queue. Put this in your sketch:

Code:
void ext_output1(const CAN_message_t &msg) { 
}
It's a background direct callback, nothing to add in setup(). All frames are sent there directly, even if they are queued.

I'm not entirely sure what this means or does?
 
Not sure if this is the right place but perhaps someone can advise, but I am using the FlexCan_T4 library for this project on of my T4.0's

CAN over OBD2 (UDS) - is there a minimum timing that needs to exist between each transmit onto the bus? and how soon can I read the frame?
Currently writing frames in the main loop and reading if more than 60ms have passed - should I change anything?
 
Back
Top