Initial commit

This is just the 2018 code configured for PlatformIO
This commit is contained in:
jvblanck
2021-06-09 12:10:12 +02:00
commit 4faddf9248
77 changed files with 10334 additions and 0 deletions

9
lib/due_can/README.md Normal file
View File

@ -0,0 +1,9 @@
due_can
=======
Object oriented canbus library for Arduino Due compatible boards
Download the archived 1.0 release if you are compiling against existing
code bases such as the EVTV GEVCU project. New projects will probably
find that the current "master" branch version of the project is easier
to use.

1387
lib/due_can/due_can.cpp Normal file

File diff suppressed because it is too large Load Diff

314
lib/due_can/due_can.h Normal file
View File

@ -0,0 +1,314 @@
/*
Copyright (c) 2013 Arduino. All right reserved.
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
*/
#ifndef _CAN_LIBRARY_
#define _CAN_LIBRARY_
#include <Arduino.h>
//add some extra stuff that is needed for Arduino 1.5.2
#ifndef PINS_CAN0
static const uint8_t CAN1RX = 88;
static const uint8_t CAN1TX = 89;
// CAN0
#define PINS_CAN0 (90u)
// CAN1
#define PINS_CAN1 (91u)
#define ARDUINO152
#endif
#define CAN Can0
#define CAN2 Can1
#define CAN0_EN 50 //these enable pins match most all recent EVTV boards (EVTVDue, CAN Due 2.0)
#define CAN1_EN 48 //they're only defaults, you can set whichever pin you need when calling begin()
/** Define the Mailbox mask for eight mailboxes. */
#define GLOBAL_MAILBOX_MASK 0x000000ff
/** Disable all interrupt mask */
#define CAN_DISABLE_ALL_INTERRUPT_MASK 0xffffffff
/** Define the typical baudrate for CAN communication. */
#ifdef CAN_BPS_500K
#undef CAN_BPS_1000K
#undef CAN_BPS_800K
#undef CAN_BPS_500K
#undef CAN_BPS_250K
#undef CAN_BPS_125K
#undef CAN_BPS_50K
#undef CAN_BPS_33333
#undef CAN_BPS_25K
#undef CAN_BPS_10K
#undef CAN_BPS_5K
#endif
#define CAN_BPS_1000K 1000000
#define CAN_BPS_800K 800000
#define CAN_BPS_500K 500000
#define CAN_BPS_250K 250000
#define CAN_BPS_125K 125000
#define CAN_BPS_50K 50000
#define CAN_BPS_33333 33333
#define CAN_BPS_25K 25000
#define CAN_BPS_10K 10000
#define CAN_BPS_5K 5000
#define CAN_DEFAULT_BAUD CAN_BPS_250K
/** Define the mailbox mode. */
#define CAN_MB_DISABLE_MODE 0
#define CAN_MB_RX_MODE 1
#define CAN_MB_RX_OVER_WR_MODE 2
#define CAN_MB_TX_MODE 3
#define CAN_MB_CONSUMER_MODE 4
#define CAN_MB_PRODUCER_MODE 5
/** Define CAN mailbox transfer status code. */
#define CAN_MAILBOX_TRANSFER_OK 0 //! Read from or write into mailbox successfully.
#define CAN_MAILBOX_NOT_READY 0x01 //! Receiver is empty or transmitter is busy.
#define CAN_MAILBOX_RX_OVER 0x02 //! Message overwriting happens or there're messages lost in different receive modes.
#define CAN_MAILBOX_RX_NEED_RD_AGAIN 0x04 //! Application needs to re-read the data register in Receive with Overwrite mode.
#define SIZE_RX_BUFFER 32 //RX incoming ring buffer is this big
#define SIZE_TX_BUFFER 16 //TX ring buffer is this big
#define SIZE_LISTENERS 4 //number of classes that can register as listeners with this class
/** Define the timemark mask. */
#define TIMEMARK_MASK 0x0000ffff
/* CAN timeout for synchronization. */
#define CAN_TIMEOUT 100000
/** The max value for CAN baudrate prescale. */
#define CAN_BAUDRATE_MAX_DIV 128
/** Define the scope for TQ. */
#define CAN_MIN_TQ_NUM 8
#define CAN_MAX_TQ_NUM 25
/** Define the fixed bit time value. */
#define CAN_BIT_SYNC 1
#define CAN_BIT_IPT 2
typedef struct {
uint8_t uc_tq; //! CAN_BIT_SYNC + uc_prog + uc_phase1 + uc_phase2 = uc_tq, 8 <= uc_tq <= 25.
uint8_t uc_prog; //! Propagation segment, (3-bits + 1), 1~8;
uint8_t uc_phase1; //! Phase segment 1, (3-bits + 1), 1~8;
uint8_t uc_phase2; //! Phase segment 2, (3-bits + 1), 1~8, CAN_BIT_IPT <= uc_phase2;
uint8_t uc_sjw; //! Resynchronization jump width, (2-bits + 1), min(uc_phase1, 4);
uint8_t uc_sp; //! Sample point value, 0~100 in percent.
} can_bit_timing_t;
/** Values of bit time register for different baudrates, Sample point = ((1 + uc_prog + uc_phase1) / uc_tq) * 100%. */
const can_bit_timing_t can_bit_time[] = {
{8, (2 + 1), (1 + 1), (1 + 1), (2 + 1), 75},
{9, (1 + 1), (2 + 1), (2 + 1), (1 + 1), 67},
{10, (2 + 1), (2 + 1), (2 + 1), (2 + 1), 70},
{11, (3 + 1), (2 + 1), (2 + 1), (3 + 1), 72},
{12, (2 + 1), (3 + 1), (3 + 1), (3 + 1), 67},
{13, (3 + 1), (3 + 1), (3 + 1), (3 + 1), 77},
{14, (3 + 1), (3 + 1), (4 + 1), (3 + 1), 64},
{15, (3 + 1), (4 + 1), (4 + 1), (3 + 1), 67},
{16, (4 + 1), (4 + 1), (4 + 1), (3 + 1), 69},
{17, (5 + 1), (4 + 1), (4 + 1), (3 + 1), 71},
{18, (4 + 1), (5 + 1), (5 + 1), (3 + 1), 67},
{19, (5 + 1), (5 + 1), (5 + 1), (3 + 1), 68},
{20, (6 + 1), (5 + 1), (5 + 1), (3 + 1), 70},
{21, (7 + 1), (5 + 1), (5 + 1), (3 + 1), 71},
{22, (6 + 1), (6 + 1), (6 + 1), (3 + 1), 68},
{23, (7 + 1), (7 + 1), (6 + 1), (3 + 1), 70},
{24, (6 + 1), (7 + 1), (7 + 1), (3 + 1), 67},
{25, (7 + 1), (7 + 1), (7 + 1), (3 + 1), 68}
};
//This is architecture specific. DO NOT USE THIS UNION ON ANYTHING OTHER THAN THE CORTEX M3 / Arduino Due
//UNLESS YOU DOUBLE CHECK THINGS!
typedef union {
uint64_t value;
struct {
uint32_t low;
uint32_t high;
};
struct {
uint16_t s0;
uint16_t s1;
uint16_t s2;
uint16_t s3;
};
uint8_t bytes[8];
uint8_t byte[8]; //alternate name so you can omit the s if you feel it makes more sense
} BytesUnion;
typedef struct
{
uint32_t id; // EID if ide set, SID otherwise
uint32_t fid; // family ID
uint8_t rtr; // Remote Transmission Request
uint8_t priority; // Priority but only important for TX frames and then only for special uses.
uint8_t extended; // Extended ID flag
uint8_t length; // Number of data bytes
BytesUnion data; // 64 bits - lots of ways to access it.
} CAN_FRAME;
class CANListener
{
public:
CANListener();
virtual void gotFrame(CAN_FRAME *frame, int mailbox);
void attachMBHandler(uint8_t mailBox);
void detachMBHandler(uint8_t mailBox);
void attachGeneralHandler();
void detachGeneralHandler();
private:
int callbacksActive; //bitfield letting the code know which callbacks to actually try to use (for object oriented callbacks only)
friend class CANRaw; //class has to have access to the the guts of this one
};
class CANRaw
{
protected:
int numTXBoxes; //There are 8 mailboxes, anything not TX will be set RX
private:
/* CAN peripheral, set by constructor */
Can* m_pCan ;
volatile CAN_FRAME rx_frame_buff[SIZE_RX_BUFFER];
volatile CAN_FRAME tx_frame_buff[SIZE_TX_BUFFER];
volatile uint16_t rx_buffer_head, rx_buffer_tail;
volatile uint16_t tx_buffer_head, tx_buffer_tail;
void mailbox_int_handler(uint8_t mb, uint32_t ul_status);
uint8_t enablePin;
uint32_t busSpeed; //what speed is the bus currently initialized at? 0 if it is off right now
uint32_t write_id; //public storage for an id. Will be used by the write function to set which ID to send to.
bool bigEndian;
void (*cbCANFrame[9])(CAN_FRAME *); //8 mailboxes plus an optional catch all
CANListener *listener[SIZE_LISTENERS];
public:
// Constructor
CANRaw( Can* pCan, uint32_t En);
int setRXFilter(uint32_t id, uint32_t mask, bool extended);
int setRXFilter(uint8_t mailbox, uint32_t id, uint32_t mask, bool extended);
int watchFor(); //allow anything through
int watchFor(uint32_t id); //allow just this ID through (automatic determination of extended status)
int watchFor(uint32_t id, uint32_t mask); //allow a range of ids through
int watchForRange(uint32_t id1, uint32_t id2); //try to allow the range from id1 to id2 - automatically determine base ID and mask
void setNumTXBoxes(int txboxes);
int findFreeRXMailbox();
uint8_t mailbox_get_mode(uint8_t uc_index);
uint32_t mailbox_get_id(uint8_t uc_index);
uint32_t getMailboxIer(int8_t mailbox);
uint32_t set_baudrate(uint32_t ul_baudrate);
uint32_t init(uint32_t ul_baudrate);
uint32_t begin();
uint32_t begin(uint32_t baudrate);
uint32_t begin(uint32_t baudrate, uint8_t enablePin);
uint32_t getBusSpeed();
void enable();
void disable();
bool sendFrame(CAN_FRAME& txFrame);
void setWriteID(uint32_t id);
template <typename t> void write(t inputValue); //write a variable # of bytes out in a frame. Uses id as the ID.
void setBigEndian(bool);
void setCallback(int mailbox, void (*cb)(CAN_FRAME *));
void setGeneralCallback(void (*cb)(CAN_FRAME *));
//note that these below versions still use mailbox number. There isn't a good way around this.
void attachCANInterrupt(void (*cb)(CAN_FRAME *)); //alternative callname for setGeneralCallback
void attachCANInterrupt(uint8_t mailBox, void (*cb)(CAN_FRAME *));
void detachCANInterrupt(uint8_t mailBox);
//now, object oriented versions to make OO projects easier
boolean attachObj(CANListener *listener);
boolean detachObj(CANListener *listener);
void reset_all_mailbox();
void interruptHandler();
bool rx_avail();
int available(); //like rx_avail but returns the number of waiting frames
uint32_t get_rx_buff(CAN_FRAME &);
uint32_t read(CAN_FRAME &);
//misc old cruft kept around just in case anyone actually used any of it in older code.
//some are used within the functions above. Unless you really know of a good reason to use
//any of these you probably should steer clear of them.
void disable_low_power_mode();
void enable_low_power_mode();
void disable_autobaud_listen_mode();
void enable_autobaud_listen_mode();
void disable_overload_frame();
void enable_overload_frame();
void set_timestamp_capture_point(uint32_t ul_flag);
void disable_time_triggered_mode();
void enable_time_triggered_mode();
void disable_timer_freeze();
void enable_timer_freeze();
void disable_tx_repeat();
void enable_tx_repeat();
void set_rx_sync_stage(uint32_t ul_stage);
void enable_interrupt(uint32_t dw_mask);
void disable_interrupt(uint32_t dw_mask);
uint32_t get_interrupt_mask();
uint32_t get_status();
uint32_t get_internal_timer_value();
uint32_t get_timestamp_value();
uint8_t get_tx_error_cnt();
uint8_t get_rx_error_cnt();
void reset_internal_timer();
void global_send_transfer_cmd(uint8_t uc_mask);
void global_send_abort_cmd(uint8_t uc_mask);
void mailbox_set_timemark(uint8_t uc_index, uint16_t us_cnt);
uint32_t mailbox_get_status(uint8_t uc_index);
void mailbox_send_transfer_cmd(uint8_t uc_index);
void mailbox_send_abort_cmd(uint8_t uc_index);
void mailbox_init(uint8_t uc_index);
uint32_t mailbox_read(uint8_t uc_index, volatile CAN_FRAME *rxframe);
uint32_t mailbox_tx_frame(uint8_t uc_index);
void mailbox_set_id(uint8_t uc_index, uint32_t id, bool extended);
void mailbox_set_priority(uint8_t uc_index, uint8_t pri);
void mailbox_set_accept_mask(uint8_t uc_index, uint32_t mask, bool ext);
void mailbox_set_mode(uint8_t uc_index, uint8_t mode);
void mailbox_set_databyte(uint8_t uc_index, uint8_t bytepos, uint8_t val);
void mailbox_set_datalen(uint8_t uc_index, uint8_t dlen);
void mailbox_set_datal(uint8_t uc_index, uint32_t val);
void mailbox_set_datah(uint8_t uc_index, uint32_t val);
};
extern CANRaw Can0;
extern CANRaw Can1;
#endif // _CAN_LIBRARY_

