Forum Rule: Always post complete source code & details to reproduce any issue!
Page 5 of 6 FirstFirst ... 3 4 5 6 LastLast
Results 101 to 125 of 144

Thread: FlexCAN_T4 - FlexCAN for Teensy 4

  1. #101
    Junior Member
    Join Date
    Dec 2019
    Posts
    10
    Many thanks, that did it! I did test similar code earlier but never figured it out all the way.
    Your advise on how to filter into mailboxes will come to use, appreciate it!

    Attached is my code for other to use.

    Code:
    #include <FlexCAN_T4.h>
    FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> Can0;
    
    CAN_message_t msg, rxmsg;
    
    
    
    
    void setup(void) {
    
      
      Serial.begin(115200); 
      delay(500);
      Can0.begin();
      Can0.setBaudRate(100000);
      
      Can0.enableMBInterrupts();
    
    }
    
    
    
    
    
    void canSniff(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();
    }
    
    
    
    
    
    void loop() {
    
      while(Can0.events() > 0){
        Can0.onReceive(canSniff);
      }
      
    
    }

  2. #102
    Senior Member
    Join Date
    Dec 2016
    Location
    Montreal, Canada
    Posts
    3,193
    Looks good but only put Can0.events() in the loop, onReceive needs only be set once in setup, just move that to setup and remove the while loop

    The return value is used by TeensyCAN, 12 bits contain Rx buffer queue size and 12bits contain Tx buffer queue size, under normal use you probably dont need to check it, but you could if you wanted do the following:

    Check the last 12 bits in a while loop to clear out the sequential transmit queue when needed or the next 12 bits to check how many of your messages are in queue to process all at same time.

    In the case of TeensyCAN, it monitors the events() return until it's transmissions are complete before going forward
    Last edited by tonton81; 12-23-2019 at 11:10 AM.

  3. #103
    Merry Christmas Tonton81,

    I'm wondering if you could recommend a transceiver for a Teensy 4.0 utilizing CAN2.0? We are currently using an MCP2588FD but are failing to transmit consistently.

    We do have a square-wave signal coming out of the TX wire of the T4, and by shear luck the CAN software we are using (Warwick X-Analyser with Vector VN1610) was able to read 10 frames and then failed again.

    I've included some pictures and the very basic code sample below (which is basically your example code).

    CAN Test Network
    Click image for larger version. 

Name:	test-can-hardware.jpg 
Views:	9 
Size:	131.2 KB 
ID:	18503

    CAN TX Oscilloscope Reading
    Click image for larger version. 

Name:	can-tx-osc.jpg 
Views:	9 
Size:	262.2 KB 
ID:	18504

    CAN X-Analyser w. VN1610
    Click image for larger version. 

