├── CMakeLists.txt ├── LICENSE.md ├── README.md ├── can.h ├── keywords.txt ├── mcp2515.cpp └── mcp2515.h /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | idf_component_register(SRCS "mcp2515.cpp" INCLUDE_DIRS "." REQUIRES mcp2515) 2 | -------------------------------------------------------------------------------- /LICENSE.md: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2013 Seeed Technology Inc. 4 | Copyright (c) 2016 Dmitry 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy 7 | of this software and associated documentation files (the "Software"), to deal 8 | in the Software without restriction, including without limitation the rights 9 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 10 | copies of the Software, and to permit persons to whom the Software is 11 | furnished to do so, subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 18 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 19 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 20 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 21 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 22 | SOFTWARE. 23 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # esp32/esp8266 MCP2515 CAN interface library 2 | 3 | it's a fork of [Arduino MCP2515 CAN interface library](https://github.com/autowp/arduino-mcp2515) Adapted for use on esp32/esp8266. 4 | 5 | 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 gives your esp32/esp8266 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. 6 | 7 | - Implements CAN V2.0B at up to 1 Mb/s 8 | - SPI Interface up to 10 MHz 9 | - Standard (11 bit) and extended (29 bit) data and remote frames 10 | - Two receive buffers with prioritized message storage 11 | 12 | **Contents:** 13 | * [Hardware](#hardware) 14 | * [CAN Shield](#can-shield) 15 | * [Software Usage](#software-usage) 16 | * [Initialization](#initialization) 17 | * [Frame data format](#frame-data-format) 18 | * [Send Data](#send-data) 19 | * [Receive Data](#receive-data) 20 | * [Set Receive Mask and Filter](#set-receive-mask-and-filter) 21 | * [Examples](#examples) 22 | 23 | # Hardware: 24 | 25 | ## CAN Shield 26 | 27 | The following code samples uses the CAN-BUS Shield, wired up as shown: 28 | 29 | Component References: 30 | * [MCP2515](https://www.microchip.com/wwwproducts/en/MCP2515) Stand-Alone CAN Controller with SPI Interface 31 | * [MCP2551](https://www.microchip.com/wwwproducts/en/MCP2551) High-speed CAN Transceiver - pictured above, however "not recommended for new designs" 32 | * [MCP2562](https://www.microchip.com/wwwproducts/en/MCP2562) High-speed CAN Transceiver with Standby Mode and VIO Pin - an updated tranceiver since the _MCP2551_ (requires different wiring, read datasheet for example, also [here](https://fragmuffin.github.io/howto-micropython/slides/index.html#/7/5)) 33 | * [TJA1055](https://www.nxp.com/docs/en/data-sheet/TJA1055.pdf) Fault-tolerant low speed CAN Transceiver. Mostly used in vehicles. 34 | 35 | 36 | # Software Usage: 37 | 38 | ## Initialization 39 | 40 | The available modes are listed as follows: 41 | ```C++ 42 | mcp2515.setNormalMode(); 43 | mcp2515.setLoopbackMode(); 44 | mcp2515.setListenOnlyMode(); 45 | ``` 46 | 47 | The available baudrates are listed as follows: 48 | ```C++ 49 | enum CAN_SPEED { 50 | CAN_5KBPS, 51 | CAN_10KBPS, 52 | CAN_20KBPS, 53 | CAN_31K25BPS, 54 | CAN_33KBPS, 55 | CAN_40KBPS, 56 | CAN_50KBPS, 57 | CAN_80KBPS, 58 | CAN_83K3BPS, 59 | CAN_95KBPS, 60 | CAN_100KBPS, 61 | CAN_125KBPS, 62 | CAN_200KBPS, 63 | CAN_250KBPS, 64 | CAN_500KBPS, 65 | CAN_1000KBPS 66 | }; 67 | ``` 68 | 69 | 70 | Example of initialization 71 | 72 | ```C++ 73 | MCP2515 mcp2515(&spi); 74 | mcp2515.reset(); 75 | mcp2515.setBitrate(CAN_125KBPS); 76 | mcp2515.setLoopbackMode(); 77 | ``` 78 | 79 | You can also set oscillator frequency for module when setting bitrate: 80 | 81 | ```C++ 82 | mcp2515.setBitrate(CAN_125KBPS, MCP_8MHZ); 83 | ``` 84 | 85 | The available clock speeds are listed as follows: 86 | 87 | ```C++ 88 | enum CAN_CLOCK { 89 | MCP_20MHZ, 90 | MCP_16MHZ, 91 | MCP_8MHZ 92 | }; 93 | ``` 94 | 95 | Default value is MCP_16MHZ 96 | 97 | Note: To transfer data on high speed of CAN interface via UART dont forget to update UART baudrate as necessary. 98 | 99 | ## Frame data format 100 | 101 | Library uses Linux-like structure to store can frames; 102 | 103 | ```C++ 104 | struct can_frame { 105 | uint32_t can_id; /* 32 bit CAN_ID + EFF/RTR/ERR flags */ 106 | uint8_t can_dlc; 107 | uint8_t data[8]; 108 | }; 109 | ``` 110 | 111 | For additional information see [SocketCAN](https://www.kernel.org/doc/Documentation/networking/can.txt) 112 | 113 | ## Send Data 114 | 115 | ```C++ 116 | MCP2515::ERROR sendMessage(const MCP2515::TXBn txbn, const struct can_frame *frame); 117 | MCP2515::ERROR sendMessage(const struct can_frame *frame); 118 | ``` 119 | 120 | This is a function to send data onto the bus. 121 | 122 | For example, In the 'send' example, we have: 123 | 124 | ```C++ 125 | struct can_frame frame; 126 | frame.can_id = 0x000; 127 | frame.can_dlc = 4; 128 | frame.data[0] = 0xFF; 129 | frame.data[1] = 0xFF; 130 | frame.data[2] = 0xFF; 131 | frame.data[3] = 0xFF; 132 | 133 | /* send out the message to the bus and 134 | tell other devices this is a standard frame from 0x00. */ 135 | mcp2515.sendMessage(&frame); 136 | ``` 137 | 138 | ```C++ 139 | struct can_frame frame; 140 | frame.can_id = 0x12345678 | CAN_EFF_FLAG; 141 | frame.can_dlc = 2; 142 | frame.data[0] = 0xFF; 143 | frame.data[1] = 0xFF; 144 | 145 | /* send out the message to the bus using second TX buffer and 146 | tell other devices this is a extended frame from 0x12345678. */ 147 | mcp2515.sendMessage(MCP2515::TXB1, &frame); 148 | ``` 149 | 150 | 151 | 152 | ## Receive Data 153 | 154 | The following function is used to receive data on the 'receive' node: 155 | 156 | ```C++ 157 | MCP2515::ERROR readMessage(const MCP2515::RXBn rxbn, struct can_frame *frame); 158 | MCP2515::ERROR readMessage(struct can_frame *frame); 159 | ``` 160 | 161 | In conditions that masks and filters have been set. This function can only get frames that meet the requirements of masks and filters. 162 | 163 | You can choise one of two method to receive: interrupt-based and polling 164 | 165 | Example of poll read 166 | 167 | ```C++ 168 | struct can_frame frame; 169 | 170 | void loop() { 171 | if (mcp2515.readMessage(&frame) == MCP2515::ERROR_OK) { 172 | // frame contains received message 173 | } 174 | } 175 | ``` 176 | 177 | Example of interrupt based read 178 | 179 | ```C++ 180 | bool interrupt = false; 181 | struct can_frame frame; 182 | 183 | void irqHandler() { 184 | interrupt = true; 185 | } 186 | 187 | void setup() { 188 | ... 189 | attachInterrupt(0, irqHandler, FALLING); 190 | } 191 | 192 | void loop() { 193 | if (interrupt) { 194 | interrupt = false; 195 | 196 | uint8_t irq = mcp2515.getInterrupts(); 197 | 198 | if (irq & MCP2515::CANINTF_RX0IF) { 199 | if (mcp2515.readMessage(MCP2515::RXB0, &frame) == MCP2515::ERROR_OK) { 200 | // frame contains received from RXB0 message 201 | } 202 | } 203 | 204 | if (irq & MCP2515::CANINTF_RX1IF) { 205 | if (mcp2515.readMessage(MCP2515::RXB1, &frame) == MCP2515::ERROR_OK) { 206 | // frame contains received from RXB1 message 207 | } 208 | } 209 | } 210 | } 211 | ``` 212 | 213 | 214 | ## Set Receive Mask and Filter 215 | 216 | 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. 217 | 218 | We provide two functions for you to utilize these mask and filter registers. They are: 219 | 220 | ```C++ 221 | MCP2515::ERROR setFilterMask(const MASK mask, const bool ext, const uint32_t ulData) 222 | MCP2515::ERROR setFilter(const RXF num, const bool ext, const uint32_t ulData) 223 | ``` 224 | 225 | **MASK mask** represents one of two mask **MCP2515::MASK0** or **MCP2515::MASK1** 226 | 227 | **RXF num** represents one of six acceptance filters registers from **MCP2515::RXF0** to **MCP2515::RXF5** 228 | 229 | **ext** represents the status of the frame. **false** means it's a mask or filter for a standard frame. **true** means it's for a extended frame. 230 | 231 | **ulData** represents the content of the mask of filter. 232 | 233 | 234 | ## Examples 235 | 236 | Example implementation of CanHacker (lawicel) protocol based device: [https://github.com/autowp/can-usb](https://github.com/autowp/can-usb) 237 | 238 | 239 | For more information, please refer to [wiki page](http://www.seeedstudio.com/wiki/CAN-BUS_Shield) . 240 | 241 | ---- 242 | 243 | This software is written by loovee ([luweicong@seeed.cc](luweicong@seeed.cc "luweicong@seeed.cc")) for seeed studio 244 | Updated by Dmitry ([https://github.com/autowp](https://github.com/autowp "https://github.com/autowp")) 245 | Adapted for use on esp32/esp8266 by dedal.qq ([https://github.com/dedalqq](https://github.com/dedalqq "https://github.com/dedalqq")) 246 | and is licensed under [The MIT License](http://opensource.org/licenses/mit-license.php). Check [LICENSE.md](LICENSE.md) for more information. 247 | 248 | Contributing to this software is warmly welcomed. You can do this basically by 249 | [forking](https://help.github.com/articles/fork-a-repo), committing modifications and then 250 | [pulling requests](https://help.github.com/articles/using-pull-requests) (follow the links above 251 | for operating guide). Adding change log and your contact into file header is encouraged. 252 | Thanks for your contribution. 253 | 254 | Seeed Studio is an open hardware facilitation company based in Shenzhen, China. 255 | Benefiting from local manufacture power and convenient global logistic system, 256 | we integrate resources to serve new era of innovation. Seeed also works with 257 | global distributors and partners to push open hardware movement. 258 | -------------------------------------------------------------------------------- /can.h: -------------------------------------------------------------------------------- 1 | #ifndef CAN_H_ 2 | #define CAN_H_ 3 | 4 | #include 5 | 6 | 7 | typedef unsigned char __u8; 8 | typedef unsigned short __u16; 9 | typedef unsigned long __u32; 10 | 11 | 12 | /* special address description flags for the CAN_ID */ 13 | #define CAN_EFF_FLAG 0x80000000UL /* EFF/SFF is set in the MSB */ 14 | #define CAN_RTR_FLAG 0x40000000UL /* remote transmission request */ 15 | #define CAN_ERR_FLAG 0x20000000UL /* error message frame */ 16 | 17 | /* valid bits in CAN ID for frame formats */ 18 | #define CAN_SFF_MASK 0x000007FFUL /* standard frame format (SFF) */ 19 | #define CAN_EFF_MASK 0x1FFFFFFFUL /* extended frame format (EFF) */ 20 | #define CAN_ERR_MASK 0x1FFFFFFFUL /* omit EFF, RTR, ERR flags */ 21 | 22 | /* 23 | * Controller Area Network Identifier structure 24 | * 25 | * bit 0-28 : CAN identifier (11/29 bit) 26 | * bit 29 : error message frame flag (0 = data frame, 1 = error message) 27 | * bit 30 : remote transmission request flag (1 = rtr frame) 28 | * bit 31 : frame format flag (0 = standard 11 bit, 1 = extended 29 bit) 29 | */ 30 | typedef __u32 canid_t; 31 | 32 | #define CAN_SFF_ID_BITS 11 33 | #define CAN_EFF_ID_BITS 29 34 | 35 | /* CAN payload length and DLC definitions according to ISO 11898-1 */ 36 | #define CAN_MAX_DLC 8 37 | #define CAN_MAX_DLEN 8 38 | 39 | struct can_frame { 40 | canid_t can_id; /* 32 bit CAN_ID + EFF/RTR/ERR flags */ 41 | __u8 can_dlc; /* frame payload length in byte (0 .. CAN_MAX_DLEN) */ 42 | __u8 data[CAN_MAX_DLEN] __attribute__((aligned(8))); 43 | }; 44 | 45 | #endif /* CAN_H_ */ 46 | -------------------------------------------------------------------------------- /keywords.txt: -------------------------------------------------------------------------------- 1 | MCP2515 KEYWORD1 2 | 3 | CAN_5KBPS LITERAL1 4 | CAN_10KBPS LITERAL1 5 | CAN_20KBPS LITERAL1 6 | CAN_40KBPS LITERAL1 7 | CAN_50KBPS LITERAL1 8 | CAN_80KBPS LITERAL1 9 | CAN_100KBPS LITERAL1 10 | CAN_125KBPS LITERAL1 11 | CAN_200KBPS LITERAL1 12 | CAN_250KBPS LITERAL1 13 | CAN_500KBPS LITERAL1 14 | CAN_1000KBPS LITERAL1 15 | -------------------------------------------------------------------------------- /mcp2515.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include "freertos/FreeRTOS.h" 4 | #include "freertos/task.h" 5 | 6 | #include "mcp2515.h" 7 | 8 | const struct MCP2515::TXBn_REGS MCP2515::TXB[MCP2515::N_TXBUFFERS] = { 9 | {MCP_TXB0CTRL, MCP_TXB0SIDH, MCP_TXB0DATA}, 10 | {MCP_TXB1CTRL, MCP_TXB1SIDH, MCP_TXB1DATA}, 11 | {MCP_TXB2CTRL, MCP_TXB2SIDH, MCP_TXB2DATA} 12 | }; 13 | 14 | const struct MCP2515::RXBn_REGS MCP2515::RXB[N_RXBUFFERS] = { 15 | {MCP_RXB0CTRL, MCP_RXB0SIDH, MCP_RXB0DATA, CANINTF_RX0IF}, 16 | {MCP_RXB1CTRL, MCP_RXB1SIDH, MCP_RXB1DATA, CANINTF_RX1IF} 17 | }; 18 | 19 | MCP2515::MCP2515(spi_device_handle_t *s) 20 | { 21 | spi = s; 22 | } 23 | 24 | MCP2515::ERROR MCP2515::reset(void) 25 | { 26 | // startSPI(); 27 | // SPI.transfer(INSTRUCTION_RESET); 28 | // endSPI(); 29 | 30 | spi_transaction_t trans = {}; 31 | 32 | trans.length = 8; 33 | trans.flags = SPI_TRANS_USE_RXDATA | SPI_TRANS_USE_TXDATA; 34 | trans.tx_data[0] = INSTRUCTION_RESET; 35 | 36 | esp_err_t ret = spi_device_transmit(*spi, &trans); 37 | if (ret != ESP_OK) { 38 | printf("spi_device_transmit failed\n"); 39 | } 40 | 41 | vTaskDelay(10 / portTICK_RATE_MS); 42 | 43 | uint8_t zeros[14]; 44 | memset(zeros, 0, sizeof(zeros)); 45 | setRegisters(MCP_TXB0CTRL, zeros, 14); 46 | setRegisters(MCP_TXB1CTRL, zeros, 14); 47 | setRegisters(MCP_TXB2CTRL, zeros, 14); 48 | 49 | setRegister(MCP_RXB0CTRL, 0); 50 | setRegister(MCP_RXB1CTRL, 0); 51 | 52 | setRegister(MCP_CANINTE, CANINTF_RX0IF | CANINTF_RX1IF | CANINTF_ERRIF | CANINTF_MERRF); 53 | 54 | // receives all valid messages using either Standard or Extended Identifiers that 55 | // meet filter criteria. RXF0 is applied for RXB0, RXF1 is applied for RXB1 56 | modifyRegister(MCP_RXB0CTRL, 57 | RXBnCTRL_RXM_MASK | RXB0CTRL_BUKT | RXB0CTRL_FILHIT_MASK, 58 | RXBnCTRL_RXM_STDEXT | RXB0CTRL_BUKT | RXB0CTRL_FILHIT); 59 | modifyRegister(MCP_RXB1CTRL, 60 | RXBnCTRL_RXM_MASK | RXB1CTRL_FILHIT_MASK, 61 | RXBnCTRL_RXM_STDEXT | RXB1CTRL_FILHIT); 62 | 63 | // clear filters and masks 64 | // do not filter any standard frames for RXF0 used by RXB0 65 | // do not filter any extended frames for RXF1 used by RXB1 66 | RXF filters[] = {RXF0, RXF1, RXF2, RXF3, RXF4, RXF5}; 67 | for (int i=0; i<6; i++) { 68 | bool ext = (i == 1); 69 | ERROR result = setFilter(filters[i], ext, 0); 70 | if (result != ERROR_OK) { 71 | return result; 72 | } 73 | } 74 | 75 | MASK masks[] = {MASK0, MASK1}; 76 | for (int i=0; i<2; i++) { 77 | ERROR result = setFilterMask(masks[i], true, 0); 78 | if (result != ERROR_OK) { 79 | return result; 80 | } 81 | } 82 | 83 | return ERROR_OK; 84 | } 85 | 86 | uint8_t MCP2515::readRegister(const REGISTER reg) 87 | { 88 | // startSPI(); 89 | // SPI.transfer(INSTRUCTION_READ); 90 | // SPI.transfer(reg); 91 | // uint8_t ret = SPI.transfer(0x00); 92 | // endSPI(); 93 | // 94 | // return ret; 95 | 96 | spi_transaction_t trans = {}; 97 | 98 | trans.length = 24; 99 | trans.flags = SPI_TRANS_USE_RXDATA | SPI_TRANS_USE_TXDATA; 100 | trans.tx_data[0] = INSTRUCTION_READ; 101 | trans.tx_data[1] = reg; 102 | trans.tx_data[2] = 0x00; 103 | 104 | esp_err_t ret = spi_device_transmit(*spi, &trans); 105 | if (ret != ESP_OK) { 106 | printf("spi_device_transmit failed\n"); 107 | } 108 | 109 | return trans.rx_data[2]; 110 | } 111 | 112 | void MCP2515::readRegisters(const REGISTER reg, uint8_t values[], const uint8_t n) 113 | { 114 | // startSPI(); 115 | // SPI.transfer(INSTRUCTION_READ); 116 | // SPI.transfer(reg); 117 | // // mcp2515 has auto-increment of address-pointer 118 | // for (uint8_t i=0; i> 8); 616 | canid = (uint16_t)(id >> 16); 617 | buffer[MCP_SIDL] = (uint8_t) (canid & 0x03); 618 | buffer[MCP_SIDL] += (uint8_t) ((canid & 0x1C) << 3); 619 | buffer[MCP_SIDL] |= TXB_EXIDE_MASK; 620 | buffer[MCP_SIDH] = (uint8_t) (canid >> 5); 621 | } else { 622 | buffer[MCP_SIDH] = (uint8_t) (canid >> 3); 623 | buffer[MCP_SIDL] = (uint8_t) ((canid & 0x07 ) << 5); 624 | buffer[MCP_EID0] = 0; 625 | buffer[MCP_EID8] = 0; 626 | } 627 | } 628 | 629 | MCP2515::ERROR MCP2515::setFilterMask(const MASK mask, const bool ext, const uint32_t ulData) 630 | { 631 | ERROR res = setConfigMode(); 632 | if (res != ERROR_OK) { 633 | return res; 634 | } 635 | 636 | uint8_t tbufdata[4]; 637 | prepareId(tbufdata, ext, ulData); 638 | 639 | REGISTER reg; 640 | switch (mask) { 641 | case MASK0: reg = MCP_RXM0SIDH; break; 642 | case MASK1: reg = MCP_RXM1SIDH; break; 643 | default: 644 | return ERROR_FAIL; 645 | } 646 | 647 | setRegisters(reg, tbufdata, 4); 648 | 649 | return ERROR_OK; 650 | } 651 | 652 | MCP2515::ERROR MCP2515::setFilter(const RXF num, const bool ext, const uint32_t ulData) 653 | { 654 | ERROR res = setConfigMode(); 655 | if (res != ERROR_OK) { 656 | return res; 657 | } 658 | 659 | REGISTER reg; 660 | 661 | switch (num) { 662 | case RXF0: reg = MCP_RXF0SIDH; break; 663 | case RXF1: reg = MCP_RXF1SIDH; break; 664 | case RXF2: reg = MCP_RXF2SIDH; break; 665 | case RXF3: reg = MCP_RXF3SIDH; break; 666 | case RXF4: reg = MCP_RXF4SIDH; break; 667 | case RXF5: reg = MCP_RXF5SIDH; break; 668 | default: 669 | return ERROR_FAIL; 670 | } 671 | 672 | uint8_t tbufdata[4]; 673 | prepareId(tbufdata, ext, ulData); 674 | setRegisters(reg, tbufdata, 4); 675 | 676 | return ERROR_OK; 677 | } 678 | 679 | MCP2515::ERROR MCP2515::sendMessage(const TXBn txbn, const struct can_frame *frame) 680 | { 681 | if (frame->can_dlc > CAN_MAX_DLEN) { 682 | return ERROR_FAILTX; 683 | } 684 | 685 | const struct TXBn_REGS *txbuf = &TXB[txbn]; 686 | 687 | uint8_t data[13]; 688 | 689 | bool ext = (frame->can_id & CAN_EFF_FLAG); 690 | bool rtr = (frame->can_id & CAN_RTR_FLAG); 691 | uint32_t id = (frame->can_id & (ext ? CAN_EFF_MASK : CAN_SFF_MASK)); 692 | 693 | prepareId(data, ext, id); 694 | 695 | data[MCP_DLC] = rtr ? (frame->can_dlc | RTR_MASK) : frame->can_dlc; 696 | 697 | memcpy(&data[MCP_DATA], frame->data, frame->can_dlc); 698 | 699 | setRegisters(txbuf->SIDH, data, 5 + frame->can_dlc); 700 | 701 | modifyRegister(txbuf->CTRL, TXB_TXREQ, TXB_TXREQ); 702 | 703 | uint8_t ctrl = readRegister(txbuf->CTRL); 704 | if ((ctrl & (TXB_ABTF | TXB_MLOA | TXB_TXERR)) != 0) { 705 | return ERROR_FAILTX; 706 | } 707 | return ERROR_OK; 708 | } 709 | 710 | MCP2515::ERROR MCP2515::sendMessage(const struct can_frame *frame) 711 | { 712 | if (frame->can_dlc > CAN_MAX_DLEN) { 713 | return ERROR_FAILTX; 714 | } 715 | 716 | TXBn txBuffers[N_TXBUFFERS] = {TXB0, TXB1, TXB2}; 717 | 718 | for (int i=0; iCTRL); 721 | if ( (ctrlval & TXB_TXREQ) == 0 ) { 722 | return sendMessage(txBuffers[i], frame); 723 | } 724 | } 725 | 726 | return ERROR_ALLTXBUSY; 727 | } 728 | 729 | MCP2515::ERROR MCP2515::readMessage(const RXBn rxbn, struct can_frame *frame) 730 | { 731 | const struct RXBn_REGS *rxb = &RXB[rxbn]; 732 | 733 | uint8_t tbufdata[5]; 734 | 735 | readRegisters(rxb->SIDH, tbufdata, 5); 736 | 737 | uint32_t id = (tbufdata[MCP_SIDH]<<3) + (tbufdata[MCP_SIDL]>>5); 738 | 739 | if ( (tbufdata[MCP_SIDL] & TXB_EXIDE_MASK) == TXB_EXIDE_MASK ) { 740 | id = (id<<2) + (tbufdata[MCP_SIDL] & 0x03); 741 | id = (id<<8) + tbufdata[MCP_EID8]; 742 | id = (id<<8) + tbufdata[MCP_EID0]; 743 | id |= CAN_EFF_FLAG; 744 | } 745 | 746 | uint8_t dlc = (tbufdata[MCP_DLC] & DLC_MASK); 747 | if (dlc > CAN_MAX_DLEN) { 748 | return ERROR_FAIL; 749 | } 750 | 751 | uint8_t ctrl = readRegister(rxb->CTRL); 752 | if (ctrl & RXBnCTRL_RTR) { 753 | id |= CAN_RTR_FLAG; 754 | } 755 | 756 | frame->can_id = id; 757 | frame->can_dlc = dlc; 758 | 759 | readRegisters(rxb->DATA, frame->data, dlc); 760 | 761 | modifyRegister(MCP_CANINTF, rxb->CANINTF_RXnIF, 0); 762 | 763 | return ERROR_OK; 764 | } 765 | 766 | MCP2515::ERROR MCP2515::readMessage(struct can_frame *frame) 767 | { 768 | ERROR rc; 769 | uint8_t stat = getStatus(); 770 | 771 | if ( stat & STAT_RX0IF ) { 772 | rc = readMessage(RXB0, frame); 773 | } else if ( stat & STAT_RX1IF ) { 774 | rc = readMessage(RXB1, frame); 775 | } else { 776 | rc = ERROR_NOMSG; 777 | } 778 | 779 | return rc; 780 | } 781 | 782 | bool MCP2515::checkReceive(void) 783 | { 784 | uint8_t res = getStatus(); 785 | if ( res & STAT_RXIF_MASK ) { 786 | return true; 787 | } else { 788 | return false; 789 | } 790 | } 791 | 792 | bool MCP2515::checkError(void) 793 | { 794 | uint8_t eflg = getErrorFlags(); 795 | 796 | if ( eflg & EFLG_ERRORMASK ) { 797 | return true; 798 | } else { 799 | return false; 800 | } 801 | } 802 | 803 | uint8_t MCP2515::getErrorFlags(void) 804 | { 805 | return readRegister(MCP_EFLG); 806 | } 807 | 808 | void MCP2515::clearRXnOVRFlags(void) 809 | { 810 | modifyRegister(MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0); 811 | } 812 | 813 | uint8_t MCP2515::getInterrupts(void) 814 | { 815 | return readRegister(MCP_CANINTF); 816 | } 817 | 818 | void MCP2515::clearInterrupts(void) 819 | { 820 | setRegister(MCP_CANINTF, 0); 821 | } 822 | 823 | uint8_t MCP2515::getInterruptMask(void) 824 | { 825 | return readRegister(MCP_CANINTE); 826 | } 827 | 828 | void MCP2515::clearTXInterrupts(void) 829 | { 830 | modifyRegister(MCP_CANINTF, (CANINTF_TX0IF | CANINTF_TX1IF | CANINTF_TX2IF), 0); 831 | } 832 | 833 | void MCP2515::clearRXnOVR(void) 834 | { 835 | uint8_t eflg = getErrorFlags(); 836 | if (eflg != 0) { 837 | clearRXnOVRFlags(); 838 | clearInterrupts(); 839 | //modifyRegister(MCP_CANINTF, CANINTF_ERRIF, 0); 840 | } 841 | 842 | } 843 | 844 | void MCP2515::clearMERR() 845 | { 846 | //modifyRegister(MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0); 847 | //clearInterrupts(); 848 | modifyRegister(MCP_CANINTF, CANINTF_MERRF, 0); 849 | } 850 | 851 | void MCP2515::clearERRIF() 852 | { 853 | //modifyRegister(MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0); 854 | //clearInterrupts(); 855 | modifyRegister(MCP_CANINTF, CANINTF_ERRIF, 0); 856 | } 857 | -------------------------------------------------------------------------------- /mcp2515.h: -------------------------------------------------------------------------------- 1 | #ifndef _MCP2515_H_ 2 | #define _MCP2515_H_ 3 | 4 | #include "driver/spi_master.h" 5 | 6 | #include "can.h" 7 | 8 | /* 9 | * Speed 8M 10 | */ 11 | #define MCP_8MHz_1000kBPS_CFG1 (0x00) 12 | #define MCP_8MHz_1000kBPS_CFG2 (0x80) 13 | #define MCP_8MHz_1000kBPS_CFG3 (0x80) 14 | 15 | #define MCP_8MHz_500kBPS_CFG1 (0x00) 16 | #define MCP_8MHz_500kBPS_CFG2 (0x90) 17 | #define MCP_8MHz_500kBPS_CFG3 (0x82) 18 | 19 | #define MCP_8MHz_250kBPS_CFG1 (0x00) 20 | #define MCP_8MHz_250kBPS_CFG2 (0xB1) 21 | #define MCP_8MHz_250kBPS_CFG3 (0x85) 22 | 23 | #define MCP_8MHz_200kBPS_CFG1 (0x00) 24 | #define MCP_8MHz_200kBPS_CFG2 (0xB4) 25 | #define MCP_8MHz_200kBPS_CFG3 (0x86) 26 | 27 | #define MCP_8MHz_125kBPS_CFG1 (0x01) 28 | #define MCP_8MHz_125kBPS_CFG2 (0xB1) 29 | #define MCP_8MHz_125kBPS_CFG3 (0x85) 30 | 31 | #define MCP_8MHz_100kBPS_CFG1 (0x01) 32 | #define MCP_8MHz_100kBPS_CFG2 (0xB4) 33 | #define MCP_8MHz_100kBPS_CFG3 (0x86) 34 | 35 | #define MCP_8MHz_80kBPS_CFG1 (0x01) 36 | #define MCP_8MHz_80kBPS_CFG2 (0xBF) 37 | #define MCP_8MHz_80kBPS_CFG3 (0x87) 38 | 39 | #define MCP_8MHz_50kBPS_CFG1 (0x03) 40 | #define MCP_8MHz_50kBPS_CFG2 (0xB4) 41 | #define MCP_8MHz_50kBPS_CFG3 (0x86) 42 | 43 | #define MCP_8MHz_40kBPS_CFG1 (0x03) 44 | #define MCP_8MHz_40kBPS_CFG2 (0xBF) 45 | #define MCP_8MHz_40kBPS_CFG3 (0x87) 46 | 47 | #define MCP_8MHz_33k3BPS_CFG1 (0x47) 48 | #define MCP_8MHz_33k3BPS_CFG2 (0xE2) 49 | #define MCP_8MHz_33k3BPS_CFG3 (0x85) 50 | 51 | #define MCP_8MHz_31k25BPS_CFG1 (0x07) 52 | #define MCP_8MHz_31k25BPS_CFG2 (0xA4) 53 | #define MCP_8MHz_31k25BPS_CFG3 (0x84) 54 | 55 | #define MCP_8MHz_20kBPS_CFG1 (0x07) 56 | #define MCP_8MHz_20kBPS_CFG2 (0xBF) 57 | #define MCP_8MHz_20kBPS_CFG3 (0x87) 58 | 59 | #define MCP_8MHz_10kBPS_CFG1 (0x0F) 60 | #define MCP_8MHz_10kBPS_CFG2 (0xBF) 61 | #define MCP_8MHz_10kBPS_CFG3 (0x87) 62 | 63 | #define MCP_8MHz_5kBPS_CFG1 (0x1F) 64 | #define MCP_8MHz_5kBPS_CFG2 (0xBF) 65 | #define MCP_8MHz_5kBPS_CFG3 (0x87) 66 | 67 | /* 68 | * speed 16M 69 | */ 70 | #define MCP_16MHz_1000kBPS_CFG1 (0x00) 71 | #define MCP_16MHz_1000kBPS_CFG2 (0xD0) 72 | #define MCP_16MHz_1000kBPS_CFG3 (0x82) 73 | 74 | #define MCP_16MHz_500kBPS_CFG1 (0x00) 75 | #define MCP_16MHz_500kBPS_CFG2 (0xF0) 76 | #define MCP_16MHz_500kBPS_CFG3 (0x86) 77 | 78 | #define MCP_16MHz_250kBPS_CFG1 (0x41) 79 | #define MCP_16MHz_250kBPS_CFG2 (0xF1) 80 | #define MCP_16MHz_250kBPS_CFG3 (0x85) 81 | 82 | #define MCP_16MHz_200kBPS_CFG1 (0x01) 83 | #define MCP_16MHz_200kBPS_CFG2 (0xFA) 84 | #define MCP_16MHz_200kBPS_CFG3 (0x87) 85 | 86 | #define MCP_16MHz_125kBPS_CFG1 (0x03) 87 | #define MCP_16MHz_125kBPS_CFG2 (0xF0) 88 | #define MCP_16MHz_125kBPS_CFG3 (0x86) 89 | 90 | #define MCP_16MHz_100kBPS_CFG1 (0x03) 91 | #define MCP_16MHz_100kBPS_CFG2 (0xFA) 92 | #define MCP_16MHz_100kBPS_CFG3 (0x87) 93 | 94 | #define MCP_16MHz_80kBPS_CFG1 (0x03) 95 | #define MCP_16MHz_80kBPS_CFG2 (0xFF) 96 | #define MCP_16MHz_80kBPS_CFG3 (0x87) 97 | 98 | #define MCP_16MHz_83k3BPS_CFG1 (0x03) 99 | #define MCP_16MHz_83k3BPS_CFG2 (0xBE) 100 | #define MCP_16MHz_83k3BPS_CFG3 (0x07) 101 | 102 | #define MCP_16MHz_50kBPS_CFG1 (0x07) 103 | #define MCP_16MHz_50kBPS_CFG2 (0xFA) 104 | #define MCP_16MHz_50kBPS_CFG3 (0x87) 105 | 106 | #define MCP_16MHz_40kBPS_CFG1 (0x07) 107 | #define MCP_16MHz_40kBPS_CFG2 (0xFF) 108 | #define MCP_16MHz_40kBPS_CFG3 (0x87) 109 | 110 | #define MCP_16MHz_33k3BPS_CFG1 (0x4E) 111 | #define MCP_16MHz_33k3BPS_CFG2 (0xF1) 112 | #define MCP_16MHz_33k3BPS_CFG3 (0x85) 113 | 114 | #define MCP_16MHz_20kBPS_CFG1 (0x0F) 115 | #define MCP_16MHz_20kBPS_CFG2 (0xFF) 116 | #define MCP_16MHz_20kBPS_CFG3 (0x87) 117 | 118 | #define MCP_16MHz_10kBPS_CFG1 (0x1F) 119 | #define MCP_16MHz_10kBPS_CFG2 (0xFF) 120 | #define MCP_16MHz_10kBPS_CFG3 (0x87) 121 | 122 | #define MCP_16MHz_5kBPS_CFG1 (0x3F) 123 | #define MCP_16MHz_5kBPS_CFG2 (0xFF) 124 | #define MCP_16MHz_5kBPS_CFG3 (0x87) 125 | 126 | /* 127 | * speed 20M 128 | */ 129 | #define MCP_20MHz_1000kBPS_CFG1 (0x00) 130 | #define MCP_20MHz_1000kBPS_CFG2 (0xD9) 131 | #define MCP_20MHz_1000kBPS_CFG3 (0x82) 132 | 133 | #define MCP_20MHz_500kBPS_CFG1 (0x00) 134 | #define MCP_20MHz_500kBPS_CFG2 (0xFA) 135 | #define MCP_20MHz_500kBPS_CFG3 (0x87) 136 | 137 | #define MCP_20MHz_250kBPS_CFG1 (0x41) 138 | #define MCP_20MHz_250kBPS_CFG2 (0xFB) 139 | #define MCP_20MHz_250kBPS_CFG3 (0x86) 140 | 141 | #define MCP_20MHz_200kBPS_CFG1 (0x01) 142 | #define MCP_20MHz_200kBPS_CFG2 (0xFF) 143 | #define MCP_20MHz_200kBPS_CFG3 (0x87) 144 | 145 | #define MCP_20MHz_125kBPS_CFG1 (0x03) 146 | #define MCP_20MHz_125kBPS_CFG2 (0xFA) 147 | #define MCP_20MHz_125kBPS_CFG3 (0x87) 148 | 149 | #define MCP_20MHz_100kBPS_CFG1 (0x04) 150 | #define MCP_20MHz_100kBPS_CFG2 (0xFA) 151 | #define MCP_20MHz_100kBPS_CFG3 (0x87) 152 | 153 | #define MCP_20MHz_83k3BPS_CFG1 (0x04) 154 | #define MCP_20MHz_83k3BPS_CFG2 (0xFE) 155 | #define MCP_20MHz_83k3BPS_CFG3 (0x87) 156 | 157 | #define MCP_20MHz_80kBPS_CFG1 (0x04) 158 | #define MCP_20MHz_80kBPS_CFG2 (0xFF) 159 | #define MCP_20MHz_80kBPS_CFG3 (0x87) 160 | 161 | #define MCP_20MHz_50kBPS_CFG1 (0x09) 162 | #define MCP_20MHz_50kBPS_CFG2 (0xFA) 163 | #define MCP_20MHz_50kBPS_CFG3 (0x87) 164 | 165 | #define MCP_20MHz_40kBPS_CFG1 (0x09) 166 | #define MCP_20MHz_40kBPS_CFG2 (0xFF) 167 | #define MCP_20MHz_40kBPS_CFG3 (0x87) 168 | 169 | #define MCP_20MHz_33k3BPS_CFG1 (0x0B) 170 | #define MCP_20MHz_33k3BPS_CFG2 (0xFF) 171 | #define MCP_20MHz_33k3BPS_CFG3 (0x87) 172 | 173 | enum CAN_CLOCK { 174 | MCP_20MHZ, 175 | MCP_16MHZ, 176 | MCP_8MHZ 177 | }; 178 | 179 | enum CAN_SPEED { 180 | CAN_5KBPS, 181 | CAN_10KBPS, 182 | CAN_20KBPS, 183 | CAN_31K25BPS, 184 | CAN_33KBPS, 185 | CAN_40KBPS, 186 | CAN_50KBPS, 187 | CAN_80KBPS, 188 | CAN_83K3BPS, 189 | CAN_95KBPS, 190 | CAN_100KBPS, 191 | CAN_125KBPS, 192 | CAN_200KBPS, 193 | CAN_250KBPS, 194 | CAN_500KBPS, 195 | CAN_1000KBPS 196 | }; 197 | 198 | enum CAN_CLKOUT { 199 | CLKOUT_DISABLE = -1, 200 | CLKOUT_DIV1 = 0x0, 201 | CLKOUT_DIV2 = 0x1, 202 | CLKOUT_DIV4 = 0x2, 203 | CLKOUT_DIV8 = 0x3, 204 | }; 205 | 206 | class MCP2515 207 | { 208 | public: 209 | enum ERROR { 210 | ERROR_OK = 0, 211 | ERROR_FAIL = 1, 212 | ERROR_ALLTXBUSY = 2, 213 | ERROR_FAILINIT = 3, 214 | ERROR_FAILTX = 4, 215 | ERROR_NOMSG = 5 216 | }; 217 | 218 | enum MASK { 219 | MASK0, 220 | MASK1 221 | }; 222 | 223 | enum RXF { 224 | RXF0 = 0, 225 | RXF1 = 1, 226 | RXF2 = 2, 227 | RXF3 = 3, 228 | RXF4 = 4, 229 | RXF5 = 5 230 | }; 231 | 232 | enum RXBn { 233 | RXB0 = 0, 234 | RXB1 = 1 235 | }; 236 | 237 | enum TXBn { 238 | TXB0 = 0, 239 | TXB1 = 1, 240 | TXB2 = 2 241 | }; 242 | 243 | enum /*class*/ CANINTF : uint8_t { 244 | CANINTF_RX0IF = 0x01, 245 | CANINTF_RX1IF = 0x02, 246 | CANINTF_TX0IF = 0x04, 247 | CANINTF_TX1IF = 0x08, 248 | CANINTF_TX2IF = 0x10, 249 | CANINTF_ERRIF = 0x20, 250 | CANINTF_WAKIF = 0x40, 251 | CANINTF_MERRF = 0x80 252 | }; 253 | 254 | enum /*class*/ EFLG : uint8_t { 255 | EFLG_RX1OVR = (1<<7), 256 | EFLG_RX0OVR = (1<<6), 257 | EFLG_TXBO = (1<<5), 258 | EFLG_TXEP = (1<<4), 259 | EFLG_RXEP = (1<<3), 260 | EFLG_TXWAR = (1<<2), 261 | EFLG_RXWAR = (1<<1), 262 | EFLG_EWARN = (1<<0) 263 | }; 264 | 265 | private: 266 | static const uint8_t CANCTRL_REQOP = 0xE0; 267 | static const uint8_t CANCTRL_ABAT = 0x10; 268 | static const uint8_t CANCTRL_OSM = 0x08; 269 | static const uint8_t CANCTRL_CLKEN = 0x04; 270 | static const uint8_t CANCTRL_CLKPRE = 0x03; 271 | 272 | enum /*class*/ CANCTRL_REQOP_MODE : uint8_t { 273 | CANCTRL_REQOP_NORMAL = 0x00, 274 | CANCTRL_REQOP_SLEEP = 0x20, 275 | CANCTRL_REQOP_LOOPBACK = 0x40, 276 | CANCTRL_REQOP_LISTENONLY = 0x60, 277 | CANCTRL_REQOP_CONFIG = 0x80, 278 | CANCTRL_REQOP_POWERUP = 0xE0 279 | }; 280 | 281 | static const uint8_t CANSTAT_OPMOD = 0xE0; 282 | static const uint8_t CANSTAT_ICOD = 0x0E; 283 | 284 | static const uint8_t CNF3_SOF = 0x80; 285 | 286 | static const uint8_t TXB_EXIDE_MASK = 0x08; 287 | static const uint8_t DLC_MASK = 0x0F; 288 | static const uint8_t RTR_MASK = 0x40; 289 | 290 | static const uint8_t RXBnCTRL_RXM_STD = 0x20; 291 | static const uint8_t RXBnCTRL_RXM_EXT = 0x40; 292 | static const uint8_t RXBnCTRL_RXM_STDEXT = 0x00; 293 | static const uint8_t RXBnCTRL_RXM_MASK = 0x60; 294 | static const uint8_t RXBnCTRL_RTR = 0x08; 295 | static const uint8_t RXB0CTRL_BUKT = 0x04; 296 | static const uint8_t RXB0CTRL_FILHIT_MASK = 0x03; 297 | static const uint8_t RXB1CTRL_FILHIT_MASK = 0x07; 298 | static const uint8_t RXB0CTRL_FILHIT = 0x00; 299 | static const uint8_t RXB1CTRL_FILHIT = 0x01; 300 | 301 | static const uint8_t MCP_SIDH = 0; 302 | static const uint8_t MCP_SIDL = 1; 303 | static const uint8_t MCP_EID8 = 2; 304 | static const uint8_t MCP_EID0 = 3; 305 | static const uint8_t MCP_DLC = 4; 306 | static const uint8_t MCP_DATA = 5; 307 | 308 | enum /*class*/ STAT : uint8_t { 309 | STAT_RX0IF = (1<<0), 310 | STAT_RX1IF = (1<<1) 311 | }; 312 | 313 | static const uint8_t STAT_RXIF_MASK = STAT_RX0IF | STAT_RX1IF; 314 | 315 | enum /*class*/ TXBnCTRL : uint8_t { 316 | TXB_ABTF = 0x40, 317 | TXB_MLOA = 0x20, 318 | TXB_TXERR = 0x10, 319 | TXB_TXREQ = 0x08, 320 | TXB_TXIE = 0x04, 321 | TXB_TXP = 0x03 322 | }; 323 | 324 | static const uint8_t EFLG_ERRORMASK = EFLG_RX1OVR 325 | | EFLG_RX0OVR 326 | | EFLG_TXBO 327 | | EFLG_TXEP 328 | | EFLG_RXEP; 329 | 330 | enum /*class*/ INSTRUCTION : uint8_t { 331 | INSTRUCTION_WRITE = 0x02, 332 | INSTRUCTION_READ = 0x03, 333 | INSTRUCTION_BITMOD = 0x05, 334 | INSTRUCTION_LOAD_TX0 = 0x40, 335 | INSTRUCTION_LOAD_TX1 = 0x42, 336 | INSTRUCTION_LOAD_TX2 = 0x44, 337 | INSTRUCTION_RTS_TX0 = 0x81, 338 | INSTRUCTION_RTS_TX1 = 0x82, 339 | INSTRUCTION_RTS_TX2 = 0x84, 340 | INSTRUCTION_RTS_ALL = 0x87, 341 | INSTRUCTION_READ_RX0 = 0x90, 342 | INSTRUCTION_READ_RX1 = 0x94, 343 | INSTRUCTION_READ_STATUS = 0xA0, 344 | INSTRUCTION_RX_STATUS = 0xB0, 345 | INSTRUCTION_RESET = 0xC0 346 | }; 347 | 348 | enum /*class*/ REGISTER : uint8_t { 349 | MCP_RXF0SIDH = 0x00, 350 | MCP_RXF0SIDL = 0x01, 351 | MCP_RXF0EID8 = 0x02, 352 | MCP_RXF0EID0 = 0x03, 353 | MCP_RXF1SIDH = 0x04, 354 | MCP_RXF1SIDL = 0x05, 355 | MCP_RXF1EID8 = 0x06, 356 | MCP_RXF1EID0 = 0x07, 357 | MCP_RXF2SIDH = 0x08, 358 | MCP_RXF2SIDL = 0x09, 359 | MCP_RXF2EID8 = 0x0A, 360 | MCP_RXF2EID0 = 0x0B, 361 | MCP_CANSTAT = 0x0E, 362 | MCP_CANCTRL = 0x0F, 363 | MCP_RXF3SIDH = 0x10, 364 | MCP_RXF3SIDL = 0x11, 365 | MCP_RXF3EID8 = 0x12, 366 | MCP_RXF3EID0 = 0x13, 367 | MCP_RXF4SIDH = 0x14, 368 | MCP_RXF4SIDL = 0x15, 369 | MCP_RXF4EID8 = 0x16, 370 | MCP_RXF4EID0 = 0x17, 371 | MCP_RXF5SIDH = 0x18, 372 | MCP_RXF5SIDL = 0x19, 373 | MCP_RXF5EID8 = 0x1A, 374 | MCP_RXF5EID0 = 0x1B, 375 | MCP_TEC = 0x1C, 376 | MCP_REC = 0x1D, 377 | MCP_RXM0SIDH = 0x20, 378 | MCP_RXM0SIDL = 0x21, 379 | MCP_RXM0EID8 = 0x22, 380 | MCP_RXM0EID0 = 0x23, 381 | MCP_RXM1SIDH = 0x24, 382 | MCP_RXM1SIDL = 0x25, 383 | MCP_RXM1EID8 = 0x26, 384 | MCP_RXM1EID0 = 0x27, 385 | MCP_CNF3 = 0x28, 386 | MCP_CNF2 = 0x29, 387 | MCP_CNF1 = 0x2A, 388 | MCP_CANINTE = 0x2B, 389 | MCP_CANINTF = 0x2C, 390 | MCP_EFLG = 0x2D, 391 | MCP_TXB0CTRL = 0x30, 392 | MCP_TXB0SIDH = 0x31, 393 | MCP_TXB0SIDL = 0x32, 394 | MCP_TXB0EID8 = 0x33, 395 | MCP_TXB0EID0 = 0x34, 396 | MCP_TXB0DLC = 0x35, 397 | MCP_TXB0DATA = 0x36, 398 | MCP_TXB1CTRL = 0x40, 399 | MCP_TXB1SIDH = 0x41, 400 | MCP_TXB1SIDL = 0x42, 401 | MCP_TXB1EID8 = 0x43, 402 | MCP_TXB1EID0 = 0x44, 403 | MCP_TXB1DLC = 0x45, 404 | MCP_TXB1DATA = 0x46, 405 | MCP_TXB2CTRL = 0x50, 406 | MCP_TXB2SIDH = 0x51, 407 | MCP_TXB2SIDL = 0x52, 408 | MCP_TXB2EID8 = 0x53, 409 | MCP_TXB2EID0 = 0x54, 410 | MCP_TXB2DLC = 0x55, 411 | MCP_TXB2DATA = 0x56, 412 | MCP_RXB0CTRL = 0x60, 413 | MCP_RXB0SIDH = 0x61, 414 | MCP_RXB0SIDL = 0x62, 415 | MCP_RXB0EID8 = 0x63, 416 | MCP_RXB0EID0 = 0x64, 417 | MCP_RXB0DLC = 0x65, 418 | MCP_RXB0DATA = 0x66, 419 | MCP_RXB1CTRL = 0x70, 420 | MCP_RXB1SIDH = 0x71, 421 | MCP_RXB1SIDL = 0x72, 422 | MCP_RXB1EID8 = 0x73, 423 | MCP_RXB1EID0 = 0x74, 424 | MCP_RXB1DLC = 0x75, 425 | MCP_RXB1DATA = 0x76 426 | }; 427 | 428 | static const uint32_t SPI_CLOCK = 10000000; // 10MHz 429 | 430 | static const int N_TXBUFFERS = 3; 431 | static const int N_RXBUFFERS = 2; 432 | 433 | static const struct TXBn_REGS { 434 | REGISTER CTRL; 435 | REGISTER SIDH; 436 | REGISTER DATA; 437 | } TXB[N_TXBUFFERS]; 438 | 439 | static const struct RXBn_REGS { 440 | REGISTER CTRL; 441 | REGISTER SIDH; 442 | REGISTER DATA; 443 | CANINTF CANINTF_RXnIF; 444 | } RXB[N_RXBUFFERS]; 445 | 446 | spi_device_handle_t *spi; 447 | 448 | private: 449 | ERROR setMode(const CANCTRL_REQOP_MODE mode); 450 | 451 | uint8_t readRegister(const REGISTER reg); 452 | void readRegisters(const REGISTER reg, uint8_t values[], const uint8_t n); 453 | void setRegister(const REGISTER reg, const uint8_t value); 454 | void setRegisters(const REGISTER reg, const uint8_t values[], const uint8_t n); 455 | void modifyRegister(const REGISTER reg, const uint8_t mask, const uint8_t data); 456 | 457 | void prepareId(uint8_t *buffer, const bool ext, const uint32_t id); 458 | 459 | public: 460 | MCP2515(spi_device_handle_t *s); 461 | ERROR reset(void); 462 | ERROR setConfigMode(); 463 | ERROR setListenOnlyMode(); 464 | ERROR setSleepMode(); 465 | ERROR setLoopbackMode(); 466 | ERROR setNormalMode(); 467 | ERROR setClkOut(const CAN_CLKOUT divisor); 468 | ERROR setBitrate(const CAN_SPEED canSpeed); 469 | ERROR setBitrate(const CAN_SPEED canSpeed, const CAN_CLOCK canClock); 470 | ERROR setFilterMask(const MASK num, const bool ext, const uint32_t ulData); 471 | ERROR setFilter(const RXF num, const bool ext, const uint32_t ulData); 472 | ERROR sendMessage(const TXBn txbn, const struct can_frame *frame); 473 | ERROR sendMessage(const struct can_frame *frame); 474 | ERROR readMessage(const RXBn rxbn, struct can_frame *frame); 475 | ERROR readMessage(struct can_frame *frame); 476 | bool checkReceive(void); 477 | bool checkError(void); 478 | uint8_t getErrorFlags(void); 479 | void clearRXnOVRFlags(void); 480 | uint8_t getInterrupts(void); 481 | uint8_t getInterruptMask(void); 482 | void clearInterrupts(void); 483 | void clearTXInterrupts(void); 484 | uint8_t getStatus(void); 485 | void clearRXnOVR(void); 486 | void clearMERR(); 487 | void clearERRIF(); 488 | }; 489 | 490 | #endif 491 | --------------------------------------------------------------------------------