View File

@ -0,0 +1,87 @@
// Arduino Due - CAN Sample 1
// Brief CAN example for Arduino Due
// Test the transmission from CAN0 Mailbox 0 to CAN1 Mailbox 0
// By Thibaut Viard/Wilfredo Molina/Collin Kidder 2013
// Required libraries
#include "variant.h"
#include <due_can.h>
#define TEST1_CAN_COMM_MB_IDX 0
#define TEST1_CAN_TRANSFER_ID 0x07
#define TEST1_CAN0_TX_PRIO 15
#define CAN_MSG_DUMMY_DATA 0x55AAEE22
// CAN frame max data length
#define MAX_CAN_FRAME_DATA_LEN 8
// Message variable to be send
uint32_t CAN_MSG_1 = 0;
//Leave defined if you use native port, comment if using programming port
#define Serial SerialUSB
void setup()
{
CAN_FRAME output;
// start serial port at 9600 bps:
Serial.begin(9600);
Serial.println("Type CAN message to send");
while (Serial.available() == 0);
}
void loop(){
CAN_FRAME output;
while (Serial.available() > 0) {
CAN_MSG_1 = Serial.parseInt();
if (Serial.read() == '\n') {
Serial.print("Sent value= ");
Serial.println(CAN_MSG_1);
}
}
// Initialize CAN0 and CAN1, baudrate is 250kb/s
Can0.begin(CAN_BPS_250K);
Can1.begin(CAN_BPS_250K);
//The default is to allow nothing through if nothing is specified
//only allow this one frame ID through.
Can1.watchFor(TEST1_CAN_TRANSFER_ID);
// Prepare transmit ID, data and data length in CAN0 mailbox 0
output.id = TEST1_CAN_TRANSFER_ID;
output.length = MAX_CAN_FRAME_DATA_LEN;
//Set first four bytes (32 bits) all at once
output.data.low = CAN_MSG_1;
//Set last four bytes (32 bits) all at once
output.data.high = CAN_MSG_DUMMY_DATA;
//Send out the frame on whichever mailbox is free or queue it for
//sending when there is an opening.
CAN.sendFrame(output);
// Wait for second canbus port to receive the frame
while (Can1.available() == 0) {
}
// Read the received data from CAN1 mailbox 0
CAN_FRAME incoming;
Can1.read(incoming);
Serial.print("CAN message received= ");
Serial.print(incoming.data.low, HEX);
Serial.print(incoming.data.high, HEX);
// Disable CAN0 Controller
Can0.disable();
// Disable CAN1 Controller
Can1.disable();
Serial.print("\nEnd of test");
while (1) {
}
}

