Overhaul
Format Custom struct for spi handle, cs pin Add prefix to functions
This commit is contained in:
487
mcp2515.c
487
mcp2515.c
@@ -7,120 +7,102 @@
|
|||||||
|
|
||||||
#include "mcp2515.h"
|
#include "mcp2515.h"
|
||||||
#include "mcp2515_consts.h"
|
#include "mcp2515_consts.h"
|
||||||
#include <stm32f4xx_hal.h>
|
// #include <stm32f0xx_hal.h>
|
||||||
#include <string.h> //Todo: this is yucky just for the memset function
|
|
||||||
|
|
||||||
/* Modify below items for your SPI configurations */
|
|
||||||
extern SPI_HandleTypeDef hspi4;
|
|
||||||
#define SPI_CAN &hspi4
|
|
||||||
#define SPI_TIMEOUT 10
|
#define SPI_TIMEOUT 10
|
||||||
//#define MCP2515_CS_HIGH() HAL_GPIO_WritePin(GPIOE, GPIO_PIN_4, GPIO_PIN_SET)
|
|
||||||
//#define MCP2515_CS_LOW() HAL_GPIO_WritePin(GPIOE, GPIO_PIN_4, GPIO_PIN_RESET)
|
|
||||||
|
|
||||||
void startSPI() {
|
void MCP2515_Init(MCP2515_HandleTypeDef* hcan, SPI_HandleTypeDef* hspi, GPIO_TypeDef* cs_port, uint16_t cs_pin) {
|
||||||
HAL_GPIO_WritePin(GPIOE, GPIO_PIN_4, GPIO_PIN_RESET);
|
hcan->hspi = hspi;
|
||||||
|
hcan->cs_port = cs_port;
|
||||||
|
hcan->cs_pin = cs_pin;
|
||||||
}
|
}
|
||||||
|
|
||||||
void endSPI() {
|
uint8_t MCP2515_SPI_transfer(MCP2515_HandleTypeDef* hcan, uint8_t txByte) {
|
||||||
HAL_GPIO_WritePin(GPIOE, GPIO_PIN_4, GPIO_PIN_SET);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t SPI_transfer(uint8_t txByte){
|
|
||||||
uint8_t rxByte;
|
uint8_t rxByte;
|
||||||
HAL_SPI_TransmitReceive(SPI_CAN, &txByte, &rxByte, 1, SPI_TIMEOUT);
|
HAL_SPI_TransmitReceive(hcan->hspi, &txByte, &rxByte, 1, SPI_TIMEOUT);
|
||||||
return rxByte;
|
return rxByte;
|
||||||
}
|
}
|
||||||
|
|
||||||
void setRegister(uint8_t reg, uint8_t value)
|
void MCP2515_Set_Register(MCP2515_HandleTypeDef* hcan, uint8_t reg, uint8_t value) {
|
||||||
{
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
startSPI();
|
MCP2515_SPI_transfer(hcan, INSTRUCTION_WRITE);
|
||||||
SPI_transfer(INSTRUCTION_WRITE);
|
MCP2515_SPI_transfer(hcan, reg);
|
||||||
SPI_transfer(reg);
|
MCP2515_SPI_transfer(hcan, value);
|
||||||
SPI_transfer(value);
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
endSPI();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void setRegisters(uint8_t reg, uint8_t values[], uint8_t n)
|
void MCP2515_Set_Registers(MCP2515_HandleTypeDef* hcan, uint8_t reg, uint8_t values[], uint8_t n) {
|
||||||
{
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
startSPI();
|
MCP2515_SPI_transfer(hcan, INSTRUCTION_WRITE);
|
||||||
SPI_transfer(INSTRUCTION_WRITE);
|
MCP2515_SPI_transfer(hcan, reg);
|
||||||
SPI_transfer(reg);
|
for (uint8_t i = 0; i < n; i++) {
|
||||||
for (uint8_t i=0; i<n; i++) {
|
MCP2515_SPI_transfer(hcan, values[i]);
|
||||||
SPI_transfer(values[i]);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// HAL_SPI_Transmit(SPI_CAN, values, n, SPI_TIMEOUT);
|
// HAL_SPI_Transmit(SPI_CAN, values, n, SPI_TIMEOUT);
|
||||||
endSPI();
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loadTx(uint8_t reg, uint8_t values[], uint8_t n){
|
void MCP2515_Load_Tx(MCP2515_HandleTypeDef* hcan, uint8_t reg, uint8_t values[], uint8_t n) {
|
||||||
startSPI();
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
//SPI_transfer(INSTRUCTION_WRITE);
|
// MCP2515_SPI_transfer(hcan, INSTRUCTION_WRITE);
|
||||||
SPI_transfer(reg);
|
MCP2515_SPI_transfer(hcan, reg);
|
||||||
for (uint8_t i=0; i<n; i++) {
|
for (uint8_t i = 0; i < n; i++) {
|
||||||
SPI_transfer(values[i]);
|
MCP2515_SPI_transfer(hcan, values[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// HAL_SPI_Transmit(SPI_CAN, values, n, SPI_TIMEOUT);
|
// HAL_SPI_Transmit(SPI_CAN, values, n, SPI_TIMEOUT);
|
||||||
endSPI();
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
}
|
}
|
||||||
|
|
||||||
void modifyRegister(uint8_t reg, uint8_t mask, uint8_t data)
|
void MCP2515_Modify_Register(MCP2515_HandleTypeDef* hcan, uint8_t reg, uint8_t mask, uint8_t data) {
|
||||||
{
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
startSPI();
|
MCP2515_SPI_transfer(hcan, INSTRUCTION_BITMOD);
|
||||||
SPI_transfer(INSTRUCTION_BITMOD);
|
MCP2515_SPI_transfer(hcan, reg);
|
||||||
SPI_transfer(reg);
|
MCP2515_SPI_transfer(hcan, mask);
|
||||||
SPI_transfer(mask);
|
MCP2515_SPI_transfer(hcan, data);
|
||||||
SPI_transfer(data);
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
endSPI();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint8_t MCP2515_Read_Register(MCP2515_HandleTypeDef* hcan, REGISTER reg) {
|
||||||
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
|
MCP2515_SPI_transfer(hcan, INSTRUCTION_READ);
|
||||||
uint8_t readRegister(REGISTER reg)
|
MCP2515_SPI_transfer(hcan, reg);
|
||||||
{
|
uint8_t ret = MCP2515_SPI_transfer(hcan, 0x00);
|
||||||
startSPI();
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
SPI_transfer(INSTRUCTION_READ);
|
|
||||||
SPI_transfer(reg);
|
|
||||||
uint8_t ret = SPI_transfer(0x00);
|
|
||||||
endSPI();
|
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
void readRegisters(REGISTER reg, uint8_t values[], uint8_t n)
|
void MCP2515_Read_Registers(MCP2515_HandleTypeDef* hcan, REGISTER reg, uint8_t values[], uint8_t n) {
|
||||||
{
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
startSPI();
|
MCP2515_SPI_transfer(hcan, INSTRUCTION_READ);
|
||||||
SPI_transfer(INSTRUCTION_READ);
|
MCP2515_SPI_transfer(hcan, reg);
|
||||||
SPI_transfer(reg);
|
|
||||||
// mcp2515 has auto-increment of address-pointer
|
// mcp2515 has auto-increment of address-pointer
|
||||||
for (uint8_t i=0; i<n; i++) {
|
for (uint8_t i = 0; i < n; i++) {
|
||||||
values[i] = SPI_transfer(0x00);
|
values[i] = MCP2515_SPI_transfer(hcan, 0x00);
|
||||||
//HAL_SPI_Receive(&hspi4, values, n, SPI_TIMEOUT); //Todo, check if the 0x00 from above is needed
|
// HAL_SPI_Receive(&hspi4, values, n, SPI_TIMEOUT); //Todo, check if the 0x00 from above is needed
|
||||||
}
|
}
|
||||||
endSPI();
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
}
|
}
|
||||||
|
|
||||||
void readRx(REGISTER reg, uint8_t values[], uint8_t n){
|
void MCP2515_Read_Rx(MCP2515_HandleTypeDef* hcan, REGISTER reg, uint8_t values[], uint8_t n) {
|
||||||
startSPI();
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
SPI_transfer(reg);
|
MCP2515_SPI_transfer(hcan, reg);
|
||||||
// mcp2515 has auto-increment of address-pointer
|
// mcp2515 has auto-increment of address-pointer
|
||||||
for (uint8_t i=0; i<n; i++) {
|
for (uint8_t i = 0; i < n; i++) {
|
||||||
values[i] = SPI_transfer(0x00);
|
values[i] = MCP2515_SPI_transfer(hcan, 0x00);
|
||||||
//HAL_SPI_Receive(&hspi4, values, n, SPI_TIMEOUT); //Todo, check if the 0x00 from above is needed
|
// HAL_SPI_Receive(&hspi4, values, n, SPI_TIMEOUT); //Todo, check if the 0x00 from above is needed
|
||||||
}
|
}
|
||||||
endSPI();
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error setMode(CANCTRL_REQOP_MODE mode)
|
CAN_Error MCP2515_Set_Mode(MCP2515_HandleTypeDef* hcan, CANCTRL_REQOP_MODE mode) {
|
||||||
{
|
|
||||||
|
|
||||||
unsigned long endTime = HAL_GetTick() + 10;
|
unsigned long endTime = HAL_GetTick() + 10;
|
||||||
uint8_t modeMatch = 0;
|
uint8_t modeMatch = 0;
|
||||||
while (HAL_GetTick() < endTime) {
|
while (HAL_GetTick() < endTime) {
|
||||||
modifyRegister(MCP_CANCTRL, CANCTRL_REQOP, mode);
|
MCP2515_Modify_Register(hcan, MCP_CANCTRL, CANCTRL_REQOP, mode);
|
||||||
uint8_t newmode = readRegister(MCP_CANSTAT);
|
uint8_t newmode = MCP2515_Read_Registers(hcan, MCP_CANSTAT);
|
||||||
newmode &= CANSTAT_OPMOD;
|
newmode &= CANSTAT_OPMOD;
|
||||||
|
|
||||||
modeMatch = newmode == mode;
|
modeMatch = newmode == mode;
|
||||||
@@ -131,57 +113,56 @@ CAN_Error setMode(CANCTRL_REQOP_MODE mode)
|
|||||||
}
|
}
|
||||||
|
|
||||||
return modeMatch ? ERROR_OK : ERROR_FAIL;
|
return modeMatch ? ERROR_OK : ERROR_FAIL;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error setConfigMode()
|
CAN_Error MCP2515_Set_Config_Mode(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
return MCP2515_Set_Mode(hcan, CANCTRL_REQOP_CONFIG);
|
||||||
return setMode(CANCTRL_REQOP_CONFIG);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void prepareId(uint8_t *buffer, uint8_t ext, uint32_t id)
|
void MCP2515_Prepare_Id(uint8_t* buffer, uint8_t ext, uint32_t id) {
|
||||||
{
|
|
||||||
uint16_t canid = (uint16_t)(id & 0x0FFFF);
|
uint16_t canid = (uint16_t)(id & 0x0FFFF);
|
||||||
|
|
||||||
if(ext) {
|
if (ext) {
|
||||||
buffer[MCP_EID0] = (uint8_t) (canid & 0xFF);
|
buffer[MCP_EID0] = (uint8_t)(canid & 0xFF);
|
||||||
buffer[MCP_EID8] = (uint8_t) (canid >> 8);
|
buffer[MCP_EID8] = (uint8_t)(canid >> 8);
|
||||||
canid = (uint16_t)(id >> 16);
|
canid = (uint16_t)(id >> 16);
|
||||||
buffer[MCP_SIDL] = (uint8_t) (canid & 0x03);
|
buffer[MCP_SIDL] = (uint8_t)(canid & 0x03);
|
||||||
buffer[MCP_SIDL] += (uint8_t) ((canid & 0x1C) << 3);
|
buffer[MCP_SIDL] += (uint8_t)((canid & 0x1C) << 3);
|
||||||
buffer[MCP_SIDL] |= TXB_EXIDE_MASK;
|
buffer[MCP_SIDL] |= TXB_EXIDE_MASK;
|
||||||
buffer[MCP_SIDH] = (uint8_t) (canid >> 5);
|
buffer[MCP_SIDH] = (uint8_t)(canid >> 5);
|
||||||
} else {
|
} else {
|
||||||
buffer[MCP_SIDH] = (uint8_t) (canid >> 3);
|
buffer[MCP_SIDH] = (uint8_t)(canid >> 3);
|
||||||
buffer[MCP_SIDL] = (uint8_t) ((canid & 0x07 ) << 5);
|
buffer[MCP_SIDL] = (uint8_t)((canid & 0x07) << 5);
|
||||||
buffer[MCP_EID0] = 0;
|
buffer[MCP_EID0] = 0;
|
||||||
buffer[MCP_EID8] = 0;
|
buffer[MCP_EID8] = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t getStatus(void)
|
uint8_t MCP2515_Get_Status(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
startSPI();
|
MCP2515_SPI_transfer(hcan, INSTRUCTION_READ_STATUS);
|
||||||
SPI_transfer(INSTRUCTION_READ_STATUS);
|
uint8_t i = MCP2515_SPI_transfer(hcan, 0x00);
|
||||||
uint8_t i = SPI_transfer(0x00);
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
endSPI();
|
|
||||||
return i;
|
return i;
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_setFilterMask(MASK mask, uint8_t ext, uint32_t ulData)
|
CAN_Error MCP2515_Set_Filter_Mask(MCP2515_HandleTypeDef* hcan, MASK mask, uint8_t ext, uint32_t ulData) {
|
||||||
{
|
|
||||||
CAN_Error res = setConfigMode();
|
CAN_Error res = setConfigMode();
|
||||||
if (res != ERROR_OK) {
|
if (res != ERROR_OK) {
|
||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t tbufdata[4];
|
uint8_t tbufdata[4];
|
||||||
prepareId(tbufdata, ext, ulData);
|
MCP2515_Prepare_Id(tbufdata, ext, ulData);
|
||||||
|
|
||||||
REGISTER reg;
|
REGISTER reg;
|
||||||
switch (mask) {
|
switch (mask) {
|
||||||
case MASK0: reg = MCP_RXM0SIDH; break;
|
case MASK0:
|
||||||
case MASK1: reg = MCP_RXM1SIDH; break;
|
reg = MCP_RXM0SIDH;
|
||||||
|
break;
|
||||||
|
case MASK1:
|
||||||
|
reg = MCP_RXM1SIDH;
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
return ERROR_FAIL;
|
return ERROR_FAIL;
|
||||||
}
|
}
|
||||||
@@ -191,8 +172,7 @@ CAN_Error MCP_setFilterMask(MASK mask, uint8_t ext, uint32_t ulData)
|
|||||||
return ERROR_OK;
|
return ERROR_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_setFilter(RXF num, uint8_t ext, uint32_t ulData)
|
CAN_Error MCP2515_Set_Filter(MCP2515_HandleTypeDef* hcan, RXF num, uint8_t ext, uint32_t ulData) {
|
||||||
{
|
|
||||||
CAN_Error res = setConfigMode();
|
CAN_Error res = setConfigMode();
|
||||||
if (res != ERROR_OK) {
|
if (res != ERROR_OK) {
|
||||||
return res;
|
return res;
|
||||||
@@ -201,34 +181,44 @@ CAN_Error MCP_setFilter(RXF num, uint8_t ext, uint32_t ulData)
|
|||||||
REGISTER reg;
|
REGISTER reg;
|
||||||
|
|
||||||
switch (num) {
|
switch (num) {
|
||||||
case RXF0: reg = MCP_RXF0SIDH; break;
|
case RXF0:
|
||||||
case RXF1: reg = MCP_RXF1SIDH; break;
|
reg = MCP_RXF0SIDH;
|
||||||
case RXF2: reg = MCP_RXF2SIDH; break;
|
break;
|
||||||
case RXF3: reg = MCP_RXF3SIDH; break;
|
case RXF1:
|
||||||
case RXF4: reg = MCP_RXF4SIDH; break;
|
reg = MCP_RXF1SIDH;
|
||||||
case RXF5: reg = MCP_RXF5SIDH; break;
|
break;
|
||||||
|
case RXF2:
|
||||||
|
reg = MCP_RXF2SIDH;
|
||||||
|
break;
|
||||||
|
case RXF3:
|
||||||
|
reg = MCP_RXF3SIDH;
|
||||||
|
break;
|
||||||
|
case RXF4:
|
||||||
|
reg = MCP_RXF4SIDH;
|
||||||
|
break;
|
||||||
|
case RXF5:
|
||||||
|
reg = MCP_RXF5SIDH;
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
return ERROR_FAIL;
|
return ERROR_FAIL;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t tbufdata[4];
|
uint8_t tbufdata[4];
|
||||||
prepareId(tbufdata, ext, ulData);
|
MCP2515_Prepare_Id(tbufdata, ext, ulData);
|
||||||
setRegisters(reg, tbufdata, 4);
|
setRegisters(reg, tbufdata, 4);
|
||||||
|
|
||||||
return ERROR_OK;
|
return ERROR_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP2515_reset(void)
|
CAN_Error MCP2515_Reset(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
startSPI();
|
MCP2515_SPI_transfer(hcan, INSTRUCTION_RESET);
|
||||||
SPI_transfer(INSTRUCTION_RESET);
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
endSPI();
|
|
||||||
|
|
||||||
|
|
||||||
HAL_Delay(10);
|
HAL_Delay(10);
|
||||||
|
|
||||||
uint8_t zeros[14];
|
uint8_t zeros[14] = {0};
|
||||||
memset(zeros, 0, sizeof(zeros));
|
|
||||||
setRegisters(MCP_TXB0CTRL, zeros, 14);
|
setRegisters(MCP_TXB0CTRL, zeros, 14);
|
||||||
setRegisters(MCP_TXB1CTRL, zeros, 14);
|
setRegisters(MCP_TXB1CTRL, zeros, 14);
|
||||||
setRegisters(MCP_TXB2CTRL, zeros, 14);
|
setRegisters(MCP_TXB2CTRL, zeros, 14);
|
||||||
@@ -240,28 +230,26 @@ CAN_Error MCP2515_reset(void)
|
|||||||
|
|
||||||
// receives all valid messages using either Standard or Extended Identifiers that
|
// receives all valid messages using either Standard or Extended Identifiers that
|
||||||
// meet filter criteria. RXF0 is applied for RXB0, RXF1 is applied for RXB1
|
// meet filter criteria. RXF0 is applied for RXB0, RXF1 is applied for RXB1
|
||||||
modifyRegister(MCP_RXB0CTRL,
|
MCP2515_Modify_Register(hcan, MCP_RXB0CTRL, RXBnCTRL_RXM_MASK | RXB0CTRL_BUKT | RXB0CTRL_FILHIT_MASK,
|
||||||
RXBnCTRL_RXM_MASK | RXB0CTRL_BUKT | RXB0CTRL_FILHIT_MASK,
|
|
||||||
RXBnCTRL_RXM_STDEXT | RXB0CTRL_BUKT | RXB0CTRL_FILHIT);
|
RXBnCTRL_RXM_STDEXT | RXB0CTRL_BUKT | RXB0CTRL_FILHIT);
|
||||||
modifyRegister(MCP_RXB1CTRL,
|
MCP2515_Modify_Register(hcan, MCP_RXB1CTRL, RXBnCTRL_RXM_MASK | RXB1CTRL_FILHIT_MASK,
|
||||||
RXBnCTRL_RXM_MASK | RXB1CTRL_FILHIT_MASK,
|
|
||||||
RXBnCTRL_RXM_STDEXT | RXB1CTRL_FILHIT);
|
RXBnCTRL_RXM_STDEXT | RXB1CTRL_FILHIT);
|
||||||
|
|
||||||
// clear filters and masks
|
// clear filters and masks
|
||||||
// do not filter any standard frames for RXF0 used by RXB0
|
// do not filter any standard frames for RXF0 used by RXB0
|
||||||
// do not filter any extended frames for RXF1 used by RXB1
|
// do not filter any extended frames for RXF1 used by RXB1
|
||||||
RXF filters[] = {RXF0, RXF1, RXF2, RXF3, RXF4, RXF5};
|
RXF filters[] = {RXF0, RXF1, RXF2, RXF3, RXF4, RXF5};
|
||||||
for (uint8_t i=0; i<6; i++) {
|
for (uint8_t i = 0; i < 6; i++) {
|
||||||
uint8_t ext = (i == 1);
|
uint8_t ext = (i == 1);
|
||||||
CAN_Error result = MCP_setFilter(filters[i], ext, 0);
|
CAN_Error result = MCP2515_Set_Filter(hcan, filters[i], ext, 0);
|
||||||
if (result != ERROR_OK) {
|
if (result != ERROR_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
MASK masks[] = {MASK0, MASK1};
|
MASK masks[] = {MASK0, MASK1};
|
||||||
for (int i=0; i<2; i++) {
|
for (int i = 0; i < 2; i++) {
|
||||||
CAN_Error result = MCP_setFilterMask(masks[i], 1, 0);
|
CAN_Error result = MCP2515_Set_Filter_Mask(hcan, masks[i], 1, 0);
|
||||||
if (result != ERROR_OK) {
|
if (result != ERROR_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
@@ -270,79 +258,23 @@ CAN_Error MCP2515_reset(void)
|
|||||||
return ERROR_OK;
|
return ERROR_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_reset(void)
|
CAN_Error MCP2515_Set_Listen_Only_Mode(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
return MCP2515_Set_Mode(hcan, CANCTRL_REQOP_LISTENONLY);
|
||||||
startSPI();
|
|
||||||
SPI_transfer(INSTRUCTION_RESET);
|
|
||||||
endSPI();
|
|
||||||
|
|
||||||
HAL_Delay(10);
|
|
||||||
|
|
||||||
uint8_t zeros[14];
|
|
||||||
memset(zeros, 0, sizeof(zeros));
|
|
||||||
setRegisters(MCP_TXB0CTRL, zeros, 14);
|
|
||||||
setRegisters(MCP_TXB1CTRL, zeros, 14);
|
|
||||||
setRegisters(MCP_TXB2CTRL, zeros, 14);
|
|
||||||
|
|
||||||
setRegister(MCP_RXB0CTRL, 0);
|
|
||||||
setRegister(MCP_RXB1CTRL, 0);
|
|
||||||
|
|
||||||
setRegister(MCP_CANINTE, CANINTF_RX0IF | CANINTF_RX1IF | CANINTF_ERRIF | CANINTF_MERRF);
|
|
||||||
|
|
||||||
// receives all valid messages using either Standard or Extended Identifiers that
|
|
||||||
// meet filter criteria. RXF0 is applied for RXB0, RXF1 is applied for RXB1
|
|
||||||
modifyRegister(MCP_RXB0CTRL,
|
|
||||||
RXBnCTRL_RXM_MASK | RXB0CTRL_BUKT | RXB0CTRL_FILHIT_MASK,
|
|
||||||
RXBnCTRL_RXM_STDEXT | RXB0CTRL_BUKT | RXB0CTRL_FILHIT);
|
|
||||||
modifyRegister(MCP_RXB1CTRL,
|
|
||||||
RXBnCTRL_RXM_MASK | RXB1CTRL_FILHIT_MASK,
|
|
||||||
RXBnCTRL_RXM_STDEXT | RXB1CTRL_FILHIT);
|
|
||||||
|
|
||||||
// clear filters and masks
|
|
||||||
// do not filter any standard frames for RXF0 used by RXB0
|
|
||||||
// do not filter any extended frames for RXF1 used by RXB1
|
|
||||||
RXF filters[] = {RXF0, RXF1, RXF2, RXF3, RXF4, RXF5};
|
|
||||||
for (int i=0; i<6; i++) {
|
|
||||||
uint8_t ext = (i == 1);
|
|
||||||
CAN_Error result = MCP_setFilter(filters[i], ext, 0);
|
|
||||||
if (result != ERROR_OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
MASK masks[] = {MASK0, MASK1};
|
|
||||||
for (int i=0; i<2; i++) {
|
|
||||||
CAN_Error result = MCP_setFilterMask(masks[i], 1, 0);
|
|
||||||
if (result != ERROR_OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return ERROR_OK;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_setListenOnlyMode()
|
CAN_Error MCP2515_Set_Sleep_Mode(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
return MCP2515_Set_Mode(hcan, CANCTRL_REQOP_SLEEP);
|
||||||
return setMode(CANCTRL_REQOP_LISTENONLY);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_setSleepMode()
|
CAN_Error MCP2515_Set_Loopback_Mode(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
return MCP2515_Set_Mode(hcan, CANCTRL_REQOP_LOOPBACK);
|
||||||
return setMode(CANCTRL_REQOP_SLEEP);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_setLoopbackMode()
|
CAN_Error MCP2515_Set_Normal_Mode(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
return MCP2515_Set_Mode(hcan, CANCTRL_REQOP_NORMAL);
|
||||||
return setMode(CANCTRL_REQOP_LOOPBACK);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_setNormalMode()
|
CAN_Error MCP2515_Set_Bitrate_Clock(MCP2515_HandleTypeDef* hcan, CAN_SPEED canSpeed, CAN_CLOCK canClock) {
|
||||||
{
|
|
||||||
return setMode(CANCTRL_REQOP_NORMAL);
|
|
||||||
}
|
|
||||||
|
|
||||||
CAN_Error MCP_setBitrateClock(CAN_SPEED canSpeed, CAN_CLOCK canClock)
|
|
||||||
{
|
|
||||||
CAN_Error error = setConfigMode();
|
CAN_Error error = setConfigMode();
|
||||||
if (error != ERROR_OK) {
|
if (error != ERROR_OK) {
|
||||||
return error;
|
return error;
|
||||||
@@ -350,11 +282,9 @@ CAN_Error MCP_setBitrateClock(CAN_SPEED canSpeed, CAN_CLOCK canClock)
|
|||||||
|
|
||||||
uint8_t set, cfg1, cfg2, cfg3;
|
uint8_t set, cfg1, cfg2, cfg3;
|
||||||
set = 1;
|
set = 1;
|
||||||
switch (canClock)
|
switch (canClock) {
|
||||||
{
|
|
||||||
case (MCP_8MHZ):
|
case (MCP_8MHZ):
|
||||||
switch (canSpeed)
|
switch (canSpeed) {
|
||||||
{
|
|
||||||
case (CAN_5KBPS): // 5KBPS
|
case (CAN_5KBPS): // 5KBPS
|
||||||
cfg1 = MCP_8MHz_5kBPS_CFG1;
|
cfg1 = MCP_8MHz_5kBPS_CFG1;
|
||||||
cfg2 = MCP_8MHz_5kBPS_CFG2;
|
cfg2 = MCP_8MHz_5kBPS_CFG2;
|
||||||
@@ -446,8 +376,7 @@ CAN_Error MCP_setBitrateClock(CAN_SPEED canSpeed, CAN_CLOCK canClock)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case (MCP_16MHZ):
|
case (MCP_16MHZ):
|
||||||
switch (canSpeed)
|
switch (canSpeed) {
|
||||||
{
|
|
||||||
case (CAN_5KBPS): // 5Kbps
|
case (CAN_5KBPS): // 5Kbps
|
||||||
cfg1 = MCP_16MHz_5kBPS_CFG1;
|
cfg1 = MCP_16MHz_5kBPS_CFG1;
|
||||||
cfg2 = MCP_16MHz_5kBPS_CFG2;
|
cfg2 = MCP_16MHz_5kBPS_CFG2;
|
||||||
@@ -539,8 +468,7 @@ CAN_Error MCP_setBitrateClock(CAN_SPEED canSpeed, CAN_CLOCK canClock)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case (MCP_20MHZ):
|
case (MCP_20MHZ):
|
||||||
switch (canSpeed)
|
switch (canSpeed) {
|
||||||
{
|
|
||||||
case (CAN_33KBPS): // 33.333Kbps
|
case (CAN_33KBPS): // 33.333Kbps
|
||||||
cfg1 = MCP_20MHz_33k3BPS_CFG1;
|
cfg1 = MCP_20MHz_33k3BPS_CFG1;
|
||||||
cfg2 = MCP_20MHz_33k3BPS_CFG2;
|
cfg2 = MCP_20MHz_33k3BPS_CFG2;
|
||||||
@@ -624,32 +552,24 @@ CAN_Error MCP_setBitrateClock(CAN_SPEED canSpeed, CAN_CLOCK canClock)
|
|||||||
setRegister(MCP_CNF3, cfg3);
|
setRegister(MCP_CNF3, cfg3);
|
||||||
return ERROR_OK;
|
return ERROR_OK;
|
||||||
}
|
}
|
||||||
else {
|
|
||||||
return ERROR_FAIL;
|
return ERROR_FAIL;
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_setBitrate( CAN_SPEED canSpeed)
|
void MCP2515_Request_To_Send(MCP2515_HandleTypeDef* hcan, uint8_t instruction) {
|
||||||
{
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_RESET);
|
||||||
return MCP_setBitrateClock(canSpeed, MCP_16MHZ);
|
MCP2515_SPI_transfer(hcan, instruction);
|
||||||
|
HAL_GPIO_WritePin(hcan->cs_port, hcan->cs_pin, GPIO_PIN_SET);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
CAN_Error MCP2515_Send_Message_To(MCP2515_HandleTypeDef* hcan, TXBn txbn, can_frame* frame)
|
||||||
void MCP_RequestToSend(uint8_t instruction)
|
// TXBm is just 0,1,2 for txbox number
|
||||||
{
|
|
||||||
startSPI();
|
|
||||||
SPI_transfer(instruction);
|
|
||||||
endSPI();
|
|
||||||
}
|
|
||||||
|
|
||||||
CAN_Error MCP_sendMessageTo(TXBn txbn, can_frame *frame)
|
|
||||||
//TXBm is just 0,1,2 for txbox number
|
|
||||||
{
|
{
|
||||||
if (frame->can_dlc > CAN_MAX_DLEN) {
|
if (frame->can_dlc > CAN_MAX_DLEN) {
|
||||||
return ERROR_FAILTX;
|
return ERROR_FAILTX;
|
||||||
}
|
}
|
||||||
|
|
||||||
//Todo, fix these magic numbers, but not with something as awful as the og arduino library
|
// Todo, fix these magic numbers, but not with something as awful as the og arduino library
|
||||||
uint8_t load_addr = (2 * txbn) | 0x40;
|
uint8_t load_addr = (2 * txbn) | 0x40;
|
||||||
|
|
||||||
uint8_t rts_addr = (1 << txbn) | 0x80;
|
uint8_t rts_addr = (1 << txbn) | 0x80;
|
||||||
@@ -660,64 +580,58 @@ CAN_Error MCP_sendMessageTo(TXBn txbn, can_frame *frame)
|
|||||||
uint8_t rtr = !!(frame->can_id & CAN_RTR_FLAG);
|
uint8_t rtr = !!(frame->can_id & CAN_RTR_FLAG);
|
||||||
uint32_t id = (frame->can_id & (ext ? CAN_EFF_MASK : CAN_SFF_MASK));
|
uint32_t id = (frame->can_id & (ext ? CAN_EFF_MASK : CAN_SFF_MASK));
|
||||||
|
|
||||||
prepareId(data, ext, id);
|
MCP2515_Prepare_Id(data, ext, id);
|
||||||
|
|
||||||
data[MCP_DLC] = rtr ? (frame->can_dlc | RTR_MASK) : frame->can_dlc;
|
data[MCP_DLC] = rtr ? (frame->can_dlc | RTR_MASK) : frame->can_dlc;
|
||||||
|
|
||||||
for(int i = 0; i < frame->can_dlc; i++){
|
for (int i = 0; i < frame->can_dlc; i++) {
|
||||||
data[MCP_DATA+i]=frame->data[i];
|
data[MCP_DATA + i] = frame->data[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
// memcpy(&data[MCP_DATA], frame->data, frame->can_dlc);
|
// memcpy(&data[MCP_DATA], frame->data, frame->can_dlc);
|
||||||
|
|
||||||
loadTx(load_addr, data, 5 + frame->can_dlc);
|
loadTx(load_addr, data, 5 + frame->can_dlc);
|
||||||
//setRegisters(load_addr, data, 5 + frame->can_dlc);
|
// setRegisters(load_addr, data, 5 + frame->can_dlc);
|
||||||
|
|
||||||
//modifyRegister(txbuf->CTRL, TXB_TXREQ, TXB_TXREQ);
|
// MCP2515_Modify_Register(hcan, txbuf->CTRL, TXB_TXREQ, TXB_TXREQ);
|
||||||
//modifyRegister(rts_addr, TXB_TXREQ, TXB_TXREQ);
|
// MCP2515_Modify_Register(hcan, rts_addr, TXB_TXREQ, TXB_TXREQ);
|
||||||
MCP_RequestToSend(rts_addr);
|
MCP_RequestToSend(rts_addr);
|
||||||
//setRegister(rts_addr, TXB_TXREQ);
|
// setRegister(rts_addr, TXB_TXREQ);
|
||||||
|
|
||||||
uint8_t ctrl = readRegister(rts_addr);
|
uint8_t ctrl = MCP2515_Read_Registers(hcan, rts_addr);
|
||||||
if ((ctrl & (TXB_ABTF | TXB_MLOA | TXB_TXERR)) != 0) {
|
if ((ctrl & (TXB_ABTF | TXB_MLOA | TXB_TXERR)) != 0) {
|
||||||
return ERROR_FAILTX;
|
return ERROR_FAILTX;
|
||||||
}
|
}
|
||||||
return ERROR_OK;
|
return ERROR_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_sendMessage(can_frame *frame)
|
CAN_Error MCP2515_Send_Message(MCP2515_HandleTypeDef* hcan, can_frame* frame) {
|
||||||
{
|
|
||||||
if (frame->can_dlc > CAN_MAX_DLEN) {
|
if (frame->can_dlc > CAN_MAX_DLEN) {
|
||||||
return ERROR_FAILTX;
|
return ERROR_FAILTX;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
for (uint8_t i = 0; i < N_TXBUFFERS; i++) {
|
||||||
for (uint8_t i=0; i<N_TXBUFFERS; i++) {
|
uint8_t ctrlval = MCP2515_Read_Registers(hcan, (i + 3) << 4);
|
||||||
uint8_t ctrlval = readRegister((i+3)<<4);
|
if ((ctrlval & TXB_TXREQ) == 0) {
|
||||||
if ( (ctrlval & TXB_TXREQ) == 0 ) {
|
return MCP2515_Send_Message_To(hcan, i, frame);
|
||||||
return MCP_sendMessageTo(i, frame);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return ERROR_ALLTXBUSY;
|
return ERROR_ALLTXBUSY;
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_readMessageFrom(RXBn rxbn, can_frame *frame)
|
CAN_Error MCP2515_Read_Message_From(MCP2515_HandleTypeDef* hcan, RXBn rxbn, can_frame* frame) {
|
||||||
{
|
|
||||||
|
|
||||||
|
|
||||||
uint8_t readCommand = (rxbn << 2) | 0x90;
|
uint8_t readCommand = (rxbn << 2) | 0x90;
|
||||||
|
|
||||||
rx_reg_t rxReg;
|
rx_reg_t rxReg;
|
||||||
|
|
||||||
readRx(readCommand, rxReg.rx_reg_array, sizeof(rxReg.rx_reg_array));
|
readRx(readCommand, rxReg.rx_reg_array, sizeof(rxReg.rx_reg_array));
|
||||||
|
|
||||||
uint32_t id = (rxReg.rx_reg_array[MCP_SIDH]<<3) + (rxReg.rx_reg_array[MCP_SIDL]>>5);
|
uint32_t id = (rxReg.rx_reg_array[MCP_SIDH] << 3) + (rxReg.rx_reg_array[MCP_SIDL] >> 5);
|
||||||
|
|
||||||
if ( (rxReg.rx_reg_array[MCP_SIDL] & TXB_EXIDE_MASK) == TXB_EXIDE_MASK ) {
|
if ((rxReg.rx_reg_array[MCP_SIDL] & TXB_EXIDE_MASK) == TXB_EXIDE_MASK) {
|
||||||
id = (id<<2) + (rxReg.rx_reg_array[MCP_SIDL] & 0x03);
|
id = (id << 2) + (rxReg.rx_reg_array[MCP_SIDL] & 0x03);
|
||||||
id = (id<<8) + rxReg.rx_reg_array[MCP_EID8];
|
id = (id << 8) + rxReg.rx_reg_array[MCP_EID8];
|
||||||
id = (id<<8) + rxReg.rx_reg_array[MCP_EID0];
|
id = (id << 8) + rxReg.rx_reg_array[MCP_EID0];
|
||||||
id |= CAN_EFF_FLAG;
|
id |= CAN_EFF_FLAG;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -726,9 +640,8 @@ CAN_Error MCP_readMessageFrom(RXBn rxbn, can_frame *frame)
|
|||||||
return ERROR_FAIL;
|
return ERROR_FAIL;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// 0x60 or 0x70
|
||||||
//0x60 or 0x70
|
uint8_t ctrl = MCP2515_Read_Registers(hcan, (rxbn + 6) << 4);
|
||||||
uint8_t ctrl = readRegister((rxbn + 6) << 4);
|
|
||||||
if (ctrl & RXBnCTRL_RTR) {
|
if (ctrl & RXBnCTRL_RTR) {
|
||||||
id |= CAN_RTR_FLAG;
|
id |= CAN_RTR_FLAG;
|
||||||
}
|
}
|
||||||
@@ -745,22 +658,20 @@ CAN_Error MCP_readMessageFrom(RXBn rxbn, can_frame *frame)
|
|||||||
frame->data[6] = rxReg.RXBnD6;
|
frame->data[6] = rxReg.RXBnD6;
|
||||||
frame->data[7] = rxReg.RXBnD7;
|
frame->data[7] = rxReg.RXBnD7;
|
||||||
|
|
||||||
|
// Clear the inbox interrupt, 0x1 or 0x2
|
||||||
//Clear the inbox interrupt, 0x1 or 0x2
|
MCP2515_Modify_Register(hcan, MCP_CANINTF, rxbn + 1, 0);
|
||||||
modifyRegister(MCP_CANINTF, rxbn + 1, 0);
|
|
||||||
|
|
||||||
return ERROR_OK;
|
return ERROR_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Error MCP_readMessage(can_frame *frame)
|
CAN_Error MCP2515_Read_Message(MCP2515_HandleTypeDef* hcan, can_frame* frame) {
|
||||||
{
|
|
||||||
CAN_Error rc;
|
CAN_Error rc;
|
||||||
uint8_t stat = getStatus();
|
uint8_t stat = MCP2515_Get_Status(hcan);
|
||||||
|
|
||||||
if ( stat & STAT_RX0IF ) {
|
if (stat & STAT_RX0IF) {
|
||||||
rc = MCP_readMessageFrom(RXB0, frame);
|
rc = MCP2515_Read_Message_From(RXB0, frame);
|
||||||
} else if ( stat & STAT_RX1IF ) {
|
} else if (stat & STAT_RX1IF) {
|
||||||
rc = MCP_readMessageFrom(RXB1, frame);
|
rc = MCP2515_Read_Message_From(RXB1, frame);
|
||||||
} else {
|
} else {
|
||||||
rc = ERROR_NOMSG;
|
rc = ERROR_NOMSG;
|
||||||
}
|
}
|
||||||
@@ -768,80 +679,66 @@ CAN_Error MCP_readMessage(can_frame *frame)
|
|||||||
return rc;
|
return rc;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t MCP_checkReceive(void)
|
uint8_t MCP2515_Check_Receive(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
uint8_t res = MCP2515_Get_Status(hcan);
|
||||||
uint8_t res = getStatus();
|
if (res & STAT_RXIF_MASK) {
|
||||||
if ( res & STAT_RXIF_MASK ) {
|
|
||||||
return 1;
|
return 1;
|
||||||
} else {
|
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t MCP_getErrorFlags(void)
|
uint8_t MCP2515_Get_Error_Flags(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
return MCP2515_Read_Registers(hcan, MCP_EFLG);
|
||||||
return readRegister(MCP_EFLG);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t MCP_checkError(void)
|
uint8_t MCP2515_Check_Error(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
|
||||||
uint8_t eflg = MCP_getErrorFlags();
|
uint8_t eflg = MCP_getErrorFlags();
|
||||||
|
|
||||||
if ( eflg & EFLG_ERRORMASK ) {
|
if (eflg & EFLG_ERRORMASK) {
|
||||||
return 1;
|
return 1;
|
||||||
} else {
|
} else {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void MCP2515_Clear_RXn_OVR_Flags(MCP2515_HandleTypeDef* hcan) {
|
||||||
void MCP_clearRXnOVRFlags(void)
|
MCP2515_Modify_Register(hcan, MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0);
|
||||||
{
|
|
||||||
modifyRegister(MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t MCP_getInterrupts(void)
|
uint8_t MCP2515_Get_Interrupts(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
return MCP2515_Read_Registers(hcan, MCP_CANINTF);
|
||||||
return readRegister(MCP_CANINTF);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void MCP_clearInterrupts(void)
|
void MCP2515_Clear_Interrupts(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
|
||||||
setRegister(MCP_CANINTF, 0);
|
setRegister(MCP_CANINTF, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t MCP_getInterruptMask(void)
|
uint8_t MCP2515_Get_Interrupt_Mask(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
return MCP2515_Read_Registers(hcan, MCP_CANINTE);
|
||||||
return readRegister(MCP_CANINTE);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void MCP_clearTXInterrupts(void)
|
void MCP2515_Clear_TX_Interrupts(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
MCP2515_Modify_Register(hcan, MCP_CANINTF, (CANINTF_TX0IF | CANINTF_TX1IF | CANINTF_TX2IF), 0);
|
||||||
modifyRegister(MCP_CANINTF, (CANINTF_TX0IF | CANINTF_TX1IF | CANINTF_TX2IF), 0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void MCP_clearRXnOVR(void)
|
void MCP2515_Clear_RXn_OVR(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
|
||||||
uint8_t eflg = MCP_getErrorFlags();
|
uint8_t eflg = MCP_getErrorFlags();
|
||||||
if (eflg != 0) {
|
if (eflg != 0) {
|
||||||
MCP_clearRXnOVRFlags();
|
MCP_clearRXnOVRFlags();
|
||||||
MCP_clearInterrupts();
|
MCP_clearInterrupts();
|
||||||
//modifyRegister(MCP_CANINTF, CANINTF_ERRIF, 0);
|
// MCP2515_Modify_Register(hcan, MCP_CANINTF, CANINTF_ERRIF, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void MCP_clearMERR()
|
void MCP2515_Clear_MERR(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
// MCP2515_Modify_Register(hcan, MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0);
|
||||||
//modifyRegister(MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0);
|
// clearInterrupts();
|
||||||
//clearInterrupts();
|
MCP2515_Modify_Register(hcan, MCP_CANINTF, CANINTF_MERRF, 0);
|
||||||
modifyRegister(MCP_CANINTF, CANINTF_MERRF, 0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void MCP_clearERRIF()
|
void MCP2515_Clear_ERRIF(MCP2515_HandleTypeDef* hcan) {
|
||||||
{
|
// MCP2515_Modify_Register(hcan, MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0);
|
||||||
//modifyRegister(MCP_EFLG, EFLG_RX0OVR | EFLG_RX1OVR, 0);
|
// clearInterrupts();
|
||||||
//clearInterrupts();
|
MCP2515_Modify_Register(hcan, MCP_CANINTF, CANINTF_ERRIF, 0);
|
||||||
modifyRegister(MCP_CANINTF, CANINTF_ERRIF, 0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
83
mcp2515.h
83
mcp2515.h
@@ -28,9 +28,7 @@ typedef enum {
|
|||||||
CLKOUT_DIV8 = 0x3,
|
CLKOUT_DIV8 = 0x3,
|
||||||
} CAN_CLKOUT;
|
} CAN_CLKOUT;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum { MCP_20MHZ, MCP_16MHZ, MCP_8MHZ } CAN_CLOCK;
|
||||||
MCP_20MHZ, MCP_16MHZ, MCP_8MHZ
|
|
||||||
} CAN_CLOCK;
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
CAN_5KBPS,
|
CAN_5KBPS,
|
||||||
@@ -51,48 +49,51 @@ typedef enum {
|
|||||||
CAN_1000KBPS
|
CAN_1000KBPS
|
||||||
} CAN_SPEED;
|
} CAN_SPEED;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum { MASK0, MASK1 } MASK;
|
||||||
MASK0, MASK1
|
|
||||||
} MASK;
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum { RXF0 = 0, RXF1 = 1, RXF2 = 2, RXF3 = 3, RXF4 = 4, RXF5 = 5 } RXF;
|
||||||
RXF0 = 0, RXF1 = 1, RXF2 = 2, RXF3 = 3, RXF4 = 4, RXF5 = 5
|
|
||||||
} RXF;
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum { TXB0 = 0, TXB1 = 1, TXB2 = 2 } TXBn;
|
||||||
TXB0 = 0, TXB1 = 1, TXB2 = 2
|
|
||||||
} TXBn;
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum { RXB0 = 0, RXB1 = 1 } RXBn;
|
||||||
RXB0 = 0, RXB1 = 1
|
|
||||||
} RXBn;
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
SPI_HandleTypeDef* hspi;
|
||||||
|
GPIO_TypeDef* cs_port;
|
||||||
|
uint16_t cs_pin;
|
||||||
|
} MCP2515_HandleTypeDef;
|
||||||
|
|
||||||
CAN_Error MCP_reset(void);//
|
void MCP2515_Init(MCP2515_HandleTypeDef* hcan, SPI_HandleTypeDef* hspi, GPIO_TypeDef* cs_port, uint16_t cs_pin);
|
||||||
CAN_Error MCP_setListenOnlyMode();//
|
CAN_Error MCP2515_Reset(MCP2515_HandleTypeDef* hcan);
|
||||||
CAN_Error MCP_setSleepMode();//
|
uint8_t MCP2515_Get_Status(MCP2515_HandleTypeDef* hcan);
|
||||||
CAN_Error MCP_setLoopbackMode();//
|
|
||||||
CAN_Error MCP_setNormalMode();//
|
CAN_Error MCP2515_Set_Listen_Only_Mode(MCP2515_HandleTypeDef* hcan);
|
||||||
CAN_Error MCP_setBitrate(CAN_SPEED canSpeed);//
|
CAN_Error MCP2515_Set_Sleep_Mode(MCP2515_HandleTypeDef* hcan);
|
||||||
CAN_Error MCP_setBitrateClock(CAN_SPEED canSpeed, CAN_CLOCK canClock); //
|
CAN_Error MCP2515_Set_Loopback_Mode(MCP2515_HandleTypeDef* hcan);
|
||||||
CAN_Error MCP_setFilterMask(MASK num, uint8_t ext, uint32_t ulData);//
|
CAN_Error MCP2515_Set_Normal_Mode(MCP2515_HandleTypeDef* hcan);
|
||||||
CAN_Error MCP_setFilter(RXF num, uint8_t ext, uint32_t ulData);//
|
|
||||||
CAN_Error MCP_sendMessageTo(TXBn txbn, can_frame *frame);//
|
CAN_Error MCP2515_Set_Bitrate_Clock(MCP2515_HandleTypeDef* hcan, CAN_SPEED canSpeed, CAN_CLOCK canClock);
|
||||||
CAN_Error MCP_sendMessage(can_frame *frame);//
|
|
||||||
CAN_Error MCP_readMessageFrom(RXBn rxbn, can_frame *frame);//
|
CAN_Error MCP2515_Set_Filter_Mask(MCP2515_HandleTypeDef* hcan, MASK mask, uint8_t ext, uint32_t ulData);
|
||||||
CAN_Error MCP_readMessage(can_frame *frame);//
|
CAN_Error MCP2515_Set_Filter(MCP2515_HandleTypeDef* hcan, RXF num, uint8_t ext, uint32_t ulData);
|
||||||
uint8_t MCP_checkReceive(void);//
|
|
||||||
uint8_t MCP_checkError(void);//
|
CAN_Error MCP2515_Send_Message_To(MCP2515_HandleTypeDef* hcan, TXBn txbn, can_frame* frame);
|
||||||
uint8_t MCP_getErrorFlags(void);//
|
CAN_Error MCP2515_Send_Message(MCP2515_HandleTypeDef* hcan, can_frame* frame);
|
||||||
void MCP_clearRXnOVRFlags(void);//
|
|
||||||
uint8_t MCP_getInterrupts(void);//
|
CAN_Error MCP2515_Read_Message_From(MCP2515_HandleTypeDef* hcan, RXBn rxbn, can_frame* frame);
|
||||||
uint8_t MCP_getInterruptMask(void);//
|
CAN_Error MCP2515_Read_Message(MCP2515_HandleTypeDef* hcan, can_frame* frame);
|
||||||
void MCP_clearInterrupts(void);//
|
|
||||||
void MCP_clearTXInterrupts(void);
|
uint8_t MCP2515_Check_Receive(MCP2515_HandleTypeDef* hcan);
|
||||||
uint8_t MCP_getStatus(void);//
|
uint8_t MCP2515_Get_Error_Flags(MCP2515_HandleTypeDef* hcan);
|
||||||
void MCP_clearRXnOVR(void);//
|
uint8_t MCP2515_Check_Error(MCP2515_HandleTypeDef* hcan);
|
||||||
void MCP_clearMERR();//
|
|
||||||
void MCP_clearERRIF();//
|
void MCP2515_Clear_RXn_OVR_Flags(MCP2515_HandleTypeDef* hcan);
|
||||||
|
uint8_t MCP2515_Get_Interrupts(MCP2515_HandleTypeDef* hcan);
|
||||||
|
void MCP2515_Clear_Interrupts(MCP2515_HandleTypeDef* hcan);
|
||||||
|
uint8_t MCP2515_Get_Interrupt_Mask(MCP2515_HandleTypeDef* hcan);
|
||||||
|
void MCP2515_Clear_TX_Interrupts(MCP2515_HandleTypeDef* hcan);
|
||||||
|
void MCP2515_Clear_RXn_OVR(MCP2515_HandleTypeDef* hcan);
|
||||||
|
void MCP2515_Clear_MERR(MCP2515_HandleTypeDef* hcan);
|
||||||
|
void MCP2515_Clear_ERRIF(MCP2515_HandleTypeDef* hcan);
|
||||||
|
|
||||||
#endif /* APPLICATION_USER_INC_MCP2515_H_ */
|
#endif /* APPLICATION_USER_INC_MCP2515_H_ */
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user