├── License.txt ├── README.md ├── examples ├── receive_Blink │ └── receive_Blink.ino ├── receive_check │ └── receive_check.ino ├── receive_interrupt │ └── receive_interrupt.ino ├── send │ └── send.ino ├── send_Blink │ └── send_Blink.ino ├── send_Blink_ROS │ └── send_Blink_ROS.ino ├── set_mask_filter_recv │ └── set_mask_filter_recv.ino └── set_mask_filter_send │ └── set_mask_filter_send.ino ├── keywords.txt ├── mcp_can.cpp ├── mcp_can.h └── mcp_can_dfs.h /License.txt: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2013 Seeed Technology Inc. 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in 13 | all copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 21 | THE SOFTWARE. -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | CAN BUS Shield 2 | --------------------------------------------------------- 3 | [![CAN BUS Shield](http://www.seeedstudio.com/depot/images/1130300211.jpg)](http://www.seeedstudio.com/depot/CANBUS-Shield-p-2256.html?cPath=19_88) 4 | 5 | 6 | 7 |
8 | CAN-BUS is a common industrial bus because of its long travel distance, medium communication speed and high reliability. It is commonly found on modern machine tools and as an automotive diagnostic bus. This CAN-BUS Shield adopts MCP2515 CAN Bus controller with SPI interface and MCP2551 CAN transceiver to give your Arduino/Seeeduino CAN-BUS capibility. With an OBD-II converter cable added on and the OBD-II library imported, you are ready to build an onboard diagnostic device or data logger. 9 | 10 | - Implements CAN V2.0B at up to 1 Mb/s 11 | - SPI Interface up to 10 MHz 12 | - Standard (11 bit) and extended (29 bit) data and remote frames 13 | - Two receive buffers with prioritized message storage 14 | - Industrial standard 9 pin sub-D connector 15 | - Two LED indicators 16 | 17 | 18 | 19 |
20 | # Usage: 21 | 22 | 23 | 24 | ## 1. Set the BaudRate 25 | 26 | This function is used to initialize the baudrate of the CAN Bus system. 27 | 28 | The available baudrates are listed as follws: 29 | 30 | #define CAN_5KBPS 1 31 | #define CAN_10KBPS 2 32 | #define CAN_20KBPS 3 33 | #define CAN_31K25BPS 4 34 | #define CAN_33KBPS 5 35 | #define CAN_40KBPS 6 36 | #define CAN_50KBPS 7 37 | #define CAN_80KBPS 8 38 | #define CAN_83K3BPS 9 39 | #define CAN_95KBPS 10 40 | #define CAN_100KBPS 11 41 | #define CAN_125KBPS 12 42 | #define CAN_200KBPS 13 43 | #define CAN_250KBPS 14 44 | #define CAN_500KBPS 15 45 | #define CAN_1000KBPS 16 46 | 47 | 48 |
49 | 50 | ##2. Set Receive Mask and Filter 51 | 52 | There are 2 receive mask registers and 5 filter registers on the controller chip that guarantee you get data from the target device. They are useful especially in a large network consisting of numerous nodes. 53 | 54 | We provide two functions for you to utilize these mask and filter registers. They are: 55 | 56 | init_Mask(unsigned char num, unsigned char ext, unsigned char ulData); 57 | init_Filt(unsigned char num, unsigned char ext, unsigned char ulData); 58 | 59 | **num** represents which register to use. You can fill 0 or 1 for mask and 0 to 5 for filter. 60 | 61 | **ext** represents the status of the frame. 0 means it's a mask or filter for a standard frame. 1 means it's for a extended frame. 62 | 63 | **ulData** represents the content of the mask of filter. 64 | 65 | 66 | 67 |
68 | ## 3. Check Receive 69 | The MCP2515 can operate in either a polled mode, where the software checks for a received frame, or using additional pins to signal that a frame has been received or transmit completed. Use the following function to poll for received frames. 70 | 71 | INT8U MCP_CAN::checkReceive(void); 72 | 73 | The function will return 1 if a frame arrives, and 0 if nothing arrives. 74 | 75 | 76 | 77 |
78 | ## 4. Get CAN ID 79 | 80 | When some data arrive, you can use the following function to get the CAN ID of the "send" node. 81 | 82 | INT32U MCP_CAN::getCanId(void); 83 | 84 | 85 | 86 |
87 | ## 5. Send Data 88 | 89 | CAN.sendMsgBuf(INT8U id, INT8U ext, INT8U len, data_buf); 90 | 91 | This is a function to send data onto the bus. In which: 92 | 93 | **id** represents where the data come from. 94 | 95 | **ext** represents the status of the frame. '0' means standard frame. '1' means extended frame. 96 | 97 | **len** represents the length of this frame. 98 | 99 | **data_buf** is the content of this message. 100 | 101 | For example, In the 'send' example, we have: 102 | 103 |
  
104 | unsigned char stmp[8] = {0, 1, 2, 3, 4, 5, 6, 7};
105 | 
106 | CAN.sendMsgBuf(0x00, 0, 8, stmp); //send out the message 'stmp' to the bus and tell other devices this is a standard frame from 0x00.
107 | 
108 | 109 | 110 | 111 |
112 | ## 6. Receive Data 113 | 114 | The following function is used to receive data on the 'receive' node: 115 | 116 | CAN.readMsgBuf(unsigned char len, unsigned char buf); 117 | 118 | In conditions that masks and filters have been set. This function can only get frames that meet the requirements of masks and filters. 119 | 120 | **len** represents the data length. 121 | 122 | **buf** is where you store the data. 123 | 124 |
125 | ## 7. Check additional flags 126 | 127 | When frame is received you may check whether it was remote request and whether it was an extended (29bit) frame. 128 | 129 | CAN.isRemoteRequest(); 130 | CAN.isExtendedFrame(); 131 | 132 | **return value** is '0' for a negative response and '1' for a positive 133 | 134 | 135 |
136 | For more information, please refer to [wiki page](http://www.seeedstudio.com/wiki/CAN-BUS_Shield). 137 | 138 | 139 | ---- 140 | 141 | This software is written by loovee ([luweicong@seeed.cc](luweicong@seeed.cc "luweicong@seeed.cc")) for seeed studio
142 | and is licensed under [The MIT License](http://opensource.org/licenses/mit-license.php). Check License.txt for more information.
143 | 144 | Contributing to this software is warmly welcomed. You can do this basically by
145 | [forking](https://help.github.com/articles/fork-a-repo), committing modifications and then [pulling requests](https://help.github.com/articles/using-pull-requests) (follow the links above
146 | for operating guide). Adding change log and your contact into file header is encouraged.
147 | Thanks for your contribution. 148 | 149 | Seeed Studio is an open hardware facilitation company based in Shenzhen, China.
150 | Benefiting from local manufacture power and convenient global logistic system,
151 | we integrate resources to serve new era of innovation. Seeed also works with
152 | global distributors and partners to push open hardware movement.
153 | 154 | 155 | 156 | 157 | 158 | 159 | [![Analytics](https://ga-beacon.appspot.com/UA-46589105-3/CAN_BUS_Shield)](https://github.com/igrigorik/ga-beacon) 160 | 161 | 162 | 172 | -------------------------------------------------------------------------------- /examples/receive_Blink/receive_Blink.ino: -------------------------------------------------------------------------------- 1 | // demo: CAN-BUS Shield, receive data with check mode 2 | // send data coming to fast, such as less than 10ms, you can use this way 3 | // loovee, 2014-6-13 4 | 5 | 6 | #include 7 | #include "mcp_can.h" 8 | 9 | 10 | // the cs pin of the version after v1.1 is default to D9 11 | // v0.9b and v1.0 is default D10 12 | const int SPI_CS_PIN = 9; 13 | const int LED=8; 14 | boolean ledON=1; 15 | MCP_CAN CAN(SPI_CS_PIN); // Set CS pin 16 | 17 | void setup() 18 | { 19 | Serial.begin(115200); 20 | pinMode(LED,OUTPUT); 21 | 22 | START_INIT: 23 | 24 | if(CAN_OK == CAN.begin(CAN_500KBPS)) // init can bus : baudrate = 500k 25 | { 26 | Serial.println("CAN BUS Shield init ok!"); 27 | } 28 | else 29 | { 30 | Serial.println("CAN BUS Shield init fail"); 31 | Serial.println("Init CAN BUS Shield again"); 32 | delay(100); 33 | goto START_INIT; 34 | } 35 | } 36 | 37 | 38 | void loop() 39 | { 40 | unsigned char len = 0; 41 | unsigned char buf[8]; 42 | 43 | if(CAN_MSGAVAIL == CAN.checkReceive()) // check if data coming 44 | { 45 | CAN.readMsgBuf(&len, buf); // read data, len: data length, buf: data buf 46 | 47 | unsigned char canId = CAN.getCanId(); 48 | 49 | Serial.println("-----------------------------"); 50 | Serial.println("get data from ID: "); 51 | Serial.println(canId); 52 | 53 | for(int i = 0; i 7 | #include "mcp_can.h" 8 | 9 | 10 | // the cs pin of the version after v1.1 is default to D9 11 | // v0.9b and v1.0 is default D10 12 | const int SPI_CS_PIN = 9; 13 | 14 | MCP_CAN CAN(SPI_CS_PIN); // Set CS pin 15 | 16 | void setup() 17 | { 18 | Serial.begin(115200); 19 | 20 | START_INIT: 21 | 22 | if(CAN_OK == CAN.begin(CAN_500KBPS)) // init can bus : baudrate = 500k 23 | { 24 | Serial.println("CAN BUS Shield init ok!"); 25 | } 26 | else 27 | { 28 | Serial.println("CAN BUS Shield init fail"); 29 | Serial.println("Init CAN BUS Shield again"); 30 | delay(100); 31 | goto START_INIT; 32 | } 33 | } 34 | 35 | 36 | void loop() 37 | { 38 | unsigned char len = 0; 39 | unsigned char buf[8]; 40 | 41 | if(CAN_MSGAVAIL == CAN.checkReceive()) // check if data coming 42 | { 43 | CAN.readMsgBuf(&len, buf); // read data, len: data length, buf: data buf 44 | 45 | unsigned long canId = CAN.getCanId(); 46 | 47 | Serial.println("-----------------------------"); 48 | Serial.print("get data from ID: "); 49 | Serial.println(canId, HEX); 50 | 51 | for(int i = 0; i20ms, or else you can use check mode 3 | // loovee, 2014-6-13 4 | 5 | #include 6 | #include "mcp_can.h" 7 | 8 | // the cs pin of the version after v1.1 is default to D9 9 | // v0.9b and v1.0 is default D10 10 | const int SPI_CS_PIN = 9; 11 | 12 | MCP_CAN CAN(SPI_CS_PIN); // Set CS pin 13 | 14 | 15 | unsigned char flagRecv = 0; 16 | unsigned char len = 0; 17 | unsigned char buf[8]; 18 | char str[20]; 19 | 20 | void setup() 21 | { 22 | Serial.begin(115200); 23 | 24 | START_INIT: 25 | 26 | if(CAN_OK == CAN.begin(CAN_500KBPS)) // init can bus : baudrate = 500k 27 | { 28 | Serial.println("CAN BUS Shield init ok!"); 29 | } 30 | else 31 | { 32 | Serial.println("CAN BUS Shield init fail"); 33 | Serial.println("Init CAN BUS Shield again"); 34 | delay(100); 35 | goto START_INIT; 36 | } 37 | 38 | attachInterrupt(0, MCP2515_ISR, FALLING); // start interrupt 39 | } 40 | 41 | void MCP2515_ISR() 42 | { 43 | flagRecv = 1; 44 | } 45 | 46 | void loop() 47 | { 48 | if(flagRecv) 49 | { // check if get data 50 | 51 | flagRecv = 0; // clear flag 52 | 53 | // iterate over all pending messages 54 | // If either the bus is saturated or the MCU is busy, 55 | // both RX buffers may be in use and reading a single 56 | // message does not clear the IRQ conditon. 57 | while (CAN_MSGAVAIL == CAN.checkReceive()) 58 | { 59 | // read data, len: data length, buf: data buf 60 | CAN.readMsgBuf(&len, buf); 61 | 62 | // print the data 63 | for(int i = 0; i 3 | #include 4 | 5 | // the cs pin of the version after v1.1 is default to D9 6 | // v0.9b and v1.0 is default D10 7 | const int SPI_CS_PIN = 9; 8 | 9 | MCP_CAN CAN(SPI_CS_PIN); // Set CS pin 10 | 11 | void setup() 12 | { 13 | Serial.begin(115200); 14 | 15 | START_INIT: 16 | 17 | if(CAN_OK == CAN.begin(CAN_500KBPS)) // init can bus : baudrate = 500k 18 | { 19 | Serial.println("CAN BUS Shield init ok!"); 20 | } 21 | else 22 | { 23 | Serial.println("CAN BUS Shield init fail"); 24 | Serial.println("Init CAN BUS Shield again"); 25 | delay(100); 26 | goto START_INIT; 27 | } 28 | } 29 | 30 | unsigned char stmp[8] = {0, 1, 2, 3, 4, 5, 6, 7}; 31 | void loop() 32 | { 33 | // send data: id = 0x00, standrad frame, data len = 8, stmp: data buf 34 | CAN.sendMsgBuf(0x00, 0, 8, stmp); 35 | delay(100); // send data per 100ms 36 | } 37 | 38 | /********************************************************************************************************* 39 | END FILE 40 | *********************************************************************************************************/ 41 | -------------------------------------------------------------------------------- /examples/send_Blink/send_Blink.ino: -------------------------------------------------------------------------------- 1 | // demo: CAN-BUS Shield, send data 2 | #include 3 | #include 4 | 5 | // the cs pin of the version after v1.1 is default to D9 6 | // v0.9b and v1.0 is default D10 7 | const int SPI_CS_PIN = 9; 8 | const int ledHIGH = 1; 9 | const int ledLOW = 0; 10 | 11 | MCP_CAN CAN(SPI_CS_PIN); // Set CS pin 12 | 13 | void setup() 14 | { 15 | Serial.begin(115200); 16 | 17 | START_INIT: 18 | 19 | if(CAN_OK == CAN.begin(CAN_500KBPS)) // init can bus : baudrate = 500k 20 | { 21 | Serial.println("CAN BUS Shield init ok!"); 22 | } 23 | else 24 | { 25 | Serial.println("CAN BUS Shield init fail"); 26 | Serial.println("Init CAN BUS Shield again"); 27 | delay(100); 28 | goto START_INIT; 29 | } 30 | } 31 | 32 | unsigned char stmp[8] = {ledHIGH, 1, 2, 3, ledLOW, 5, 6, 7}; 33 | 34 | void loop() 35 | { Serial.println("In loop"); 36 | // send data: id = 0x00, standrad frame, data len = 8, stmp: data buf 37 | CAN.sendMsgBuf(0x70,0, 8, stmp); 38 | delay(1000); // send data per 100ms 39 | } 40 | 41 | /********************************************************************************************************* 42 | END FILE 43 | *********************************************************************************************************/ 44 | -------------------------------------------------------------------------------- /examples/send_Blink_ROS/send_Blink_ROS.ino: -------------------------------------------------------------------------------- 1 | // demo: CAN-BUS Shield, send data 2 | // Hardware: TWO ArduinoMega with CAN-SHIELDS 3 | // Run this send_Blink_ROS.ino file on one of the Arduinos 4 | // Run receive_Blink on the other 5 | // ***ROS commands to be followe***// 6 | // roscore 7 | // rosrun roial_python serial_node.py /dev/ttyACM1 _baud:=57600 8 | // rostopic pub toggle_led std_msgs/Empty -r 100 9 | // Jaghvi: jaghvim@andrew.cmu.edu 10 | 11 | 12 | #include 13 | #include 14 | 15 | //ROS 16 | #include 17 | #include 18 | 19 | ros::NodeHandle nh; 20 | 21 | const int SPI_CS_PIN = 9; 22 | const int ledHIGH=1; 23 | const int ledLOW=0; 24 | unsigned char stmp[8] = {ledHIGH, 1, 2, 3, ledLOW, 5, 6, 7}; 25 | 26 | MCP_CAN CAN(SPI_CS_PIN); // Set CS pin 27 | 28 | void messageCb( const std_msgs::Empty& toggle_msg){ 29 | //digitalWrite(13, HIGH-digitalRead(13)); // blink the led 30 | // send data: id = 0x00, standrad frame, data len = 8, stmp: data buf 31 | CAN.sendMsgBuf(0x70,0, 8, stmp); 32 | delay(1000); // send data per 100ms 33 | } 34 | 35 | ros::Subscriber sub("toggle_led", &messageCb ); 36 | 37 | // the cs pin of the version after v1.1 is default to D9 38 | // v0.9b and v1.0 is default D10 39 | 40 | 41 | 42 | void setup() 43 | { 44 | Serial.begin(115200); 45 | nh.initNode(); 46 | nh.subscribe(sub); 47 | 48 | START_INIT: 49 | 50 | if(CAN_OK == CAN.begin(CAN_500KBPS)) // init can bus : baudrate = 500k 51 | { 52 | Serial.println("CAN BUS Shield init ok!"); 53 | } 54 | else 55 | { 56 | Serial.println("CAN BUS Shield init fail"); 57 | Serial.println("Init CAN BUS Shield again"); 58 | delay(100); 59 | goto START_INIT; 60 | } 61 | } 62 | 63 | 64 | void loop() 65 | { 66 | 67 | nh.spinOnce(); 68 | delay(1); 69 | } 70 | 71 | /********************************************************************************************************* 72 | END FILE 73 | *********************************************************************************************************/ 74 | -------------------------------------------------------------------------------- /examples/set_mask_filter_recv/set_mask_filter_recv.ino: -------------------------------------------------------------------------------- 1 | // demo: CAN-BUS Shield, receive data with interrupt mode, and set mask and filter 2 | // 3 | // when in interrupt mode, the data coming can't be too fast, must >20ms, or else you can use check mode 4 | // loovee, 2014-7-8 5 | 6 | #include 7 | #include "mcp_can.h" 8 | 9 | // the cs pin of the version after v1.1 is default to D9 10 | // v0.9b and v1.0 is default D10 11 | const int SPI_CS_PIN = 9; 12 | 13 | MCP_CAN CAN(SPI_CS_PIN); // Set CS pin 14 | 15 | 16 | unsigned char flagRecv = 0; 17 | unsigned char len = 0; 18 | unsigned char buf[8]; 19 | char str[20]; 20 | 21 | void setup() 22 | { 23 | Serial.begin(115200); 24 | 25 | START_INIT: 26 | 27 | if(CAN_OK == CAN.begin(CAN_500KBPS)) // init can bus : baudrate = 500k 28 | { 29 | Serial.println("CAN BUS Shield init ok!"); 30 | } 31 | else 32 | { 33 | Serial.println("CAN BUS Shield init fail"); 34 | Serial.println("Init CAN BUS Shield again"); 35 | delay(100); 36 | goto START_INIT; 37 | } 38 | 39 | attachInterrupt(0, MCP2515_ISR, FALLING); // start interrupt 40 | 41 | 42 | /* 43 | * set mask, set both the mask to 0x3ff 44 | */ 45 | CAN.init_Mask(0, 0, 0x3ff); // there are 2 mask in mcp2515, you need to set both of them 46 | CAN.init_Mask(1, 0, 0x3ff); 47 | 48 | 49 | /* 50 | * set filter, we can receive id from 0x04 ~ 0x09 51 | */ 52 | CAN.init_Filt(0, 0, 0x04); // there are 6 filter in mcp2515 53 | CAN.init_Filt(1, 0, 0x05); // there are 6 filter in mcp2515 54 | 55 | CAN.init_Filt(2, 0, 0x06); // there are 6 filter in mcp2515 56 | CAN.init_Filt(3, 0, 0x07); // there are 6 filter in mcp2515 57 | CAN.init_Filt(4, 0, 0x08); // there are 6 filter in mcp2515 58 | CAN.init_Filt(5, 0, 0x09); // there are 6 filter in mcp2515 59 | 60 | } 61 | 62 | void MCP2515_ISR() 63 | { 64 | flagRecv = 1; 65 | } 66 | 67 | void loop() 68 | { 69 | if(flagRecv) // check if get data 70 | { 71 | 72 | flagRecv = 0; // clear flag 73 | CAN.readMsgBuf(&len, buf); // read data, len: data length, buf: data buf 74 | 75 | Serial.println("\r\n------------------------------------------------------------------"); 76 | Serial.print("Get Data From id: "); 77 | Serial.println(CAN.getCanId()); 78 | for(int i = 0; i 5 | #include 6 | 7 | // the cs pin of the version after v1.1 is default to D9 8 | // v0.9b and v1.0 is default D10 9 | const int SPI_CS_PIN = 9; 10 | 11 | MCP_CAN CAN(SPI_CS_PIN); // Set CS pin 12 | 13 | void setup() 14 | { 15 | Serial.begin(115200); 16 | 17 | START_INIT: 18 | 19 | if(CAN_OK == CAN.begin(CAN_500KBPS)) // init can bus : baudrate = 500k 20 | { 21 | Serial.println("CAN BUS Shield init ok!"); 22 | } 23 | else 24 | { 25 | Serial.println("CAN BUS Shield init fail"); 26 | Serial.println("Init CAN BUS Shield again"); 27 | delay(100); 28 | goto START_INIT; 29 | } 30 | } 31 | 32 | unsigned char stmp[8] = {0, 1, 2, 3, 4, 5, 6, 7}; 33 | 34 | void loop() 35 | { 36 | for(int id=0; id<10; id++) 37 | { 38 | memset(stmp, id, sizeof(stmp)); // set id to send data buff 39 | CAN.sendMsgBuf(id, 0, sizeof(stmp), stmp); 40 | delay(100); 41 | } 42 | } 43 | 44 | /********************************************************************************************************* 45 | END FILE 46 | *********************************************************************************************************/ 47 | -------------------------------------------------------------------------------- /keywords.txt: -------------------------------------------------------------------------------- 1 | ####################################### 2 | # Syntax Coloring Map For debug_lvc 3 | ####################################### 4 | 5 | ####################################### 6 | # Datatypes (KEYWORD1) 7 | ####################################### 8 | MCP_CAN KEYWORD1 9 | mcp_can_dfs KEYWORD1 10 | mcp_can KEYWORD1 11 | 12 | ####################################### 13 | # Methods and Functions (KEYWORD2) 14 | ####################################### 15 | begin KEYWORD2 16 | init_Mask KEYWORD2 17 | init_Filt KEYWORD2 18 | sendMsgBuf KEYWORD2 19 | readMsgBuf KEYWORD2 20 | checkReceive KEYWORD2 21 | checkError KEYWORD2 22 | getCanId KEYWORD2 23 | 24 | ####################################### 25 | # Constants (LITERAL1) 26 | ####################################### 27 | CAN_5KBPS LITERAL1 28 | CAN_10KBPS LITERAL1 29 | CAN_20KBPS LITERAL1 30 | CAN_40KBPS LITERAL1 31 | CAN_50KBPS LITERAL1 32 | CAN_80KBPS LITERAL1 33 | CAN_100KBPS LITERAL1 34 | CAN_125KBPS LITERAL1 35 | CAN_200KBPS LITERAL1 36 | CAN_250KBPS LITERAL1 37 | CAN_500KBPS LITERAL1 38 | CAN_1000KBPS LITERAL1 39 | CAN_OK LITERAL1 40 | CAN_FAILINIT LITERAL1 41 | CAN_FAILTX LITERAL1 42 | CAN_MSGAVAIL LITERAL1 43 | CAN_NOMSG LITERAL1 44 | CAN_CTRLERROR LITERAL1 45 | CAN_GETTXBFTIMEOUT LITERAL1 46 | CAN_SENDMSGTIMEOUT LITERAL1 47 | CAN_FAIL LITERAL1 48 | -------------------------------------------------------------------------------- /mcp_can.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | mcp_can.cpp 3 | 2012 Copyright (c) Seeed Technology Inc. All right reserved. 4 | 2014 Copyright (c) Cory J. Fowler All Rights Reserved. 5 | 6 | Author: Loovee 7 | Contributor: Cory J. Fowler 8 | 2014-9-16 9 | This library is free software; you can redistribute it and/or 10 | modify it under the terms of the GNU Lesser General Public 11 | License as published by the Free Software Foundation; either 12 | version 2.1 of the License, or (at your option) any later version. 13 | 14 | This library is distributed in the hope that it will be useful, 15 | but WITHOUT ANY WARRANTY; without even the implied warranty of 16 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 17 | Lesser General Public License for more details. 18 | 19 | You should have received a copy of the GNU Lesser General Public 20 | License along with this library; if not, write to the Free Software 21 | Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110- 22 | 1301 USA 23 | */ 24 | #include "mcp_can.h" 25 | 26 | #define spi_readwrite SPI.transfer 27 | #define spi_read() spi_readwrite(0x00) 28 | 29 | /********************************************************************************************************* 30 | ** Function name: mcp2515_reset 31 | ** Descriptions: Performs a software reset 32 | *********************************************************************************************************/ 33 | void MCP_CAN::mcp2515_reset(void) 34 | { 35 | MCP2515_SELECT(); 36 | spi_readwrite(MCP_RESET); 37 | MCP2515_UNSELECT(); 38 | delay(10); 39 | } 40 | 41 | /********************************************************************************************************* 42 | ** Function name: mcp2515_readRegister 43 | ** Descriptions: Read data register 44 | *********************************************************************************************************/ 45 | INT8U MCP_CAN::mcp2515_readRegister(const INT8U address) 46 | { 47 | INT8U ret; 48 | 49 | MCP2515_SELECT(); 50 | spi_readwrite(MCP_READ); 51 | spi_readwrite(address); 52 | ret = spi_read(); 53 | MCP2515_UNSELECT(); 54 | 55 | return ret; 56 | } 57 | 58 | /********************************************************************************************************* 59 | ** Function name: mcp2515_readRegisterS 60 | ** Descriptions: Reads sucessive data registers 61 | *********************************************************************************************************/ 62 | void MCP_CAN::mcp2515_readRegisterS(const INT8U address, INT8U values[], const INT8U n) 63 | { 64 | INT8U i; 65 | MCP2515_SELECT(); 66 | spi_readwrite(MCP_READ); 67 | spi_readwrite(address); 68 | // mcp2515 has auto-increment of address-pointer 69 | for (i=0; i TXBnD7 */ 489 | a1 = MCP_TXB0CTRL; 490 | a2 = MCP_TXB1CTRL; 491 | a3 = MCP_TXB2CTRL; 492 | for (i = 0; i < 14; i++) { /* in-buffer loop */ 493 | mcp2515_setRegister(a1, 0); 494 | mcp2515_setRegister(a2, 0); 495 | mcp2515_setRegister(a3, 0); 496 | a1++; 497 | a2++; 498 | a3++; 499 | } 500 | mcp2515_setRegister(MCP_RXB0CTRL, 0); 501 | mcp2515_setRegister(MCP_RXB1CTRL, 0); 502 | } 503 | 504 | /********************************************************************************************************* 505 | ** Function name: mcp2515_init 506 | ** Descriptions: Initialize the controller 507 | *********************************************************************************************************/ 508 | INT8U MCP_CAN::mcp2515_init(const INT8U canSpeed, const INT8U clock) /* mcp2515init */ 509 | { 510 | return mcp2515_init(MCP_STDEXT, canSpeed, clock); 511 | } 512 | 513 | /********************************************************************************************************* 514 | ** Function name: mcp2515_init 515 | ** Descriptions: Initialize the controller 516 | *********************************************************************************************************/ 517 | INT8U MCP_CAN::mcp2515_init(const INT8U canIDMode, const INT8U canSpeed, const INT8U canClock) 518 | { 519 | 520 | INT8U res; 521 | 522 | mcp2515_reset(); 523 | 524 | mcpMode = MCP_LOOPBACK; 525 | 526 | res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); 527 | if(res > 0) 528 | { 529 | #if DEBUG_MODE 530 | Serial.print("Entering Configuration Mode Failure...\r\n"); 531 | #endif 532 | return res; 533 | } 534 | #if DEBUG_MODE 535 | Serial.print("Entering Configuration Mode Successful!\r\n"); 536 | #endif 537 | 538 | // Set Baudrate 539 | if(mcp2515_configRate(canSpeed, canClock)) 540 | { 541 | #if DEBUG_MODE 542 | Serial.print("Setting Baudrate Failure...\r\n"); 543 | #endif 544 | return res; 545 | } 546 | #if DEBUG_MODE 547 | Serial.print("Setting Baudrate Successful!\r\n"); 548 | #endif 549 | 550 | if ( res == MCP2515_OK ) { 551 | 552 | /* init canbuffers */ 553 | mcp2515_initCANBuffers(); 554 | 555 | /* interrupt mode */ 556 | mcp2515_setRegister(MCP_CANINTE, MCP_RX0IF | MCP_RX1IF); 557 | 558 | switch(canIDMode) 559 | { 560 | case (MCP_ANY): 561 | mcp2515_modifyRegister(MCP_RXB0CTRL, 562 | MCP_RXB_RX_MASK | MCP_RXB_BUKT_MASK, 563 | MCP_RXB_RX_ANY | MCP_RXB_BUKT_MASK); 564 | mcp2515_modifyRegister(MCP_RXB1CTRL, MCP_RXB_RX_MASK, 565 | MCP_RXB_RX_ANY); 566 | break; 567 | /* The followingn two functions of the MCP2515 do not work, there is a bug in the silicon. 568 | case (MCP_STD): 569 | mcp2515_modifyRegister(MCP_RXB0CTRL, 570 | MCP_RXB_RX_MASK | MCP_RXB_BUKT_MASK, 571 | MCP_RXB_RX_STD | MCP_RXB_BUKT_MASK ); 572 | mcp2515_modifyRegister(MCP_RXB1CTRL, MCP_RXB_RX_MASK, 573 | MCP_RXB_RX_STD); 574 | break; 575 | 576 | case (MCP_EXT): 577 | mcp2515_modifyRegister(MCP_RXB0CTRL, 578 | MCP_RXB_RX_MASK | MCP_RXB_BUKT_MASK, 579 | MCP_RXB_RX_EXT | MCP_RXB_BUKT_MASK ); 580 | mcp2515_modifyRegister(MCP_RXB1CTRL, MCP_RXB_RX_MASK, 581 | MCP_RXB_RX_EXT); 582 | break; 583 | */ 584 | case (MCP_STDEXT): 585 | mcp2515_modifyRegister(MCP_RXB0CTRL, 586 | MCP_RXB_RX_MASK | MCP_RXB_BUKT_MASK, 587 | MCP_RXB_RX_STDEXT | MCP_RXB_BUKT_MASK ); 588 | mcp2515_modifyRegister(MCP_RXB1CTRL, MCP_RXB_RX_MASK, 589 | MCP_RXB_RX_STDEXT); 590 | break; 591 | 592 | default: 593 | #if DEBUG_MODE 594 | Serial.print("`Setting ID Mode Failure...\r\n"); 595 | #endif 596 | return MCP2515_FAIL; 597 | break; 598 | } 599 | 600 | 601 | res = mcp2515_setCANCTRL_Mode(mcpMode); 602 | if(res) 603 | { 604 | #if DEBUG_MODE 605 | Serial.print("Returning to Previous Mode Failure...\r\n"); 606 | #endif 607 | return res; 608 | } 609 | 610 | } 611 | return res; 612 | 613 | } 614 | 615 | /********************************************************************************************************* 616 | ** Function name: mcp2515_write_id 617 | ** Descriptions: Write CAN ID 618 | *********************************************************************************************************/ 619 | void MCP_CAN::mcp2515_write_id( const INT8U mcp_addr, const INT8U ext, const INT32U id ) 620 | { 621 | uint16_t canid; 622 | INT8U tbufdata[4]; 623 | 624 | canid = (uint16_t)(id & 0x0FFFF); 625 | 626 | if ( ext == 1) 627 | { 628 | tbufdata[MCP_EID0] = (INT8U) (canid & 0xFF); 629 | tbufdata[MCP_EID8] = (INT8U) (canid >> 8); 630 | canid = (uint16_t)(id >> 16); 631 | tbufdata[MCP_SIDL] = (INT8U) (canid & 0x03); 632 | tbufdata[MCP_SIDL] += (INT8U) ((canid & 0x1C) << 3); 633 | tbufdata[MCP_SIDL] |= MCP_TXB_EXIDE_M; 634 | tbufdata[MCP_SIDH] = (INT8U) (canid >> 5 ); 635 | } 636 | else 637 | { 638 | tbufdata[MCP_SIDH] = (INT8U) (canid >> 3 ); 639 | tbufdata[MCP_SIDL] = (INT8U) ((canid & 0x07 ) << 5); 640 | tbufdata[MCP_EID0] = 0; 641 | tbufdata[MCP_EID8] = 0; 642 | } 643 | 644 | mcp2515_setRegisterS( mcp_addr, tbufdata, 4 ); 645 | } 646 | 647 | /********************************************************************************************************* 648 | ** Function name: mcp2515_write_mf 649 | ** Descriptions: Write Masks and Filters 650 | *********************************************************************************************************/ 651 | void MCP_CAN::mcp2515_write_mf( const INT8U mcp_addr, const INT8U ext, const INT32U id ) 652 | { 653 | uint16_t canid; 654 | INT8U tbufdata[4]; 655 | 656 | canid = (uint16_t)(id & 0x0FFFF); 657 | 658 | if ( ext == 1) 659 | { 660 | tbufdata[MCP_EID0] = (INT8U) (canid & 0xFF); 661 | tbufdata[MCP_EID8] = (INT8U) (canid >> 8); 662 | canid = (uint16_t)(id >> 16); 663 | tbufdata[MCP_SIDL] = (INT8U) (canid & 0x03); 664 | tbufdata[MCP_SIDL] += (INT8U) ((canid & 0x1C) << 3); 665 | tbufdata[MCP_SIDL] |= MCP_TXB_EXIDE_M; 666 | tbufdata[MCP_SIDH] = (INT8U) (canid >> 5 ); 667 | } 668 | else 669 | { 670 | tbufdata[MCP_EID0] = (INT8U) (canid & 0xFF); 671 | tbufdata[MCP_EID8] = (INT8U) (canid >> 8); 672 | canid = (uint16_t)(id >> 16); 673 | tbufdata[MCP_SIDL] = (INT8U) ((canid & 0x07) << 5); 674 | tbufdata[MCP_SIDH] = (INT8U) (canid >> 3 ); 675 | } 676 | 677 | mcp2515_setRegisterS( mcp_addr, tbufdata, 4 ); 678 | } 679 | 680 | /********************************************************************************************************* 681 | ** Function name: mcp2515_read_id 682 | ** Descriptions: Read CAN ID 683 | *********************************************************************************************************/ 684 | void MCP_CAN::mcp2515_read_id( const INT8U mcp_addr, INT8U* ext, INT32U* id ) 685 | { 686 | INT8U tbufdata[4]; 687 | 688 | *ext = 0; 689 | *id = 0; 690 | 691 | mcp2515_readRegisterS( mcp_addr, tbufdata, 4 ); 692 | 693 | *id = (tbufdata[MCP_SIDH]<<3) + (tbufdata[MCP_SIDL]>>5); 694 | 695 | if ( (tbufdata[MCP_SIDL] & MCP_TXB_EXIDE_M) == MCP_TXB_EXIDE_M ) 696 | { 697 | /* extended id */ 698 | *id = (*id<<2) + (tbufdata[MCP_SIDL] & 0x03); 699 | *id = (*id<<8) + tbufdata[MCP_EID8]; 700 | *id = (*id<<8) + tbufdata[MCP_EID0]; 701 | *ext = 1; 702 | } 703 | } 704 | 705 | /********************************************************************************************************* 706 | ** Function name: mcp2515_write_canMsg 707 | ** Descriptions: Write message 708 | *********************************************************************************************************/ 709 | void MCP_CAN::mcp2515_write_canMsg( const INT8U buffer_sidh_addr) 710 | { 711 | INT8U mcp_addr; 712 | mcp_addr = buffer_sidh_addr; 713 | mcp2515_setRegisterS(mcp_addr+5, m_nDta, m_nDlc ); /* write data bytes */ 714 | 715 | if ( m_nRtr == 1) /* if RTR set bit in byte */ 716 | m_nDlc |= MCP_RTR_MASK; 717 | 718 | mcp2515_setRegister((mcp_addr+4), m_nDlc ); /* write the RTR and DLC */ 719 | mcp2515_write_id(mcp_addr, m_nExtFlg, m_nID ); /* write CAN id */ 720 | 721 | } 722 | 723 | /********************************************************************************************************* 724 | ** Function name: mcp2515_read_canMsg 725 | ** Descriptions: Read message 726 | *********************************************************************************************************/ 727 | void MCP_CAN::mcp2515_read_canMsg( const INT8U buffer_sidh_addr) /* read can msg */ 728 | { 729 | INT8U mcp_addr, ctrl; 730 | 731 | mcp_addr = buffer_sidh_addr; 732 | 733 | mcp2515_read_id( mcp_addr, &m_nExtFlg,&m_nID ); 734 | 735 | ctrl = mcp2515_readRegister( mcp_addr-1 ); 736 | m_nDlc = mcp2515_readRegister( mcp_addr+4 ); 737 | 738 | if (ctrl & 0x08) 739 | m_nRtr = 1; 740 | else 741 | m_nRtr = 0; 742 | 743 | m_nDlc &= MCP_DLC_MASK; 744 | mcp2515_readRegisterS( mcp_addr+5, &(m_nDta[0]), m_nDlc ); 745 | } 746 | 747 | /********************************************************************************************************* 748 | ** Function name: mcp2515_start_transmit 749 | ** Descriptions: Start transmission 750 | *********************************************************************************************************/ 751 | void MCP_CAN::mcp2515_start_transmit(const INT8U mcp_addr) /* start transmit */ 752 | { 753 | mcp2515_modifyRegister( mcp_addr-1 , MCP_TXB_TXREQ_M, MCP_TXB_TXREQ_M ); 754 | } 755 | 756 | /********************************************************************************************************* 757 | ** Function name: mcp2515_getNextFreeTXBuf 758 | ** Descriptions: Send message 759 | *********************************************************************************************************/ 760 | INT8U MCP_CAN::mcp2515_getNextFreeTXBuf(INT8U *txbuf_n) /* get Next free txbuf */ 761 | { 762 | INT8U res, i, ctrlval; 763 | INT8U ctrlregs[MCP_N_TXBUFFERS] = { MCP_TXB0CTRL, MCP_TXB1CTRL, MCP_TXB2CTRL }; 764 | 765 | res = MCP_ALLTXBUSY; 766 | *txbuf_n = 0x00; 767 | 768 | /* check all 3 TX-Buffers */ 769 | for (i=0; i 0){ 829 | #if DEBUG_MODE 830 | Serial.print("Entering Configuration Mode Failure...\r\n"); 831 | #endif 832 | return res; 833 | } 834 | 835 | if (num == 0){ 836 | mcp2515_write_mf(MCP_RXM0SIDH, ext, ulData); 837 | 838 | } 839 | else if(num == 1){ 840 | mcp2515_write_mf(MCP_RXM1SIDH, ext, ulData); 841 | } 842 | else res = MCP2515_FAIL; 843 | 844 | res = mcp2515_setCANCTRL_Mode(mcpMode); 845 | if(res > 0){ 846 | #if DEBUG_MODE 847 | Serial.print("Entering Previous Mode Failure...\r\nSetting Mask Failure...\r\n"); 848 | #endif 849 | return res; 850 | } 851 | #if DEBUG_MODE 852 | Serial.print("Setting Mask Successful!\r\n"); 853 | #endif 854 | return res; 855 | } 856 | 857 | /********************************************************************************************************* 858 | ** Function name: init_Mask 859 | ** Descriptions: Public function to set mask(s). 860 | *********************************************************************************************************/ 861 | INT8U MCP_CAN::init_Mask(INT8U num, INT32U ulData) 862 | { 863 | INT8U res = MCP2515_OK; 864 | INT8U ext = 0; 865 | #if DEBUG_MODE 866 | Serial.print("Starting to Set Mask!\r\n"); 867 | #endif 868 | res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); 869 | if(res > 0){ 870 | #if DEBUG_MODE 871 | Serial.print("Entering Configuration Mode Failure...\r\n"); 872 | #endif 873 | return res; 874 | } 875 | 876 | if((num & 0x80000000) == 0x80000000) 877 | ext = 1; 878 | 879 | if (num == 0){ 880 | mcp2515_write_mf(MCP_RXM0SIDH, ext, ulData); 881 | 882 | } 883 | else if(num == 1){ 884 | mcp2515_write_mf(MCP_RXM1SIDH, ext, ulData); 885 | } 886 | else res = MCP2515_FAIL; 887 | 888 | res = mcp2515_setCANCTRL_Mode(mcpMode); 889 | if(res > 0){ 890 | #if DEBUG_MODE 891 | Serial.print("Entering Previous Mode Failure...\r\nSetting Mask Failure...\r\n"); 892 | #endif 893 | return res; 894 | } 895 | #if DEBUG_MODE 896 | Serial.print("Setting Mask Successful!\r\n"); 897 | #endif 898 | return res; 899 | } 900 | 901 | /********************************************************************************************************* 902 | ** Function name: init_Filt 903 | ** Descriptions: Public function to set filter(s). 904 | *********************************************************************************************************/ 905 | INT8U MCP_CAN::init_Filt(INT8U num, INT8U ext, INT32U ulData) 906 | { 907 | INT8U res = MCP2515_OK; 908 | #if DEBUG_MODE 909 | Serial.print("Starting to Set Filter!\r\n"); 910 | #endif 911 | res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); 912 | if(res > 0) 913 | { 914 | #if DEBUG_MODE 915 | Serial.print("Enter Configuration Mode Failure...\r\n"); 916 | #endif 917 | return res; 918 | } 919 | 920 | switch( num ) 921 | { 922 | case 0: 923 | mcp2515_write_mf(MCP_RXF0SIDH, ext, ulData); 924 | break; 925 | 926 | case 1: 927 | mcp2515_write_mf(MCP_RXF1SIDH, ext, ulData); 928 | break; 929 | 930 | case 2: 931 | mcp2515_write_mf(MCP_RXF2SIDH, ext, ulData); 932 | break; 933 | 934 | case 3: 935 | mcp2515_write_mf(MCP_RXF3SIDH, ext, ulData); 936 | break; 937 | 938 | case 4: 939 | mcp2515_write_mf(MCP_RXF4SIDH, ext, ulData); 940 | break; 941 | 942 | case 5: 943 | mcp2515_write_mf(MCP_RXF5SIDH, ext, ulData); 944 | break; 945 | 946 | default: 947 | res = MCP2515_FAIL; 948 | } 949 | 950 | res = mcp2515_setCANCTRL_Mode(mcpMode); 951 | if(res > 0) 952 | { 953 | #if DEBUG_MODE 954 | Serial.print("Entering Previous Mode Failure...\r\nSetting Filter Failure...\r\n"); 955 | #endif 956 | return res; 957 | } 958 | #if DEBUG_MODE 959 | Serial.print("Setting Filter Successfull!\r\n"); 960 | #endif 961 | 962 | return res; 963 | } 964 | 965 | /********************************************************************************************************* 966 | ** Function name: init_Filt 967 | ** Descriptions: Public function to set filter(s). 968 | *********************************************************************************************************/ 969 | INT8U MCP_CAN::init_Filt(INT8U num, INT32U ulData) 970 | { 971 | INT8U res = MCP2515_OK; 972 | INT8U ext = 0; 973 | 974 | #if DEBUG_MODE 975 | Serial.print("Starting to Set Filter!\r\n"); 976 | #endif 977 | res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); 978 | if(res > 0) 979 | { 980 | #if DEBUG_MODE 981 | Serial.print("Enter Configuration Mode Failure...\r\n"); 982 | #endif 983 | return res; 984 | } 985 | 986 | if((num & 0x80000000) == 0x80000000) 987 | ext = 1; 988 | 989 | switch( num ) 990 | { 991 | case 0: 992 | mcp2515_write_mf(MCP_RXF0SIDH, ext, ulData); 993 | break; 994 | 995 | case 1: 996 | mcp2515_write_mf(MCP_RXF1SIDH, ext, ulData); 997 | break; 998 | 999 | case 2: 1000 | mcp2515_write_mf(MCP_RXF2SIDH, ext, ulData); 1001 | break; 1002 | 1003 | case 3: 1004 | mcp2515_write_mf(MCP_RXF3SIDH, ext, ulData); 1005 | break; 1006 | 1007 | case 4: 1008 | mcp2515_write_mf(MCP_RXF4SIDH, ext, ulData); 1009 | break; 1010 | 1011 | case 5: 1012 | mcp2515_write_mf(MCP_RXF5SIDH, ext, ulData); 1013 | break; 1014 | 1015 | default: 1016 | res = MCP2515_FAIL; 1017 | } 1018 | 1019 | res = mcp2515_setCANCTRL_Mode(mcpMode); 1020 | if(res > 0) 1021 | { 1022 | #if DEBUG_MODE 1023 | Serial.print("Entering Previous Mode Failure...\r\nSetting Filter Failure...\r\n"); 1024 | #endif 1025 | return res; 1026 | } 1027 | #if DEBUG_MODE 1028 | Serial.print("Setting Filter Successfull!\r\n"); 1029 | #endif 1030 | 1031 | return res; 1032 | } 1033 | 1034 | /********************************************************************************************************* 1035 | ** Function name: setMsg 1036 | ** Descriptions: Set can message, such as dlc, id, dta[] and so on 1037 | *********************************************************************************************************/ 1038 | INT8U MCP_CAN::setMsg(INT32U id, INT8U ext, INT8U len, INT8U rtr, INT8U *pData) 1039 | { 1040 | int i = 0; 1041 | m_nID = id; 1042 | m_nRtr = rtr; 1043 | m_nExtFlg = ext; 1044 | m_nDlc = len; 1045 | for(i = 0; i 29 | #include 30 | #include 31 | 32 | #ifndef INT32U 33 | #define INT32U unsigned long 34 | #endif 35 | 36 | #ifndef INT8U 37 | #define INT8U byte 38 | #endif 39 | 40 | // if print debug information 41 | #define DEBUG_MODE 0 42 | 43 | /* 44 | * Begin mt 45 | */ 46 | #define TIMEOUTVALUE 50 47 | #define MCP_SIDH 0 48 | #define MCP_SIDL 1 49 | #define MCP_EID8 2 50 | #define MCP_EID0 3 51 | 52 | #define MCP_TXB_EXIDE_M 0x08 /* In TXBnSIDL */ 53 | #define MCP_DLC_MASK 0x0F /* 4 LSBits */ 54 | #define MCP_RTR_MASK 0x40 /* (1<<6) Bit 6 */ 55 | 56 | #define MCP_RXB_RX_ANY 0x60 57 | #define MCP_RXB_RX_EXT 0x40 58 | #define MCP_RXB_RX_STD 0x20 59 | #define MCP_RXB_RX_STDEXT 0x00 60 | #define MCP_RXB_RX_MASK 0x60 61 | #define MCP_RXB_BUKT_MASK (1<<2) 62 | 63 | /* 64 | ** Bits in the TXBnCTRL registers. 65 | */ 66 | #define MCP_TXB_TXBUFE_M 0x80 67 | #define MCP_TXB_ABTF_M 0x40 68 | #define MCP_TXB_MLOA_M 0x20 69 | #define MCP_TXB_TXERR_M 0x10 70 | #define MCP_TXB_TXREQ_M 0x08 71 | #define MCP_TXB_TXIE_M 0x04 72 | #define MCP_TXB_TXP10_M 0x03 73 | 74 | #define MCP_TXB_RTR_M 0x40 /* In TXBnDLC */ 75 | #define MCP_RXB_IDE_M 0x08 /* In RXBnSIDL */ 76 | #define MCP_RXB_RTR_M 0x40 /* In RXBnDLC */ 77 | 78 | #define MCP_STAT_RXIF_MASK (0x03) 79 | #define MCP_STAT_RX0IF (1<<0) 80 | #define MCP_STAT_RX1IF (1<<1) 81 | 82 | #define MCP_EFLG_RX1OVR (1<<7) 83 | #define MCP_EFLG_RX0OVR (1<<6) 84 | #define MCP_EFLG_TXBO (1<<5) 85 | #define MCP_EFLG_TXEP (1<<4) 86 | #define MCP_EFLG_RXEP (1<<3) 87 | #define MCP_EFLG_TXWAR (1<<2) 88 | #define MCP_EFLG_RXWAR (1<<1) 89 | #define MCP_EFLG_EWARN (1<<0) 90 | #define MCP_EFLG_ERRORMASK (0xF8) /* 5 MS-Bits */ 91 | 92 | 93 | /* 94 | * Define MCP2515 register addresses 95 | */ 96 | #define MCP_RXF0SIDH 0x00 97 | #define MCP_RXF0SIDL 0x01 98 | #define MCP_RXF0EID8 0x02 99 | #define MCP_RXF0EID0 0x03 100 | #define MCP_RXF1SIDH 0x04 101 | #define MCP_RXF1SIDL 0x05 102 | #define MCP_RXF1EID8 0x06 103 | #define MCP_RXF1EID0 0x07 104 | #define MCP_RXF2SIDH 0x08 105 | #define MCP_RXF2SIDL 0x09 106 | #define MCP_RXF2EID8 0x0A 107 | #define MCP_RXF2EID0 0x0B 108 | #define MCP_CANSTAT 0x0E 109 | #define MCP_CANCTRL 0x0F 110 | #define MCP_RXF3SIDH 0x10 111 | #define MCP_RXF3SIDL 0x11 112 | #define MCP_RXF3EID8 0x12 113 | #define MCP_RXF3EID0 0x13 114 | #define MCP_RXF4SIDH 0x14 115 | #define MCP_RXF4SIDL 0x15 116 | #define MCP_RXF4EID8 0x16 117 | #define MCP_RXF4EID0 0x17 118 | #define MCP_RXF5SIDH 0x18 119 | #define MCP_RXF5SIDL 0x19 120 | #define MCP_RXF5EID8 0x1A 121 | #define MCP_RXF5EID0 0x1B 122 | #define MCP_TEC 0x1C 123 | #define MCP_REC 0x1D 124 | #define MCP_RXM0SIDH 0x20 125 | #define MCP_RXM0SIDL 0x21 126 | #define MCP_RXM0EID8 0x22 127 | #define MCP_RXM0EID0 0x23 128 | #define MCP_RXM1SIDH 0x24 129 | #define MCP_RXM1SIDL 0x25 130 | #define MCP_RXM1EID8 0x26 131 | #define MCP_RXM1EID0 0x27 132 | #define MCP_CNF3 0x28 133 | #define MCP_CNF2 0x29 134 | #define MCP_CNF1 0x2A 135 | #define MCP_CANINTE 0x2B 136 | #define MCP_CANINTF 0x2C 137 | #define MCP_EFLG 0x2D 138 | #define MCP_TXB0CTRL 0x30 139 | #define MCP_TXB1CTRL 0x40 140 | #define MCP_TXB2CTRL 0x50 141 | #define MCP_RXB0CTRL 0x60 142 | #define MCP_RXB0SIDH 0x61 143 | #define MCP_RXB1CTRL 0x70 144 | #define MCP_RXB1SIDH 0x71 145 | 146 | 147 | #define MCP_TX_INT 0x1C // Enable all transmit interrup ts 148 | #define MCP_TX01_INT 0x0C // Enable TXB0 and TXB1 interru pts 149 | #define MCP_RX_INT 0x03 // Enable receive interrupts 150 | #define MCP_NO_INT 0x00 // Disable all interrupts 151 | 152 | #define MCP_TX01_MASK 0x14 153 | #define MCP_TX_MASK 0x54 154 | 155 | /* 156 | * Define SPI Instruction Set 157 | */ 158 | 159 | #define MCP_WRITE 0x02 160 | 161 | #define MCP_READ 0x03 162 | 163 | #define MCP_BITMOD 0x05 164 | 165 | #define MCP_LOAD_TX0 0x40 166 | #define MCP_LOAD_TX1 0x42 167 | #define MCP_LOAD_TX2 0x44 168 | 169 | #define MCP_RTS_TX0 0x81 170 | #define MCP_RTS_TX1 0x82 171 | #define MCP_RTS_TX2 0x84 172 | #define MCP_RTS_ALL 0x87 173 | 174 | #define MCP_READ_RX0 0x90 175 | #define MCP_READ_RX1 0x94 176 | 177 | #define MCP_READ_STATUS 0xA0 178 | 179 | #define MCP_RX_STATUS 0xB0 180 | 181 | #define MCP_RESET 0xC0 182 | 183 | 184 | /* 185 | * CANCTRL Register Values 186 | */ 187 | 188 | #define MODE_NORMAL 0x00 189 | #define MODE_SLEEP 0x20 190 | #define MODE_LOOPBACK 0x40 191 | #define MODE_LISTENONLY 0x60 192 | #define MCP_NORMAL 0x00 193 | #define MCP_SLEEP 0x20 194 | #define MCP_LOOPBACK 0x40 195 | #define MCP_LISTENONLY 0x60 196 | #define MODE_CONFIG 0x80 197 | #define MODE_POWERUP 0xE0 198 | #define MODE_MASK 0xE0 199 | #define ABORT_TX 0x10 200 | #define MODE_ONESHOT 0x08 201 | #define CLKOUT_ENABLE 0x04 202 | #define CLKOUT_DISABLE 0x00 203 | #define CLKOUT_PS1 0x00 204 | #define CLKOUT_PS2 0x01 205 | #define CLKOUT_PS4 0x02 206 | #define CLKOUT_PS8 0x03 207 | 208 | 209 | /* 210 | * CNF1 Register Values 211 | */ 212 | 213 | #define SJW1 0x00 214 | #define SJW2 0x40 215 | #define SJW3 0x80 216 | #define SJW4 0xC0 217 | 218 | 219 | /* 220 | * CNF2 Register Values 221 | */ 222 | 223 | #define BTLMODE 0x80 224 | #define SAMPLE_1X 0x00 225 | #define SAMPLE_3X 0x40 226 | 227 | 228 | /* 229 | * CNF3 Register Values 230 | */ 231 | 232 | #define SOF_ENABLE 0x80 233 | #define SOF_DISABLE 0x00 234 | #define WAKFIL_ENABLE 0x40 235 | #define WAKFIL_DISABLE 0x00 236 | 237 | 238 | /* 239 | * CANINTF Register Bits 240 | */ 241 | 242 | #define MCP_RX0IF 0x01 243 | #define MCP_RX1IF 0x02 244 | #define MCP_TX0IF 0x04 245 | #define MCP_TX1IF 0x08 246 | #define MCP_TX2IF 0x10 247 | #define MCP_ERRIF 0x20 248 | #define MCP_WAKIF 0x40 249 | #define MCP_MERRF 0x80 250 | 251 | /* 252 | * clock 253 | */ 254 | #define MCP_20MHz 1 255 | #define MCP_16MHz 2 256 | #define MCP_8MHz 3 257 | 258 | #define MCP_20MHZ MCP_20MHz 259 | #define MCP_16MHZ MCP_16MHz 260 | #define MCP_8MHZ MCP_8MHz 261 | 262 | /* 263 | * speed 16M 264 | */ 265 | #define MCP_16MHz_1000kBPS_CFG1 (0x00) 266 | #define MCP_16MHz_1000kBPS_CFG2 (0xD0) 267 | #define MCP_16MHz_1000kBPS_CFG3 (0x82) 268 | 269 | #define MCP_16MHz_500kBPS_CFG1 (0x00) 270 | #define MCP_16MHz_500kBPS_CFG2 (0xF0) 271 | #define MCP_16MHz_500kBPS_CFG3 (0x86) 272 | 273 | #define MCP_16MHz_250kBPS_CFG1 (0x41) 274 | #define MCP_16MHz_250kBPS_CFG2 (0xF1) 275 | #define MCP_16MHz_250kBPS_CFG3 (0x85) 276 | 277 | #define MCP_16MHz_200kBPS_CFG1 (0x01) 278 | #define MCP_16MHz_200kBPS_CFG2 (0xFA) 279 | #define MCP_16MHz_200kBPS_CFG3 (0x87) 280 | 281 | #define MCP_16MHz_125kBPS_CFG1 (0x03) 282 | #define MCP_16MHz_125kBPS_CFG2 (0xF0) 283 | #define MCP_16MHz_125kBPS_CFG3 (0x86) 284 | 285 | #define MCP_16MHz_100kBPS_CFG1 (0x03) 286 | #define MCP_16MHz_100kBPS_CFG2 (0xFA) 287 | #define MCP_16MHz_100kBPS_CFG3 (0x87) 288 | 289 | /* 290 | #define MCP_16MHz_100kBPS_CFG1 (0x03) 291 | #define MCP_16MHz_100kBPS_CFG2 (0xBA) 292 | #define MCP_16MHz_100kBPS_CFG3 (0x07) 293 | */ 294 | 295 | #define MCP_16MHz_95kBPS_CFG1 (0x03) 296 | #define MCP_16MHz_95kBPS_CFG2 (0xAD) 297 | #define MCP_16MHz_95kBPS_CFG3 (0x07) 298 | 299 | #define MCP_16MHz_83k3BPS_CFG1 (0x03) 300 | #define MCP_16MHz_83k3BPS_CFG2 (0xBE) 301 | #define MCP_16MHz_83k3BPS_CFG3 (0x07) 302 | 303 | #define MCP_16MHz_80kBPS_CFG1 (0x03) 304 | #define MCP_16MHz_80kBPS_CFG2 (0xFF) 305 | #define MCP_16MHz_80kBPS_CFG3 (0x87) 306 | 307 | #define MCP_16MHz_50kBPS_CFG1 (0x07) 308 | #define MCP_16MHz_50kBPS_CFG2 (0xFA) 309 | #define MCP_16MHz_50kBPS_CFG3 (0x87) 310 | 311 | #define MCP_16MHz_40kBPS_CFG1 (0x07) 312 | #define MCP_16MHz_40kBPS_CFG2 (0xFF) 313 | #define MCP_16MHz_40kBPS_CFG3 (0x87) 314 | 315 | #define MCP_16MHz_33k3BPS_CFG1 (0x4E) 316 | #define MCP_16MHz_33k3BPS_CFG2 (0xF1) 317 | #define MCP_16MHz_33k3BPS_CFG3 (0x85) 318 | 319 | #define MCP_16MHz_33kBPS_CFG1 (0x09) 320 | #define MCP_16MHz_33kBPS_CFG2 (0xBE) 321 | #define MCP_16MHz_33kBPS_CFG3 (0x07) 322 | 323 | #define MCP_16MHz_31k25BPS_CFG1 (0x0F) 324 | #define MCP_16MHz_31k25BPS_CFG2 (0xF1) 325 | #define MCP_16MHz_31k25BPS_CFG3 (0x85) 326 | 327 | #define MCP_16MHz_20kBPS_CFG1 (0x0F) 328 | #define MCP_16MHz_20kBPS_CFG2 (0xFF) 329 | #define MCP_16MHz_20kBPS_CFG3 (0x87) 330 | 331 | #define MCP_16MHz_10kBPS_CFG1 (0x1F) 332 | #define MCP_16MHz_10kBPS_CFG2 (0xFF) 333 | #define MCP_16MHz_10kBPS_CFG3 (0x87) 334 | 335 | #define MCP_16MHz_5kBPS_CFG1 (0x3F) 336 | #define MCP_16MHz_5kBPS_CFG2 (0xFF) 337 | #define MCP_16MHz_5kBPS_CFG3 (0x87) 338 | 339 | /* 340 | * speed 8M 341 | */ 342 | #define MCP_8MHz_1000kBPS_CFG1 (0x00) 343 | #define MCP_8MHz_1000kBPS_CFG2 (0x80) 344 | #define MCP_8MHz_1000kBPS_CFG3 (0x00) 345 | 346 | #define MCP_8MHz_500kBPS_CFG1 (0x00) 347 | #define MCP_8MHz_500kBPS_CFG2 (0x90) 348 | #define MCP_8MHz_500kBPS_CFG3 (0x02) 349 | 350 | #define MCP_8MHz_250kBPS_CFG1 (0x00) 351 | #define MCP_8MHz_250kBPS_CFG2 (0xb1) 352 | #define MCP_8MHz_250kBPS_CFG3 (0x05) 353 | 354 | #define MCP_8MHz_200kBPS_CFG1 (0x00) 355 | #define MCP_8MHz_200kBPS_CFG2 (0xb4) 356 | #define MCP_8MHz_200kBPS_CFG3 (0x06) 357 | 358 | #define MCP_8MHz_125kBPS_CFG1 (0x01) 359 | #define MCP_8MHz_125kBPS_CFG2 (0xb1) 360 | #define MCP_8MHz_125kBPS_CFG3 (0x05) 361 | 362 | #define MCP_8MHz_100kBPS_CFG1 (0x01) 363 | #define MCP_8MHz_100kBPS_CFG2 (0xb4) 364 | #define MCP_8MHz_100kBPS_CFG3 (0x06) 365 | 366 | #define MCP_8MHz_80kBPS_CFG1 (0x01) 367 | #define MCP_8MHz_80kBPS_CFG2 (0xbf) 368 | #define MCP_8MHz_80kBPS_CFG3 (0x07) 369 | 370 | #define MCP_8MHz_50kBPS_CFG1 (0x03) 371 | #define MCP_8MHz_50kBPS_CFG2 (0xb4) 372 | #define MCP_8MHz_50kBPS_CFG3 (0x06) 373 | 374 | #define MCP_8MHz_40kBPS_CFG1 (0x03) 375 | #define MCP_8MHz_40kBPS_CFG2 (0xbf) 376 | #define MCP_8MHz_40kBPS_CFG3 (0x07) 377 | 378 | #define MCP_8MHz_33k3BPS_CFG1 (0x47) 379 | #define MCP_8MHz_33k3BPS_CFG2 (0xE2) 380 | #define MCP_8MHz_33k3BPS_CFG3 (0x85) 381 | 382 | #define MCP_8MHz_31k25BPS_CFG1 (0x07) 383 | #define MCP_8MHz_31k25BPS_CFG2 (0xa4) 384 | #define MCP_8MHz_31k25BPS_CFG3 (0x04) 385 | 386 | #define MCP_8MHz_20kBPS_CFG1 (0x07) 387 | #define MCP_8MHz_20kBPS_CFG2 (0xbf) 388 | #define MCP_8MHz_20kBPS_CFG3 (0x07) 389 | 390 | #define MCP_8MHz_10kBPS_CFG1 (0x0f) 391 | #define MCP_8MHz_10kBPS_CFG2 (0xbf) 392 | #define MCP_8MHz_10kBPS_CFG3 (0x07) 393 | 394 | #define MCP_8MHz_5kBPS_CFG1 (0x1f) 395 | #define MCP_8MHz_5kBPS_CFG2 (0xbf) 396 | #define MCP_8MHz_5kBPS_CFG3 (0x07) 397 | 398 | /* 399 | * speed 20M 400 | */ 401 | #define MCP_20MHz_1000kBPS_CFG1 (0x00) 402 | #define MCP_20MHz_1000kBPS_CFG2 (0xD9) 403 | #define MCP_20MHz_1000kBPS_CFG3 (0x82) 404 | 405 | #define MCP_20MHz_500kBPS_CFG1 (0x00) 406 | #define MCP_20MHz_500kBPS_CFG2 (0xFA) 407 | #define MCP_20MHz_500kBPS_CFG3 (0x87) 408 | 409 | #define MCP_20MHz_250kBPS_CFG1 (0x41) 410 | #define MCP_20MHz_250kBPS_CFG2 (0xFB) 411 | #define MCP_20MHz_250kBPS_CFG3 (0x86) 412 | 413 | #define MCP_20MHz_200kBPS_CFG1 (0x01) 414 | #define MCP_20MHz_200kBPS_CFG2 (0xFF) 415 | #define MCP_20MHz_200kBPS_CFG3 (0x87) 416 | 417 | #define MCP_20MHz_125kBPS_CFG1 (0x03) 418 | #define MCP_20MHz_125kBPS_CFG2 (0xFA) 419 | #define MCP_20MHz_125kBPS_CFG3 (0x87) 420 | 421 | #define MCP_20MHz_100kBPS_CFG1 (0x04) 422 | #define MCP_20MHz_100kBPS_CFG2 (0xFA) 423 | #define MCP_20MHz_100kBPS_CFG3 (0x87) 424 | 425 | #define MCP_20MHz_80kBPS_CFG1 (0x04) 426 | #define MCP_20MHz_80kBPS_CFG2 (0xFF) 427 | #define MCP_20MHz_80kBPS_CFG3 (0x87) 428 | 429 | #define MCP_20MHz_50kBPS_CFG1 (0x09) 430 | #define MCP_20MHz_50kBPS_CFG2 (0xFA) 431 | #define MCP_20MHz_50kBPS_CFG3 (0x87) 432 | 433 | #define MCP_20MHz_40kBPS_CFG1 (0x09) 434 | #define MCP_20MHz_40kBPS_CFG2 (0xFF) 435 | #define MCP_20MHz_40kBPS_CFG3 (0x87) 436 | 437 | #define MCPDEBUG (0) 438 | #define MCPDEBUG_TXBUF (0) 439 | #define MCP_N_TXBUFFERS (3) 440 | 441 | #define MCP_RXBUF_0 (MCP_RXB0SIDH) 442 | #define MCP_RXBUF_1 (MCP_RXB1SIDH) 443 | 444 | //#define SPICS 10 445 | #define MCP2515_SELECT() digitalWrite(SPICS, LOW) 446 | #define MCP2515_UNSELECT() digitalWrite(SPICS, HIGH) 447 | 448 | #define MCP2515_OK (0) 449 | #define MCP2515_FAIL (1) 450 | #define MCP_ALLTXBUSY (2) 451 | 452 | #define CANDEBUG 1 453 | 454 | #define CANUSELOOP 0 455 | 456 | #define CANSENDTIMEOUT (200) /* milliseconds */ 457 | 458 | /* 459 | * initial value of gCANAutoProcess 460 | */ 461 | #define CANAUTOPROCESS (1) 462 | #define CANAUTOON (1) 463 | #define CANAUTOOFF (0) 464 | 465 | #define CAN_STDID (0) 466 | #define CAN_EXTID (1) 467 | 468 | #define MCP_STDEXT 0 /* Standard and Extended */ 469 | #define MCP_STD 1 /* Standard IDs ONLY */ 470 | #define MCP_EXT 2 /* Extended IDs ONLY */ 471 | #define MCP_ANY 3 /* Disables Masks and Filters */ 472 | 473 | #define CANDEFAULTIDENT (0x55CC) 474 | #define CANDEFAULTIDENTEXT (CAN_EXTID) 475 | 476 | #define CAN_4K096BPS 0 477 | #define CAN_5KBPS 1 478 | #define CAN_10KBPS 2 479 | #define CAN_20KBPS 3 480 | #define CAN_31K25BPS 4 481 | #define CAN_33KBPS 5 482 | #define CAN_33K3BPS 6 483 | #define CAN_40KBPS 7 484 | #define CAN_50KBPS 8 485 | #define CAN_80KBPS 9 486 | #define CAN_83K3BPS 10 487 | #define CAN_95KBPS 11 488 | #define CAN_100KBPS 12 489 | #define CAN_125KBPS 13 490 | #define CAN_200KBPS 14 491 | #define CAN_250KBPS 15 492 | #define CAN_500KBPS 16 493 | #define CAN_1000KBPS 17 494 | 495 | #define CAN_OK (0) 496 | #define CAN_FAILINIT (1) 497 | #define CAN_FAILTX (2) 498 | #define CAN_MSGAVAIL (3) 499 | #define CAN_NOMSG (4) 500 | #define CAN_CTRLERROR (5) 501 | #define CAN_GETTXBFTIMEOUT (6) 502 | #define CAN_SENDMSGTIMEOUT (7) 503 | #define CAN_FAIL (0xff) 504 | 505 | #endif 506 | /********************************************************************************************************* 507 | END FILE 508 | *********************************************************************************************************/ 509 | --------------------------------------------------------------------------------