View File

@ -0,0 +1,108 @@
// Arduino Due - CANbus Library - Extended Frames with Ping/Pong sending
// Ping/Pong torture test with extended frames.
// This example sets up a receive and transmit mailbox on both canbus devices.
// First CAN0 sends to CAN1. When CAN1 receives it sends to CAN0. PING/PONGs forever
// and as quickly as possible - This will saturate the bus so don't have anything important connected.
// By Thibaut Viard/Wilfredo Molina/Collin Kidder 2014
// Required libraries
#include "variant.h"
#include <due_can.h>
#define TEST1_CAN_TRANSFER_ID 0x11AE756A //random 29 bits
#define TEST1_CAN0_TX_PRIO 15
#define CAN_MSG_DUMMY_DATA 0x11BFFA4E
// CAN frame max data length
#define MAX_CAN_FRAME_DATA_LEN 8
uint32_t sentFrames, receivedFrames;
//Leave this defined if you use the native port or comment it out if you use the programming port
#define Serial SerialUSB
CAN_FRAME frame1, frame2, incoming;
void setup() {
// start serial port at 115200 bps:
Serial.begin(115200);
// Verify CAN0 and CAN1 initialization, baudrate is 1Mb/s:
if (Can0.begin(CAN_BPS_1000K) &&
Can1.begin(CAN_BPS_1000K)) {
}
else {
Serial.println("CAN initialization (sync) ERROR");
}
//Initialize the definitions for the frames we'll be sending.
//This can be done here because the frame never changes
frame1.id = TEST1_CAN_TRANSFER_ID;
frame1.length = MAX_CAN_FRAME_DATA_LEN;
//Below we set the 8 data bytes in 32 bit (4 byte) chunks
//Bytes can be set individually with frame1.data.bytes[which] = something
frame1.data.low = 0x20103040;
frame1.data.high = CAN_MSG_DUMMY_DATA;
//We are using extended frames so mark that here. Otherwise it will just use
//the first 11 bits of the ID set
frame1.extended = 1;
frame2.id = TEST1_CAN_TRANSFER_ID + 0x200;
frame2.length = MAX_CAN_FRAME_DATA_LEN;
frame2.data.low = 0xB8C8A8E8;
frame2.data.high = 0x01020304;
frame2.extended = 1;
//Both of these lines create a filter on the corresponding CAN device that allows
//just the one ID we're interested in to get through.
//The syntax is (mailbox #, ID, mask, extended)
//You can also leave off the mailbox number: (ID, mask, extended)
Can1.watchFor(TEST1_CAN_TRANSFER_ID + 0x200);
Can0.watchFor(TEST1_CAN_TRANSFER_ID);
test_1();
}
// Test rapid fire ping/pong of extended frames
static void test_1(void)
{
CAN_FRAME inFrame;
uint32_t counter = 0;
// Send out the first frame
Can0.sendFrame(frame2);
sentFrames++;
while (1==1) {
if (Can0.available() > 0) {
Can0.read(incoming);
Can0.sendFrame(frame2);
delayMicroseconds(100);
sentFrames++;
receivedFrames++;
counter++;
}
if (Can1.available() > 0) {
Can1.read(incoming);
Can1.sendFrame(frame1);
delayMicroseconds(100);
sentFrames++;
receivedFrames++;
counter++;
}
if (counter > 5000) {
counter = 0;
Serial.print("S: ");
Serial.print(sentFrames);
Serial.print(" R: ");
Serial.println(receivedFrames);
}
}
}
// can_example application entry point
void loop()
{
}