Name:	test-can.jpg 
Views:	11 
Size:	91.6 KB 
ID:	18502

    Code:
    #include "FlexCAN_T4.h"
    FlexCAN_T4<CAN2, RX_SIZE_256, TX_SIZE_16> Can0;
    
    void setup(void) {
      Serial.begin(115200); delay(400);
      pinMode(6, OUTPUT); digitalWrite(6, LOW); // enable tranceiver
      Can0.begin();
      Can0.setBaudRate(1000000);
      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 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 loop() {
      Can0.events();
    
      static uint32_t timeout = millis();
      if ( millis() - timeout > 20 ) { // send random frame every 20ms
        CAN_message_t msg;
        msg.id = random(0x1,0x7FE);
        for ( uint8_t i = 0; i < 8; i++ ) msg.buf[i] = i + 1;
        Can0.write(msg);
        timeout = millis();
        
        canSniff(msg);
      }
    
    }
    Datasheet for the transceiver: https://ww1.microchip.com/downloads/.../20005533A.pdf

    Kind regards,
    Dearborn Electric Racing (University of Michigan-Dearborn)

  4. #104
    Senior Member
    Join Date
    Dec 2016
    Location
    Montreal, Canada
    Posts
    3,193
    Try using Can0.setClock(CLK_60MHz) then do setBaudRate after that, check if you have timing issues with that after. I am using skpang's breakout board in my car with a retail Teensy 4, it has triple CAN transceivers, and connected to 2 CAN busses of the car. You can check the datasheet on the breakout board to see what transceiver he uses

    http://skpang.co.uk/catalog/teensy-4...40-p-1575.html

    This is the setup i did, single loomed bcan and fcan with 12v and gnd sourced at BCM and OBD port
    Click image for larger version. 

Name:	JPEG_20191213_142925.jpg 
Views:	18 
Size:	73.3 KB 
ID:	18505

    The PJRC breakout board transceiver is also recommended, I suggested a different clock because on T3 it was 16MHz and T4 SDK was at 20MHz so they use different divisors, I found that 60MHz works pretty well for me, one bus is 125kbps and the other is 500kbps

    Merry Xmas
    Last edited by tonton81; 12-24-2019 at 07:36 PM.

  5. #105
    Quote Originally Posted by DearbornElectricRacing View Post
    Merry Christmas Tonton81,

    Datasheet for the transceiver: https://ww1.microchip.com/downloads/.../20005533A.pdf

    Kind regards,
    Dearborn Electric Racing (University of Michigan-Dearborn)
    Don't think you have wired the transceiver up correctly. There is a separate supply for Vio (pin 5), you need to connect to this the 3.3v supply but it looks like you have connected to the 5v supply. So the Teensy is getting 5v logic. This could of damaged the Teensy as the IO is not 5v tolerant.

    Connect pin 5 to 3.3v instead and try again. Also add 100nF capacitor close to pin 5 and another 100nF capacitor close to 3pin of the transceiver.

  6. #106
    Junior Member
    Join Date
    Dec 2019
    Posts
    10
    Adjusted the code, ignore the while loop, it was just a part of me testing something.
    We should upload this as an example on Git for others


    Code:
    #include <FlexCAN_T4.h>
    FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> Can0;
    
    CAN_message_t msg, rxmsg;
    
    
    
    
    void setup(void) {
    
      
      Serial.begin(115200); 
      delay(500);
      Can0.begin();
      Can0.setBaudRate(100000);
      
      Can0.enableMBInterrupts();
      Can0.onReceive(canSniff);
    
    }
    
    
    
    
    
    void canSniff(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();
    }
    
    
    
    
    
    void loop() {
    
    Can0.events();
    
      
    
    }

  7. #107
    Senior Member
    Join Date
    Dec 2016
    Location
    Montreal, Canada
    Posts
    3,193
    Yup that looks good, will add it today or tomorrow as a 2.0 example, the FD beta example needs to be updated as well.

  8. #108
    Junior Member
    Join Date
    Dec 2019
    Posts
    10
    Trying to build a gateway, hopefully you on here could give me advise on how to improve the foundation of the code attached.
    Not asking for you to solve it all for me =) .

    Intention of the gateway is to alter specific messages in between 2 modules on a can bus, I need to maintain the sequence/order of communication.

    Merry Christmas

    Code:
    #include <FlexCAN_T4.h>
    FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> Can0;
    FlexCAN_T4<CAN2, RX_SIZE_256, TX_SIZE_16> Can1;
    
    CAN_message_t msg, rxmsg;
    
    
    
    
    
    void setup(void) {
      
      Serial.begin(115200); 
      delay(500);
    
      Can0.begin();
      Can0.setBaudRate(100000);
      Can1.begin();
      Can1.setBaudRate(100000);
    
      Can0.enableMBInterrupts();
      Can1.enableMBInterrupts();
      Can0.onReceive(can0Sniff);
      Can1.onReceive(can1Sniff);
    
    }
    
    
    
    
    
    void can0Sniff(const CAN_message_t &msg) { // global callback
    
      Serial.print(" Buffer: "); 
        for ( uint8_t i = 0; i < msg.len; i++ ) { 
        Serial.print(msg.buf[i], HEX); 
        Serial.print(" "); 
        } 
      Serial.println();
      Can1.write(msg);
    }
    
    void can1Sniff(const CAN_message_t &msg) { // global callback
    
      Serial.print(" Buffer: "); 
        for ( uint8_t i = 0; i < msg.len; i++ ) { 
        Serial.print(msg.buf[i], HEX); 
        Serial.print(" "); 
        } 
      Serial.println();
      Can0.write(msg);
    }
    
    
    
    
    
    void loop() {  
    
      Can0.events();
      Can1.events();
        
     
    
    }

  9. #109
    Senior Member
    Join Date
    Dec 2016
    Location
    Montreal, Canada
    Posts
    3,193
    You can send both onReceive to same callback if you wish to handle it in one function, each frame has a msg.bus (1,2,3 is returned for CAN1,CAN2, amd CAN3.

    To send frames ordered sequentially, you can set msg.seq = 1 before transmitting.

    The callback frame is read only so if you wanted to modify it you can copy it, modify copy, then transmit on other bus:

    If ( msg.bus == 1 ) { // from CAN1
    CAN_message_t theCopy = msg;
    msg.seq = 1;
    // modify if necessary data fields
    Can1.write(theCopy); // write to CAN2


    Separate callbacks work too if you dont want to rely on msg.bus field

  10. #110
    Junior Member
    Join Date
    Dec 2019
    Posts
    10
    Some further testing and feedback on the former sketch modified with your suggestion.

    Following code added to void canSniff(){}, it works but need to uncomment "msg.seq = 1" or I get the following error when compiling:
    Teensy_Gateway_Callback:70: error: assignment of member 'CAN_message_t::seq' in read-only object

    It will compile if I drop it in the loop but then the sketch doesn't work

    Code:
    if ( msg.bus == 1 ) { 
    CAN_message_t theCopy = msg;
    //msg.seq = 1;
    // modify if necessary data fields
    Can1.write(theCopy); 
    }
    
    if ( msg.bus == 2 ) { 
    CAN_message_t theCopy = msg;
    //msg.seq = 1;
    // modify if necessary data fields
    Can0.write(theCopy); 
    }

    I have a issue with, hopefully you cam assist me in how to do it. Data on the bus is there as I can see it.
    if(msg.id == 0x800 && msg.buf[0] == 0xFF){do something} // won't work
    if(msg.id == 0x800){do something} // this works

  11. #111
    Quote Originally Posted by tonton81 View Post
    Try using Can0.setClock(CLK_60MHz) then do setBaudRate after that, check if you have timing issues with that after. I am using skpang's breakout board in my car with a retail Teensy 4, it has triple CAN transceivers, and connected to 2 CAN busses of the car. You can check the datasheet on the breakout board to see what transceiver he uses

    http://skpang.co.uk/catalog/teensy-4...40-p-1575.html

    This is the setup i did, single loomed bcan and fcan with 12v and gnd sourced at BCM and OBD port
    Click image for larger version. 

Name:	JPEG_20191213_142925.jpg 
Views:	18 
Size:	73.3 KB 
ID:	18505

    The PJRC breakout board transceiver is also recommended, I suggested a different clock because on T3 it was 16MHz and T4 SDK was at 20MHz so they use different divisors, I found that 60MHz works pretty well for me, one bus is 125kbps and the other is 500kbps

    Merry Xmas


    Quote Originally Posted by skpang View Post
    Don't think you have wired the transceiver up correctly. There is a separate supply for Vio (pin 5), you need to connect to this the 3.3v supply but it looks like you have connected to the 5v supply. So the Teensy is getting 5v logic. This could of damaged the Teensy as the IO is not 5v tolerant.

    Connect pin 5 to 3.3v instead and try again. Also add 100nF capacitor close to pin 5 and another 100nF capacitor close to 3pin of the transceiver.
    Thank you both! I really appreciate the quick responses. I stopped in the lab this morning to test out the recommended changes.


    CAN Test Network: Changed Pin 5 to 3.3V; added 0.1uF capacitors to pin 5s & 3, where only pin 3 receives 5V.
    Click image for larger version. 

Name:	can-test-hardware.jpg 
Views:	13 
Size:	150.3 KB 
ID:	18525

    Measuring TX Oscilloscope Reading and receiving plenty of Square Waves out (still at 5V which I expected 3.3V this time; perhaps both 5V and 3.3V need to be connected to the Teensy).
    Click image for larger version. 

Name:	test-can-osc.jpg 
Views:	7 
Size:	224.3 KB 
ID:	18527

    Code:
    #include "FlexCAN_T4.h"
    FlexCAN_T4<CAN2, RX_SIZE_256, TX_SIZE_16> Can0;
    
    void setup(void) {
      Serial.begin(115200); delay(400);
      pinMode(6, OUTPUT); digitalWrite(6, LOW); // enable transceiver
      Can0.begin();
      Can0.setClock(CLK_60MHz); // Added this per TonTon81's suggestion
      Can0.setBaudRate(1000000);
      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 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 loop() {
      Can0.events();
    
      static uint32_t timeout = millis();
      if ( millis() - timeout > 20 ) { // send random frame every 20ms
        CAN_message_t msg;
        msg.id = random(0x1,0x7FE);
        for ( uint8_t i = 0; i < 8; i++ ) msg.buf[i] = i + 1;
        Can0.write(msg);
        timeout = millis();
        
        canSniff(msg);
      }
    
    }
    Next steps will be trying out the MCP2562's over the MCP2558FD's. I'll also swap Teensy's just in case we damaged the IO's here with 5V.

    Thanks again for all of the help, and Merry Christmas!

  12. #112
    Senior Member
    Join Date
    Dec 2016
    Location
    Montreal, Canada
    Posts
    3,193
    Quote Originally Posted by EPV77 View Post
    Some further testing and feedback on the former sketch modified with your suggestion.

    Following code added to void canSniff(){}, it works but need to uncomment "msg.seq = 1" or I get the following error when compiling:
    Teensy_Gateway_Callback:70: error: assignment of member 'CAN_message_t::seq' in read-only object

    It will compile if I drop it in the loop but then the sketch doesn't work

    Code:
    if ( msg.bus == 1 ) { 
    CAN_message_t theCopy = msg;
    //msg.seq = 1;
    // modify if necessary data fields
    Can1.write(theCopy); 
    }
    
    if ( msg.bus == 2 ) { 
    CAN_message_t theCopy = msg;
    //msg.seq = 1;
    // modify if necessary data fields
    Can0.write(theCopy); 
    }

    I have a issue with, hopefully you cam assist me in how to do it. Data on the bus is there as I can see it.
    if(msg.id == 0x800 && msg.buf[0] == 0xFF){do something} // won't work
    if(msg.id == 0x800){do something} // this works
    You can't modify msg in callback because its read only, you can copy it then modify the copy

    CAN_message_t theCopy = msg; // copy it
    theCopy.seq = 1;

    The data 0xFF looks good, just make sure it's the right offset in the array(0?) and that it exists on ID 0x800

  13. #113
    Quote Originally Posted by skpang View Post
    Don't think you have wired the transceiver up correctly. There is a separate supply for Vio (pin 5), you need to connect to this the 3.3v supply but it looks like you have connected to the 5v supply. So the Teensy is getting 5v logic. This could of damaged the Teensy as the IO is not 5v tolerant.

    Connect pin 5 to 3.3v instead and try again. Also add 100nF capacitor close to pin 5 and another 100nF capacitor close to 3pin of the transceiver.
    Thanks again for you input, I'm looking over your schematic for your breakout board and I'm curious about the "D1" component of four Zener Diodes going to ground. Would you mind sharing what the purpose of this component is, and whether or not we need to group CAN-H and CAN-L similarly?

  14. #114
    A bit of progress today, we got the MCP2558FD transceivers working properly (which are the one's in PJRC's breakout board).

    Unfortunately it seems to produce only errors with no memory id's and no data.

    Any chance when you have a moment you could review our 2.0 code again to make sure we are interpreting the example correctly?

    400,00+ CAN messages read through X-Analyser via the VN1610 adapter; all errors.
    Click image for larger version. 

Name:	can-test-2.jpg 
Views:	7 
Size:	109.2 KB 
ID:	18549

    Code:
    #include "FlexCAN_T4.h"
    FlexCAN_T4 <CAN2, RX_SIZE_256, TX_SIZE_16> Can0;
    
    void setup(void) {
      Serial.begin(115200); delay(400);
      pinMode(6, OUTPUT); digitalWrite(6, LOW); // enable transceiver
      Can0.begin();
      Can0.setClock(CLK_60MHz);
      Can0.setBaudRate(1000000);
      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 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 loop() {
      Can0.events();
    
      static uint32_t timeout = millis();
      if ( millis() - timeout > 20 ) { // send random frame every 20ms
        CAN_message_t msg;
        msg.id = random(0x1,0x7FE);
        for ( uint8_t i = 0; i < 8; i++ ) msg.buf[i] = i + 1;
        Can0.write(msg);
        timeout = millis();
        
        canSniff(msg);
      }
    
    }

  15. #115
    Senior Member
    Join Date
    Dec 2016
    Location
    Montreal, Canada
    Posts
    3,193
    Do you have proper termination on the lines? Verify the transceiver is not crosswired to the CAN network as well, the code looks ok so far, and your printing to serial monitor what your sending as well (which is fine for sanity checks), double check the wiring and resistances

  16. #116
    Quote Originally Posted by DearbornElectricRacing View Post
    Thank you both! I really appreciate the quick responses. I stopped in the lab this morning to test out the recommended changes.


    CAN Test Network: Changed Pin 5 to 3.3V; added 0.1uF capacitors to pin 5s & 3, where only pin 3 receives 5V.
    Click image for larger version. 

Name:	can-test-hardware.jpg 
Views:	13 
Size:	150.3 KB 
ID:	18525
    From what I can see on the photo the wiring still doesn't look right. On the 5v rail on the breadboard there is a cap connected to it but it does not look like it is connected to the transceiver.
    Same goes on the 3.3v line. There doesn't look like a connection to the transceiver Vio pin.

    You can use the 3.3v output from the Teensy to power the transceiver.

    Also the terminator resistor. Have you got two 100R resistor connected in parallel ? If so that is not right. You need a 120R on each end of your network. That is 120R resistor on the breadboard.
    Your CAN-bus analyser should provide the other 120R. Check that.

    The diodes on the Teensy 4.0 Triple CAN Board is for ESD protection.

  17. #117
    Quote Originally Posted by skpang View Post
    From what I can see on the photo the wiring still doesn't look right. On the 5v rail on the breadboard there is a cap connected to it but it does not look like it is connected to the transceiver.
    Same goes on the 3.3v line. There doesn't look like a connection to the transceiver Vio pin.

    You can use the 3.3v output from the Teensy to power the transceiver.

    Also the terminator resistor. Have you got two 100R resistor connected in parallel ? If so that is not right. You need a 120R on each end of your network. That is 120R resistor on the breadboard.
    Your CAN-bus analyser should provide the other 120R. Check that.

    The diodes on the Teensy 4.0 Triple CAN Board is for ESD protection.
    Thank you for the advice, I should have commented with another photo of the wiring changes we made last night.

    I'll be in the university's lab again tonight after work, and I'll double check. Here's the changes we made last night photo and diagram.

    Hardware photo with the caps corrected; note all grounds are made common.
    Click image for larger version. 

Name:	can-test-hw-191227.jpg 
Views:	4 
Size:	142.2 KB 
ID:	18557

    Our current diagram of the breadboard.
    Click image for larger version. 

Name:	Test CAN 2.0 __ Teensy 4.0 via MCP2558 __ 191227.jpg 
Views:	14 
Size:	40.1 KB 
ID:	18558

    Tonight I'll pull one of the 100 ohm resistor out of the board, and add a 20 ohm resistor in series to bring it to exactly 120ohm.

    Thanks again!

  18. #118
    Quote Originally Posted by tonton81 View Post
    Do you have proper termination on the lines? Verify the transceiver is not crosswired to the CAN network as well, the code looks ok so far, and your printing to serial monitor what your sending as well (which is fine for sanity checks), double check the wiring and resistances
    Thanks, I'm going to triple check the wiring tonight.

  19. #119
    Click image for larger version. 

Name:	can-test-success.jpg 
Views:	7 
Size:	126.6 KB 
ID:	18560

    Update: Removed the caps and a single 100 ohm resistor and the analyser lit up like a Christmas tree!

    (120*100)/(220) = 54.54 ohms in the bus which is close enough to 60 ohms for business.

    Thanks again for the help everyone!

  20. #120
    Junior Member
    Join Date
    Dec 2019
    Posts
    10
    Quote Originally Posted by tonton81 View Post

    The data 0xFF looks good, just make sure it's the right offset in the array(0?) and that it exists on ID 0x800
    I think I figured out the issue, offset is correct.
    Coding problem on my side.

  21. #121
    Junior Member
    Join Date
    Dec 2019
    Posts
    10
    Using SN65HVD230 modules, had to remove the build in 120R before data could be seen by the Teensy.

  22. #122
    Junior Member
    Join Date
    Dec 2019
    Posts
    10
    Any "Can0.available(rxmsg)" function for a push set up ?

    while(Can0.available(rxmsg)){//do somethig};

  23. #123
    Senior Member
    Join Date
    Dec 2016
    Location
    Montreal, Canada
    Posts
    3,193
    What do you mean? ((Can0.events() & 0xFFF000) >> 3) will show if there are frames in queue (in interrupt mode). Is that what you meant or you mean polling mode? None exists at the moment for poll mode, aside from the mailboxStatus() giving a visual of which mailboxes contain a message. If one were to be implemented it would probably be a redundant mailbox scanner to see which contain messages, but at that point your needlessly scanning every mailbox to tally every cycle wasting resources

    Can0.available() would make sense in interrupt mode, where it actually returns the queue size. Polling mode doesn't store a queue, otherwise it wouldn't be considered polling.

    Can0.read(msg) would return bool though, 1 if a message was read and 0 if not.

  24. #124
    Junior Member
    Join Date
    Dec 2019
    Posts
    10
    My English is poor, let's try with the following code.
    While loop will show the latest received data and will continue to loop as returned value will stay 1 when the bus goes silent.
    I would like it to return 0 as soon as no new data is available on the bus.

    Code:
    #include <FlexCAN_T4.h>
    FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> Can0;
    
    CAN_message_t msg, rxmsg;
    
    
    void setup(void) {
      
      Serial.begin(115200); 
      delay(500);
      Can0.begin();
      Can0.setBaudRate(100000);
    
    }
    
    
    void loop() {
    
      while (Can0.read(rxmsg) > 0) {
      Serial.print("RECEIVE: ");
      Serial.print(" ID: "); Serial.print(rxmsg.id, HEX);
      Serial.print(" Buffer: ");
      for ( uint8_t i = 0; i < rxmsg.len; i++ ) {
        Serial.print(rxmsg.buf[i], HEX); Serial.print(" ");
      } Serial.println();           
      }
    
    
    }

  25. #125
    Senior Member
    Join Date
    Dec 2016
    Location
    Montreal, Canada
    Posts
    3,193
    It will return 0 of there are no more messages filling one or more mailboxes. 1 is returned when at least one mailbox was read of an available message. There is no other way of counting especially if the stream is too fast filling before reading. The while loop does exit though when the messages are read faster than consumed

Posting Permissions

  • You may not post new threads
  • You may not post replies
  • You may not post attachments
  • You may not edit your posts
  •