View File

@ -0,0 +1,55 @@
//Reads all traffic on CAN0 and forwards it to CAN1 (and in the reverse direction) but modifies some frames first.
// Required libraries
#include "variant.h"
#include <due_can.h>
//Leave defined if you use native port, comment if using programming port
#define Serial SerialUSB
void setup()
{
Serial.begin(115200);
// Initialize CAN0 and CAN1, Set the proper baud rates here
Can0.begin(CAN_BPS_250K);
Can1.begin(CAN_BPS_250K);
Can0.watchFor();
}
void sendData()
{
CAN_FRAME outgoing;
outgoing.id = 0x400;
outgoing.extended = false;
outgoing.priority = 4; //0-15 lower is higher priority
outgoing.data.s0 = 0xFEED;
outgoing.data.byte[2] = 0xDD;
outgoing.data.byte[3] = 0x55;
outgoing.data.high = 0xDEADBEEF;
Can0.sendFrame(outgoing);
}
void loop(){
CAN_FRAME incoming;
static unsigned long lastTime = 0;
if (Can0.available() > 0) {
Can0.read(incoming);
Can1.sendFrame(incoming);
}
if (Can1.available() > 0) {
Can1.read(incoming);
Can0.sendFrame(incoming);
}
if ((millis() - lastTime) > 1000)
{
lastTime = millis();
sendData();
}
}

View File

@ -0,0 +1,93 @@
// Arduino Due - Displays all traffic found on either canbus port
//Modified version of the SnooperCallback sketch. This one illustrates
//how to use a class object to receive callbacks. It's a little different
//from the non-OO approach.
// By Thibaut Viard/Wilfredo Molina/Collin Kidder 2013-2015
// Required libraries
#include "variant.h"
#include <due_can.h>
//Leave defined if you use native port, comment if using programming port
//This sketch could provide a lot of traffic so it might be best to use the
//native port
#define Serial SerialUSB
class ExampleClass : public CANListener //CANListener provides an interface to get callbacks on this class
{
public:
void printFrame(CAN_FRAME *frame, int mailbox);
void gotFrame(CAN_FRAME *frame, int mailbox); //overrides the parent version so we can actually do something
};
//Prints out the most useful information about the incoming frame.
void ExampleClass::printFrame(CAN_FRAME *frame, int mailbox)
{
Serial.print("MB: ");
if (mailbox > -1) Serial.print(mailbox);
else Serial.print("???");
Serial.print(" ID: 0x");
Serial.print(frame->id, HEX);
Serial.print(" Len: ");
Serial.print(frame->length);
Serial.print(" Data: 0x");
for (int count = 0; count < frame->length; count++) {
Serial.print(frame->data.bytes[count], HEX);
Serial.print(" ");
}
Serial.print("\r\n");
}
//Classes register just one method that receives all callbacks. If a frame didn't match any specific mailbox
//callback but the general callback was registered then the mailbox will be set as -1. Otherwise it is the mailbox
//with the matching filter for this frame.
void ExampleClass::gotFrame(CAN_FRAME* frame, int mailbox)
{
this->printFrame(frame, mailbox);
}
ExampleClass myClass; //initialize the class global so the reference to it can be picked up anywhere
void setup()
{
Serial.begin(115200);
// Initialize CAN0, Set the proper baud rates here
// Pass the proper pin for enabling your transceiver or 255 if you don't need an enable pin to be toggled.
Can0.begin(CAN_BPS_500K, 50);
//By default there are 7 RX mailboxes for each device
//extended
//syntax is mailbox, ID, mask, extended
Can0.setRXFilter(0, 0x2FF00, 0x1FF2FF00, true);
Can0.setRXFilter(1, 0x1F0000, 0x1F1F0000, true);
Can0.setRXFilter(2, 0, 0, true); //catch all mailbox
//standard
Can0.setRXFilter(3, 0x40F, 0x7FF, false);
Can0.setRXFilter(4, 0x310, 0x7F0, false);
Can0.setRXFilter(5, 0x200, 0x700, false);
Can0.setRXFilter(6, 0, 0, false); //catch all mailbox
Can0.attachObj(&myClass);
//let library know we want to receive callbacks for the following mailboxes
//once we attach above the canbus object knows about us. The actual functions
//to attach are members of CANListener so use your class name
myClass.attachMBHandler(0);
myClass.attachMBHandler(1);
myClass.attachMBHandler(3);
myClass.attachMBHandler(4);
myClass.attachMBHandler(5);
//set to get a callback for any other mailboxes not already covered above
myClass.attachGeneralHandler();
}
void loop(){ //All work is done via callback as frames come in - no need to poll for them. SO, just print periodic message to show we're alive
delay(5000);
Serial.println("Still listening");
}

View File

@ -0,0 +1,101 @@
/*
Arduino Due - Displays frames that fall between a range of addresses.
Modified from some of the other examples - notably CAN_SnooperCallBack
The difference here is that we only allow a range of ids. This demonstrates
the new watchForRange function as well as per-mailbox and general callback
functionality
By Thibaut Viard/Wilfredo Molina/Collin Kidder 2013-2014
*/
// Required libraries
#include "variant.h"
#include <due_can.h>
//Leave defined if you use native port, comment if using programming port
//This sketch could provide a lot of traffic so it might be best to use the
//native port
#define Serial SerialUSB
void printFrame(CAN_FRAME *frame, int filter) {
Serial.print("Fltr: ");
if (filter > -1) Serial.print(filter);
else Serial.print("???");
Serial.print(" ID: 0x");
Serial.print(frame->id, HEX);
Serial.print(" Len: ");
Serial.print(frame->length);
Serial.print(" Data: 0x");
for (int count = 0; count < frame->length; count++) {
Serial.print(frame->data.bytes[count], HEX);
Serial.print(" ");
}
Serial.print("\r\n");
}
void gotFrameMB0(CAN_FRAME *frame)
{
printFrame(frame, 0);
}
void gotFrameMB1(CAN_FRAME *frame)
{
printFrame(frame, 1);
}
void gotFrameMB3(CAN_FRAME *frame)
{
printFrame(frame, 3);
}
void gotFrameMB4(CAN_FRAME *frame)
{
printFrame(frame, 4);
}
void gotFrameMB5(CAN_FRAME *frame)
{
printFrame(frame, 5);
}
void gotFrame(CAN_FRAME *frame)
{
printFrame(frame, -1);
}
void setup()
{
Serial.begin(115200);
// Initialize CAN0, Set the proper baud rates here
Can0.init(CAN_BPS_250K);
//By default there are 7 RX mailboxes for each device
//extended
//syntax is mailbox, ID, mask, extended
Can0.watchForRange(0x10000000, 0x10004000);
Can0.watchForRange(0x10050000, 0x100500FF);
Can0.setRXFilter(0, 0, true); //catch all mailbox
//standard
Can0.watchForRange(0x400, 0x470);
Can0.watchForRange(0x500, 0x5FF);
Can0.watchForRange(0x200, 0x220);
Can0.setRXFilter(0, 0, false); //catch all mailbox
//now register all of the callback functions.
Can0.attachCANInterrupt(0, gotFrameMB0);
Can0.attachCANInterrupt(1, gotFrameMB1);
Can0.attachCANInterrupt(3, gotFrameMB3);
Can0.attachCANInterrupt(4, gotFrameMB4);
Can0.attachCANInterrupt(5, gotFrameMB5);
//this function will get a callback for any mailbox that doesn't have a registered callback from above -> 2 and 6
Can0.attachCANInterrupt(gotFrame);
}
void loop(){ //note the empty loop here. All work is done via callback as frames come in - no need to poll for them
}

View File

@ -0,0 +1,97 @@
// Arduino Due - Displays all traffic found on either canbus port
//Modified from the more generic TrafficSniffer sketch to instead use
//callback functions to receive the frames. Illustrates how to use
//the per-mailbox and general callback functionality
// By Thibaut Viard/Wilfredo Molina/Collin Kidder 2013-2014
// Required libraries
#include "variant.h"
#include <due_can.h>
//Leave defined if you use native port, comment if using programming port
//This sketch could provide a lot of traffic so it might be best to use the
//native port
#define Serial SerialUSB
void printFrame(CAN_FRAME *frame, int filter) {
Serial.print("Fltr: ");
if (filter > -1) Serial.print(filter);
else Serial.print("???");
Serial.print(" ID: 0x");
Serial.print(frame->id, HEX);
Serial.print(" Len: ");
Serial.print(frame->length);
Serial.print(" Data: 0x");
for (int count = 0; count < frame->length; count++) {
Serial.print(frame->data.bytes[count], HEX);
Serial.print(" ");
}
Serial.print("\r\n");
}
void gotFrameMB0(CAN_FRAME *frame)
{
printFrame(frame, 0);
}
void gotFrameMB1(CAN_FRAME *frame)
{
printFrame(frame, 1);
}
void gotFrameMB3(CAN_FRAME *frame)
{
printFrame(frame, 3);
}
void gotFrameMB4(CAN_FRAME *frame)
{
printFrame(frame, 4);
}
void gotFrameMB5(CAN_FRAME *frame)
{
printFrame(frame, 5);
}
void gotFrame(CAN_FRAME *frame)
{
printFrame(frame, -1);
}
void setup()
{
Serial.begin(115200);
// Initialize CAN0, Set the proper baud rates here
Can0.begin(CAN_BPS_250K);
//By default there are 7 RX mailboxes for each device
//extended
//syntax is mailbox, ID, mask, extended
Can0.setRXFilter(0, 0x2FF00, 0x1FF2FF00, true);
Can0.setRXFilter(1, 0x1F0000, 0x1F1F0000, true);
Can0.setRXFilter(2, 0, 0, true); //catch all mailbox
//standard
Can0.setRXFilter(3, 0x40F, 0x7FF, false);
Can0.setRXFilter(4, 0x310, 0x7F0, false);
Can0.watchFor(0x200, 0x700); //used in place of above syntax
Can0.setRXFilter(0, 0, false); //catch all mailbox - no mailbox ID specified
//now register all of the callback functions.
Can0.setCallback(0, gotFrameMB0);
Can0.setCallback(1, gotFrameMB1);
Can0.setCallback(3, gotFrameMB3);
Can0.setCallback(4, gotFrameMB4);
Can0.setCallback(5, gotFrameMB5);
//this function will get a callback for any mailbox that doesn't have a registered callback from above -> 2 and 6
Can0.setGeneralCallback(gotFrame);
}
void loop(){ //note the empty loop here. All work is done via callback as frames come in - no need to poll for them
}

View File

@ -0,0 +1,63 @@
//Reads all traffic on CAN0 and forwards it to CAN1 (and in the reverse direction) but modifies some frames first.
// Required libraries
#include "variant.h"
#include <due_can.h>
//Leave defined if you use native port, comment if using programming port
#define Serial SerialUSB
void setup()
{
Serial.begin(115200);
// Initialize CAN0 and CAN1, Set the proper baud rates here
Can0.begin(CAN_BPS_500K);
Can1.begin(CAN_BPS_250K);
//By default there are 7 mailboxes for each device that are RX boxes
//This sets each mailbox to have an open filter that will accept extended
//or standard frames
int filter;
//extended
for (filter = 0; filter < 3; filter++) {
Can0.setRXFilter(filter, 0, 0, true);
Can1.setRXFilter(filter, 0, 0, true);
}
//standard
//for (int filter = 3; filter < 7; filter++) {
//Can0.setRXFilter(filter, 0, 0, false);
//Can1.setRXFilter(filter, 0, 0, false);
//}
}
void printFrame(CAN_FRAME &frame) {
Serial.print("ID: 0x");
Serial.print(frame.id, HEX);
Serial.print(" Len: ");
Serial.print(frame.length);
Serial.print(" Data: 0x");
for (int count = 0; count < frame.length; count++) {
Serial.print(frame.data.bytes[count], HEX);
Serial.print(" ");
}
Serial.print("\r\n");
}
void loop(){
CAN_FRAME incoming;
if (Can0.available() > 0) {
Can0.read(incoming);
Can1.sendFrame(incoming);
//printFrame(incoming); //uncomment line to print frames that are going out
}
if (Can1.available() > 0) {
Can1.read(incoming);
Can0.sendFrame(incoming);
//printFrame(incoming);
}
}

View File

@ -0,0 +1,65 @@
// Arduino Due - Displays all traffic found on either canbus port
// By Thibaut Viard/Wilfredo Molina/Collin Kidder 2013-2014
// Required libraries
#include "variant.h"
#include <due_can.h>
//Leave defined if you use native port, comment if using programming port
//This sketch could provide a lot of traffic so it might be best to use the
//native port
#define Serial SerialUSB
void setup()
{
Serial.begin(115200);
// Initialize CAN0 and CAN1, Set the proper baud rates here
Can0.begin(CAN_BPS_250K);
Can1.begin(CAN_BPS_250K);
//By default there are 7 mailboxes for each device that are RX boxes
//This sets each mailbox to have an open filter that will accept extended
//or standard frames
int filter;
//extended
for (filter = 0; filter < 3; filter++) {
Can0.setRXFilter(filter, 0, 0, true);
Can1.setRXFilter(filter, 0, 0, true);
}
//standard
for (int filter = 3; filter < 7; filter++) {
Can0.setRXFilter(filter, 0, 0, false);
Can1.setRXFilter(filter, 0, 0, false);
}
}
void printFrame(CAN_FRAME &frame) {
Serial.print("ID: 0x");
Serial.print(frame.id, HEX);
Serial.print(" Len: ");
Serial.print(frame.length);
Serial.print(" Data: 0x");
for (int count = 0; count < frame.length; count++) {
Serial.print(frame.data.bytes[count], HEX);
Serial.print(" ");
}
Serial.print("\r\n");
}
void loop(){
CAN_FRAME incoming;
if (Can0.available() > 0) {
Can0.read(incoming);
printFrame(incoming);
}
if (Can1.available() > 0) {
Can1.read(incoming);
printFrame(incoming);
}
}

195
lib/due_can/howtouse.txt Normal file
View File

@ -0,0 +1,195 @@
The library has a ton of functions. A lot of them are complicated
and really aren't necessary for normal use. This document
explains how to use the library simply and will suffice for most
applications.
To start with, you'll need to initialize the canbus hardware. There are two
Canbus ports on the Due. There are objects already created
for each port: Can0 and Can1. All functions below are called on one
of those two objects. Note: The library used to use CAN and CAN2 in place
of Can0 and Can1. You can still use those other names as they've been maintained
as aliases. Where functions have been added the old functions have been left behind
so backward compatibility is maintained. Use whichever functions work best for you.
init(baudrate) - Initializes the given canbus port with the given baud
rate. Sets up for interrupt driven canbus with 7 receive mailboxes
and 1 transmit mailbox. You don't need to worry about mailboxes though
if you don't want to. Also sets the default enable pin (62 for Can0, 65 for Can1)
Example: Can0.init(250000);
begin(baudrate) - Exactly like init above.
begin(baudrate, enablepin) - Like above two but with addition of an enable pin. The enable pin
will be raised high when the relevant canbus port is enabled and sunk low when the relevant port
is disabled. If you do not need an enable pin then pass 255.
Example: Can0.begin(250000, 62);
begin() - Initializes with default settings for both baud and enable (250k baud, enable as above)
set_baudrate(baudrate) - Set the baud rate of the canbus. This
can be set to anything you'd like (within reason) but the common
baud rates are 33333, 125000, 250000, 500000, 1000000. Do not
use this unless you are changing the baud rate of an already
initialized canbus port.
Example: Can0.set_baudrate(500000);
enable() - Enable the canbus port. You don't need to call this unless
you've disabled the port at some time in the past.
Example: Can0.enable();
disable() - Disable the canbus port. You will no longer be able to
properly use it.
Example: Can0.disable();
Then, it is on to using the newly set-up canbus port:
This is the structure you will use for both sending and receiving.
typedef struct
{
uint32_t id; // Can0 be either 11 or 29 bit ID
uint32_t fid; // Family ID is a somewhat advanced thing. You Can0 ignore it.
uint8_t rtr; // Remote Transmission Request - Don't use this.
uint8_t priority; // Priority for TX frames. Probably not that useful normally
uint8_t extended;//Set to true for extended frames, false for standard
uint8_t length; // Number of data bytes
BytesUnion data; // Data bytes
} CAN_FRAME;
In turn, BytesUnion is a way to access the 8 data bytes in a variety of ways with a variety of names:
typedef union {
uint64_t value;
struct {
uint32_t low;
uint32_t high;
};
struct {
uint16_t s0;
uint16_t s1;
uint16_t s2;
uint16_t s3;
};
uint8_t bytes[8];
uint8_t byte[8]; //alternate name so you can omit the s if you feel it makes more sense
} BytesUnion;
int setRXFilter(id, mask, extended) - Set up a filter for incoming frames.
This version of the function allows one to forget about mailboxes and just
set a filter. It will handle the details for you and return which mailbox it used
in case you need to change it later. It returns -1 if there was a problem.
Example: Can0.setRXFilter(0x7E0, 0x7E0, false);
int setRXFilter(mailbox,id,mask,extended) - The other version of setting a filter.
It takes the mailbox to change. So long as you pass a valid mailbox number (0-7)
you will get that number back as the return value. It returns -1 on error.
Example: Can0.setRXFilter(0, 0x10000, 0x10000, true);
int watchFor() - An easy way to allow all traffic through. Will automatically add 1 mailbox
for standard frames and 1 for extended frames.
Example: Can0.watchFor();
int watchFor(uint32_t id) - Watch for a specific and single ID. Will automatically determine whether to accept
extended or standard frames.
Example: Can0.watchFor(0x740);
int watchFor(uint32_t id, uint32_t mask) - Watch for a group of IDs based on ID and a mask. Also uses
automatic determination of extended/standard.
Example: Can0.watchFor(0x620, 0x7F0); //Watch for a range of ids from 0x620 to 0x62F
int watchForRange(uint32_t id1, uint32_t id2) - A potentially much easier routine. Pass the lowest and highest
IDs you want to accept and it will automatically determine a suitable ID and mask to use. It might accept
more IDs than what you passed if necessary.
Example: Can0.watchForRange(0x620, 0x64F); //Accept frames with IDs from 0x620 to 0x64F
int findFreeRXMailbox() - Allows your program to get a free mailbox if you're
going to use the above function directly. You shouldn't need to use this very often.
Example: mailbox = Can0.findFreeRXMailbox();
setNumTXBoxes(txboxes) - Above it was mentioned that the default setup is to
have 7 RX mailboxes and 1 TX mailbox. This should work for 95% of programs
because the underlying library code uses interrupts with large buffers. But, if you
will only be sending or only receiving or if you otherwise really need to tweak the
arrangement you Can0 with this function. This function totally reinitializes all
mailboxes so be sure to call this function before you start setting up your filters.
Example: Can0.setNumTXBoxes(2);
There are two ways to receive canbus frames with this library. You Can0 choose from
callback driven reception or buffered frames. Either one is interrupt driven. The
choice really comes down to whether you'd like to process frames at a given point
in your code or whether you'd like to immediately get a call when a frame comes in.
Buffered / Polling version:
bool rx_avail() - The actual frame reception code is interrupt driven so you do not
need to rapidly poll for incoming frames at risk of losing some. However, it is still
handy to know if one or more frames came in. This function returns true if there
are received frames waiting to be processed by your program.
Example: if (Can0.rx_avail()) //do something here.
int available() - Returns the number of waiting frames in the receive buffer. Can be used in place
of rx_avail()
Example: if (Can0.available() > 0) //do something
get_rx_buff(CAN_FRAME &) - Read a waiting frame into the variable passed to the function.
Example:
CAN_FRAME myFrame;
if (Can0.rx_avail()) get_rx_buff(myFrame);
read(CAN_FRAME &) - Exactly like get_rx_buff but with an easier to remember name.
Example: Can0.read(myFrame);
Callback version:
setCallback(mailbox, cb) - Set a callback function for a mailbox (0-7)
Example:
void someFunction(Can0_FRAME *frame)
{
//do something with frame in here
}
setCallback(3, someFunction); //sets callback for third mailbox
setGeneralCallback(cb) - Set a callback that will be used for any mailbox that doesn't have a registered callback
Example: Can0.setGeneralCallback(someFunction);
void attachCANInterrupt(void (*cb)(CAN_FRAME *)) - Merely an alternative name for setGeneralCallback
void attachCANInterrupt(uint8_t mailBox, void (*cb)(CAN_FRAME *)) - An alternative name for setCallback
void detachCANInterrupt(uint8_t mailBox) - Removes the handler from the given mailbox.
Example: Can0.detachCANInterrupt(0);
These calls will not require any polling at all. You will immediately be given any frames that come into the system.
However, care must be taken as your callback function will be in interrupt context. Do not do very much work
in the callback function. Any frame that was returned via callback will not be buffered and thus will not be available
to the buffered system described previously.
Frame sending:
bool sendFrame(Can0_FRAME&) - Send a frame over canbus. It will try to send immediately
but will automatically fall back to buffering the frame and sending via interrupt
when the bus frees up. Returns whether it could send a frame (true/false). Only false if the TX buffer
fills up for some reason. In that cases you'll have to send frames at a slower rate or check to be sure
that the CAN bus is actually operational.
Example:
CAN_FRAME myFrame;
myFrame.id = 45;
myFrame.length = 1
myFrame.data[0] = 128;
Can0.sendFrame(myFrame);
There is an alternative output method now. You can set the ID and then use write to write out frames. This will
send one frame per call but can be used to output the value of variables up to 8 bytes in size:
void setWriteID(uint32_t id) - Set the ID to use for the write function.
Example: Can0.setWriteID(0x620);
void setBigEndian(bool) - Set how to output the bytes sent by the write function. The Due is little endian so
setting True to this function will cause bytes to be output in reverse order (big endian)
Example: Can0.setBigEndian(true);
template <typename t> void write(t inputValue) - Write the given input bytewise into a frame and send it. Uses
the ID from the setWriteID function. Immediately tries to send the frame. This function is probably most useful
for simple tests as it does not support sending multiple values in the same frame.
Example:
int SomeValue = 23423;
Can0.write(SomeValue);

117
lib/due_can/keywords.txt Normal file
View File

@ -0,0 +1,117 @@
###classes, datatypes, C++ keywords
CAN_FRAME KEYWORD1
CANListener KEYWORD1
###functions and methods
setRXFilter KEYWORD2
watchFor KEYWORD2
watchForRange KEYWORD2
setNumTXBoxes KEYWORD2
begin KEYWORD2
set_baudrate KEYWORD2
init KEYWORD2
enable KEYWORD2
disable KEYWORD2
disable_low_power_mode KEYWORD2
enable_low_power_mode KEYWORD2
disable_autobaud_listen_mode KEYWORD2
enable_autobaud_listen_mode KEYWORD2
disable_overload_frame KEYWORD2
enable_overload_frame KEYWORD2
set_timestamp_capture_point KEYWORD2
disable_time_triggered_mode KEYWORD2
enable_time_triggered_mode KEYWORD2
disable_timer_freeze KEYWORD2
enable_timer_freeze KEYWORD2
disable_tx_repeat KEYWORD2
enable_tx_repeat KEYWORD2
set_rx_sync_stage KEYWORD2
enable_interrupt KEYWORD2
disable_interrupt KEYWORD2
get_interrupt_mask KEYWORD2
get_status KEYWORD2
get_internal_timer_value KEYWORD2
get_timestamp_value KEYWORD2
get_tx_error_cnt KEYWORD2
get_rx_error_cnt KEYWORD2
reset_internal_timer KEYWORD2
global_send_transfer_cmd KEYWORD2
global_send_abort_cmd KEYWORD2
mailbox_set_timemark KEYWORD2
mailbox_get_status KEYWORD2
mailbox_send_transfer_cmd KEYWORD2
mailbox_send_abort_cmd KEYWORD2
mailbox_init KEYWORD2
mailbox_read KEYWORD2
mailbox_tx_frame KEYWORD2
mailbox_set_id KEYWORD2
mailbox_set_priority KEYWORD2
mailbox_set_accept_mask KEYWORD2
mailbox_set_mode KEYWORD2
mailbox_set_databyte KEYWORD2
mailbox_set_datalen KEYWORD2
mailbox_set_datal KEYWORD2
mailbox_set_datah KEYWORD2
reset_all_mailbox KEYWORD2
rx_avail KEYWORD2
get_rx_buff KEYWORD2
sendFrame KEYWORD2
setWriteID KEYWORD2
write KEYWORD2
setBigEndian KEYWORD2
setCallBack KEYWORD2
setGeneralCallback KEYWORD2
attachCANInterrupt KEYWORD2
detachCANInterrupt KEYWORD2
available KEYWORD2
read KEYWORD2
getBusSpeed KEYWORD2
attachObj KEYWORD2
detachObj KEYWORD2
CAN KEYWORD3
CAN2 KEYWORD3
Can0 KEYWORD3
Can1 KEYWORD3
###Constants
CAN_BPS_1000K LITERAL1
CAN_BPS_800K LITERAL1
CAN_BPS_500K LITERAL1
CAN_BPS_250K LITERAL1
CAN_BPS_125K LITERAL1
CAN_BPS_50K LITERAL1
CAN_BPS_25K LITERAL1
CAN_BPS_10K LITERAL1
CAN_BPS_5K LITERAL1
CAN_MB_DISABLE_MODE LITERAL1
CAN_MB_RX_MODE LITERAL1
CAN_MB_RX_OVER_WR_MODE LITERAL1
CAN_MB_TX_MODE LITERAL1
CAN_MB_CONSUMER_MODE LITERAL1
CAN_MB_PRODUCER_MODE LITERAL1
CAN_TCR_MB0 LITERAL1
CAN_TCR_MB1 LITERAL1
CAN_TCR_MB2 LITERAL1
CAN_TCR_MB3 LITERAL1
CAN_TCR_MB4 LITERAL1
CAN_TCR_MB5 LITERAL1
CAN_TCR_MB6 LITERAL1
CAN_TCR_MB7 LITERAL1
CAN_MSR_MRDY LITERAL1
CAN_IER_MB0 LITERAL1
CAN_IER_MB1 LITERAL1
CAN_IER_MB2 LITERAL1
CAN_IER_MB3 LITERAL1
CAN_IER_MB4 LITERAL1
CAN_IER_MB5 LITERAL1
CAN_IER_MB6 LITERAL1
CAN_IER_MB7 LITERAL1
CAN_DISABLE_ALL_INTERRUPT_MASK LITERAL1
CAN0_IRQn LITERAL1
CAN1_IRQn LITERAL1

View File

@ -0,0 +1,9 @@
name=due_can
version=2.0.1
author=Collin Kidder <kidderc@gmail.com>, Thibaut Viard, Wilfredo Molina
maintainer=Collin Kidder <kidderc@gmail.com>
sentence=Allows for CAN bus communications with the Arduino Due
paragraph=Implements interrupt driven communication and supports both object oriented and non-OOP callbacks
category=Communication
url=https://github.com/collin80/due_can
architectures=sam