CAN Bus Support

@Owen_Williams First of all, thanks for the amazing port for the G431-ESC device! On that base i added simple CAN-bus features to it.
If anyone is interested at it, here is the code for it - i know not the best way to publish source-code in that form :wink:, anyhow here it is:
SimpleCan.h:

#pragma once

#include "Arduino.h"
#include <stm32g4xx_hal_fdcan.h>

enum CanSpeed
{
	Mbit1 = 10,
	Kbit500 = 20,
	Kbit250 = 40,
	Kbit125 = 80	
};

/**
 CAN wrapper for G431 board.
*/
class SimpleCan
{
public:
	class RxHandler
	{
	public:
		RxHandler(uint16_t dataLength, void(*callback)(FDCAN_RxHeaderTypeDef rxHeader, uint8_t *rxData));
		~RxHandler();

		void notify(FDCAN_HandleTypeDef *hfdcan);
	private:
		FDCAN_RxHeaderTypeDef _rxHeader;
		uint8_t *_rxData;
		void(*_callback)(FDCAN_RxHeaderTypeDef, uint8_t *);
	};
	
	SimpleCan(bool terminateTransceiver);

	HAL_StatusTypeDef init(CanSpeed speed);
	HAL_StatusTypeDef configFilter(FDCAN_FilterTypeDef *filterDef);
	HAL_StatusTypeDef configGlobalFilter(
		uint32_t nonMatchingStd,
		uint32_t nonMatchingExt,
		uint32_t rejectRemoteStd,
		uint32_t rejectRemoteExt);
	HAL_StatusTypeDef activateNotification(RxHandler *rxHandler);
	HAL_StatusTypeDef deactivateNotification();
	HAL_StatusTypeDef start();
	HAL_StatusTypeDef stop();
	HAL_StatusTypeDef addMessageToTxFifoQ(
		FDCAN_TxHeaderTypeDef *pTxHeader,
		uint8_t *pTxData);
//private: interrupt handler needs access to it
	static FDCAN_HandleTypeDef _hfdcan1;
	static RxHandler *_rxHandler;
};

SimpleCan.cpp:

#include "SimpleCan.h"

// will be called from: HAL_FDCAN_Init
extern "C" void HAL_FDCAN_MspInit(FDCAN_HandleTypeDef *hfdcan);
extern "C" void FDCAN1_IT0_IRQHandler();
extern "C" void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs);

FDCAN_HandleTypeDef SimpleCan::_hfdcan1 = { };
SimpleCan::RxHandler* SimpleCan::_rxHandler = NULL;

SimpleCan::SimpleCan(bool terminateTransceiver)
{
	if (_hfdcan1.Instance != NULL)
	{
		Error_Handler();
	}

	_hfdcan1.Instance = FDCAN1;

	pinMode(CAN_SHDN, OUTPUT);
	pinMode(CAN_TERM, OUTPUT);

	digitalWrite(CAN_TERM, terminateTransceiver ? HIGH : LOW);
}

HAL_StatusTypeDef SimpleCan::start(void)
{
	digitalWrite(CAN_SHDN, LOW);
	return HAL_FDCAN_Start(&_hfdcan1);
}

HAL_StatusTypeDef SimpleCan::stop(void)
{
	digitalWrite(CAN_SHDN, HIGH);
	return HAL_FDCAN_Stop(&_hfdcan1);
}

HAL_StatusTypeDef SimpleCan::init(CanSpeed speed)
{
	FDCAN_InitTypeDef *init = &_hfdcan1.Init;
	
	init->ClockDivider = FDCAN_CLOCK_DIV1;
	init->FrameFormat = FDCAN_FRAME_FD_BRS;
	init->Mode = FDCAN_MODE_NORMAL;
	init->AutoRetransmission = DISABLE;
	init->TransmitPause = ENABLE;
	init->ProtocolException = DISABLE;
	
	// 1 MBit: NominalPrescaler = 10
	// see: http://www.bittiming.can-wiki.info/
	// 170MHz / Prescaler / SyncJumpWith / (TimeSeg1 + TimeSeg2 + SyncSeg) 
	// SyncSeg = SYNC_SEG = 1, TimeSeg1 = PROP_SEG + PHASE_SEG1, TimeSeg2 = PHASE_SEG2
	init->NominalPrescaler = (uint16_t) speed;
	init->NominalSyncJumpWidth = 1;
	init->NominalTimeSeg1 = 14;
	init->NominalTimeSeg2 = 2;

	init->DataPrescaler = 1;
	init->DataSyncJumpWidth = 4;
	init->DataTimeSeg1 = 5;
	init->DataTimeSeg2 = 4;
	init->StdFiltersNbr = 1;
	init->ExtFiltersNbr = 0;
	init->TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
	
	return HAL_FDCAN_Init(&_hfdcan1);
}

HAL_StatusTypeDef SimpleCan::configFilter(FDCAN_FilterTypeDef *filterDef)
{
	return HAL_FDCAN_ConfigFilter(&_hfdcan1, filterDef);
}

HAL_StatusTypeDef SimpleCan::configGlobalFilter(
	uint32_t nonMatchingStd,
	uint32_t nonMatchingExt,
	uint32_t rejectRemoteStd,
	uint32_t rejectRemoteExt)
{
	return HAL_FDCAN_ConfigGlobalFilter(&_hfdcan1, nonMatchingStd, nonMatchingExt, rejectRemoteStd, rejectRemoteExt);
}

HAL_StatusTypeDef SimpleCan::activateNotification(RxHandler *rxHandler)
{
	if (_rxHandler != NULL)
	{
		return HAL_ERROR;
	}
#if USE_HAL_FDCAN_REGISTER_CALLBACKS
	// This would make interrupt handling much easier and cleaner.
	// But how to activate it on Arduino platform?
	//_hfdcan1.Instance->RxFifo0Callback = ...;
#endif
	_rxHandler = rxHandler;
	return HAL_FDCAN_ActivateNotification(&_hfdcan1, FDCAN_IT_RX_FIFO0_NEW_MESSAGE, 0);
}

HAL_StatusTypeDef SimpleCan::deactivateNotification()
{
	_rxHandler = NULL;
	return HAL_FDCAN_DeactivateNotification(&_hfdcan1, FDCAN_IT_RX_FIFO0_NEW_MESSAGE);
}

HAL_StatusTypeDef SimpleCan::addMessageToTxFifoQ(
	FDCAN_TxHeaderTypeDef *pTxHeader,
	uint8_t *pTxData)
{
	return HAL_FDCAN_AddMessageToTxFifoQ(&_hfdcan1, pTxHeader, pTxData);
}

void HAL_FDCAN_MspInit(FDCAN_HandleTypeDef *hfdcan)
{
	if (hfdcan == NULL || hfdcan->Instance != FDCAN1)
	{
		return;
	}

	RCC_PeriphCLKInitTypeDef periphClkInit = { };
	
	HAL_RCCEx_GetPeriphCLKConfig(&periphClkInit);
	
	// Initializes the peripherals clocks
	periphClkInit.PeriphClockSelection |= RCC_PERIPHCLK_FDCAN;
	periphClkInit.FdcanClockSelection = RCC_FDCANCLKSOURCE_PCLK1;
	if (HAL_RCCEx_PeriphCLKConfig(&periphClkInit) != HAL_OK)
	{
		Error_Handler();
	}
	
	// Peripheral clock enable
	__HAL_RCC_FDCAN_CLK_ENABLE();

	__HAL_RCC_GPIOA_CLK_ENABLE();
	__HAL_RCC_GPIOB_CLK_ENABLE();
	
	// FDCAN1 GPIO Configuration
	// PA11 ------> FDCAN1_RX
	GPIO_InitTypeDef GPIO_InitStruct = { 0 };
	GPIO_InitStruct.Pin = GPIO_PIN_11;
	GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
	GPIO_InitStruct.Pull = GPIO_NOPULL;
	GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
	GPIO_InitStruct.Alternate = GPIO_AF9_FDCAN1;
	HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);

	// PB9 ------> FDCAN1_TX 
	GPIO_InitStruct.Pin = GPIO_PIN_9;
	GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
	GPIO_InitStruct.Pull = GPIO_NOPULL;
	GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
	GPIO_InitStruct.Alternate = GPIO_AF9_FDCAN1;
	HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);

	// FDCAN1 interrupt Init
	HAL_NVIC_SetPriority(FDCAN1_IT0_IRQn, 0, 0);
	HAL_NVIC_EnableIRQ(FDCAN1_IT0_IRQn);
}

void FDCAN1_IT0_IRQHandler(void)
{
	HAL_FDCAN_IRQHandler(&SimpleCan::_hfdcan1);
}

void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs)
{
	if ((RxFifo0ITs & FDCAN_IT_RX_FIFO0_NEW_MESSAGE) != RESET)
	{
		if (SimpleCan::_rxHandler == NULL)
		{
			return;
		}
		SimpleCan::_rxHandler->notify(hfdcan);
	}
}

SimpleCan::RxHandler::RxHandler(uint16_t dataLength, void (*callback)(FDCAN_RxHeaderTypeDef, uint8_t *))
{
	_rxData = new byte[dataLength];
	_callback = callback;
}

SimpleCan::RxHandler::~RxHandler()
{
	delete[] _rxData; 
}

void SimpleCan::RxHandler::notify(FDCAN_HandleTypeDef *hfdcan)
{
	if (HAL_FDCAN_GetRxMessage(hfdcan, FDCAN_RX_FIFO0, &_rxHeader, _rxData) != HAL_OK)
	{
		Error_Handler();
	}

	if (_callback != NULL)
	{
		_callback(_rxHeader, _rxData);
	}
}
1 Like

usage SimpleFocForG431Esc.ino:

#include <Arduino.h>
#include <SimpleFOC.h>
#include <math.h>
#include <SimpleCan.h>

const int MotorPolePairs = 4;
const Direction MotorNaturalDirection = CCW;
const float MotorZeroElectricAngle = 5.235;

static void handleCanMessage(FDCAN_RxHeaderTypeDef rxHeader, uint8_t *rxData);
static void init_CAN(void);
static String serialReceiveUserCommand(void);
static void Button_Down(void);
static float readNtc(void);
static float readVbus(void);

HardwareSerial Serial1(USART2_RX, USART2_TX);
BLDCDriver6PWM driver(PHASE_UH, PHASE_UL, PHASE_VH, PHASE_VL, PHASE_WH, PHASE_WL);
BLDCMotor motor(MotorPolePairs);
HallSensor sensor(HALL1, HALL2, HALL3, motor.pole_pairs);
SimpleCan can1(/*terminateTransceiver:*/true);
SimpleCan::RxHandler can1RxHandler(8, handleCanMessage);

FDCAN_TxHeaderTypeDef TxHeader;
uint8_t TxData[8];

static void hallA() { sensor.handleA(); }

static void hallB() { sensor.handleB(); }

static void hallC() { sensor.handleC(); }

void setup() {
	Serial1.begin(115200);
	Serial1.println();
	
	pinMode(LED_BUILTIN, OUTPUT);
	attachInterrupt(digitalPinToInterrupt(BUTTON), Button_Down, LOW);

	delay(100);

	sensor.enableInterrupts(hallA, hallB, hallC);
	sensor.init();

	motor.linkDriver(&driver);
	motor.linkSensor(&sensor);
	motor.controller = ControlType::voltage;

	driver.voltage_power_supply = 24;
	motor.foc_modulation = FOCModulationType::Trapezoid_120;
	motor.voltage_limit = 5;
	motor.voltage_sensor_align = 1;
	motor.useMonitoring(Serial1);

	driver.init();
	motor.init();
	//motor.initFOC();
	//Serial1.printf("zero electric angle: %10.4f\r\n", motor.zero_electric_angle);
	motor.initFOC(MotorZeroElectricAngle, MotorNaturalDirection);

	init_CAN();
}

void loop()
{
	static uint32_t triggerT1;
	static uint32_t triggerT2;
	uint32_t nowT = millis();

	if ((nowT - triggerT1) >= 1000)
	{
		Serial1.println();
		Serial1.printf("VBUS: %3.1f V\r\n", readVbus());
		Serial1.printf("TEMP: %4.1f C\r\n", readNtc());
		//Serial1.printf("POTI: %d\r\n", analogRead(POTENTIOMETER));
		triggerT1 = nowT;
	}
	if ((nowT - triggerT2) >= 100)
	{
		motor.monitor();
		triggerT2 = nowT;
	}

	motor.loopFOC();

	String command = serialReceiveUserCommand();
	motor.move();
	motor.command(command);
}

// utility function enabling serial communication the user
static String serialReceiveUserCommand() {
	// a string to hold incoming data
	static String received_chars;
	String command = "";

	while (Serial1.available()) {
		char inChar = (char)Serial1.read();
		received_chars += inChar;

		if (inChar == '\r')
		{
			command = received_chars;
			received_chars = "";
			Serial1.println(".");
		}
		else
		{
			Serial1.write(inChar);
		}
	}
	return command;
}

static float readVbus()
{
	const int AdcMaxValue = 1023;
	const float Factor = 3.3 / AdcMaxValue * (169.0 + 18.0) / 18.0;

	return analogRead(VBUS) * Factor;
}

static float readNtc() 
{
	const float ResistorBalance = 4700.0;
	const int AdcMaxValue = 1023;
	const float Beta = 3425;
	const float RoomTemp = 298.15; //[K]
	const float ResistorNtcRoomTemp = 10000.0;
	const float Factor1 =  ResistorBalance * AdcMaxValue;
	const float Factor2 = Beta * RoomTemp;
		
	float adcValue  = analogRead(TEMPERATURE);
	float resistorNtc = Factor1 / adcValue - ResistorBalance;
	float temperature = Factor2 / (Beta + RoomTemp * log(resistorNtc / ResistorNtcRoomTemp));

	return temperature - 273.15;
}

static void init_CAN()
{
	Serial1.println(can1.init(CanSpeed::Mbit1) == HAL_OK
		? "CAN: initialized."
		: "CAN: error when initializing.");

	FDCAN_FilterTypeDef sFilterConfig;

	// Configure Rx filter
	sFilterConfig.IdType = FDCAN_STANDARD_ID;
	sFilterConfig.FilterIndex = 0;
	sFilterConfig.FilterType = FDCAN_FILTER_MASK;
	sFilterConfig.FilterConfig = FDCAN_FILTER_TO_RXFIFO0;
	sFilterConfig.FilterID1 = 0x321;
	sFilterConfig.FilterID2 = 0x7FF;

	can1.configFilter(&sFilterConfig);
	can1.configGlobalFilter(FDCAN_REJECT, FDCAN_REJECT, FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE);
	can1.activateNotification(&can1RxHandler);
	
	Serial1.println(can1.start() == HAL_OK
		? "CAN: started."
		: "CAN: error when starting.");
}

static void handleCanMessage(FDCAN_RxHeaderTypeDef rxHeader, uint8_t *rxData)
{
	if ((rxHeader.Identifier != 0x321) || (rxHeader.IdType != FDCAN_STANDARD_ID) || (rxHeader.DataLength != FDCAN_DLC_BYTES_2))
	{
		return;
	}

	digitalToggle(LED_BUILTIN);
}

static void Button_Down()
{
	TxHeader.Identifier = 0x321;
	TxHeader.IdType = FDCAN_STANDARD_ID;
	TxHeader.TxFrameType = FDCAN_DATA_FRAME;
	TxHeader.DataLength = FDCAN_DLC_BYTES_2;
	TxHeader.ErrorStateIndicator = FDCAN_ESI_ACTIVE;
	TxHeader.BitRateSwitch = FDCAN_BRS_OFF;
	TxHeader.FDFormat = FDCAN_CLASSIC_CAN;
	TxHeader.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
	TxHeader.MessageMarker = 0;

	TxData[0] = 0x13;
	TxData[1] = 0xAD;

	Serial1.print("CAN: sending message ");
	Serial1.println(can1.addMessageToTxFifoQ(&TxHeader, TxData) == HAL_OK
		? "was ok."
		: "failed.");
}

@erwin74 - welcome and thankyou!

I’ve split this message because I want to see if there is any interest in spinning off a separate repo for a generic CAN library that supports many architectures.

STM32 for example has two implementations for CAN and FDCAN and esp32 does it a different way and I suspect there are generic SPI solutions our there too. A common API with multiple hardware implementations would be great!

I don’t have the bandwidth to start this right now but it is something I’d like to work on in 2021.

BTW: I tried and failed to get FDCAN working on this board. It was silently failing to send messages for me - so I’ll be looking at your code at some point!

CAN-FD could be useful for talking to duet3 controllers in the future.

@erwin74 - I got a chance to try out your fdcan code. Works! Thank you for helping me out.

I’m wondering whether my failed efforts were because I’d not terminated the other end of CAN? I didn’t think this would be necessary when running loopback internal.

I’m guessing you uncommented
//#define HAL_FDCAN_MODULE_ENABLED
in variant.h. I think I should push this to stm32duino so others don’t have to? It’s a non obvious step and without it you get loads of reference errors during linking.

Also I guess you added
#define VBUS PA0
What do you think this is for? It always comes up with 12V (in your code) even if I’m supplying 5 or 14V

Next step is to send more complex data and then see if I can link up a cheapo CAN tranceiver to an esp32 ā€˜master’.

Longer term we could try to create a CAN HAL library. This would probably mean that your SimpleFOC.h must have no dependency on stm32g4xx_hal_fdcan.h and we’d have several implementations.

Oh yes, CAN can be a diva.

Yes, you are right we need HAL_FDCAN_MODULE_ENABLED, forgot to tell.

I tried to measure the input voltage (PA0 is connected to the input voltage over a voltage divider) and the temperature (PB14 is connected to the NTC). Temperature seems to work, but the input voltage also doesn’t work in my sample - no idea, no time to investigate.

I do not work with Arduino often, mainly i use mbed or bare metal (HAL) to realize my projects. So i do not know if there exists a good CAN library in the Arduino ecosystem. But if there is, then we should better use this and add the leaking support for the boards to it (ESP32, STM32G431). I would not recomment to use my simple example as base for a new Arduino CAN library - CAN (FD) is a broad field, with all its possibilities (filters, fifo, …) @Owen_Williams What do you think?

I’ve pushed that change to stm32duino. My PR is still waiting for 2.0 release but they are almost done.

@erwin74 - I hope you don’t mind but I’ve used your code sample here:
https://github.com/owennewo/youtube_can

And mentioned it in a youtube video:
https://www.youtube.com/watch?v=c_iQgfNlFz8

I’d like to acknowledge you - if that is OK? Are you ok with me putting MIT license on that repo?

2 Likes

Hi @Owen_Williams, @erwin74

You make my day with [eXoCAN] :I I have spent / wasted a couple of days trying to figure out how to get CAN from Arduino on my STM32 Blue :).

Unfortunately, it seems that this MCU shares CAN pins with USB and it is not having both at the same time :frowning:

Do you know if eXoCAN works with STM32F407 or if there is a another equivalent library allowing CAN from Arduino that woks on this MCU?

I don’t have a blue pill (stm32f103) but if I did then I’d probably try the following:

  1. Don’t use the USB for programming - use the stlink instead. They’ve broken out the PA11 and PA12 pins separately which may suggest that they can be used for other things??
  2. This PeripheralPins.h (if this is the board/variant you are using?) suggests you can use an alternative CAN pins of PB8 and PB9

I’ve a jlcpcb board with an stm32f407 + can transceiver on order. If it doesn’t go up in a puff of smoke, I’ll give it a try in a few weeks.

The closes I have right now is a blackpill (stm32f411) but I’ve not played with it much.

I program the board using an STlink and use the USB as serial output for which I have to put some build_flags that I guess are causing the error since moving to PB8 and PB9 mdos not remve the issue until build_flags are removed.
The same behavior occurs by programming the board directly at the HAL level with CubeIDE … I guess it is related to some interrupts shared by both peripherals. I assumed that if you did not configure the USB, there would be no interference, but it seems that is not the case.

Captura de pantalla 2021-01-19 a las 22.37.22

Not sure of what errors you are getting. You can upload but get errors/hangs using CAN?

Perhaps you can use an ftdi → usb dongle and print to Serial1 instead of Serial. Serial1 I think will default to rx=PA10, tx=PA9. I’m not sure if this gets you anywhere though.

Everything was solved thanks to your ā€œmagic pointerā€ to eXoCAN library :slight_smile:

I ordered a USB to TTL dongle from AliExpress per week, … the solution to have CAN and Serial communications it is comming from China :slight_smile: In the mid term I will migrate to STM32F407 since is the MCU I chosen to develo may board.

1 Like

@Owen_Williams definitively use the code for whatever you need, as long it is helpfull - and doesn’t make any troubles :wink:

Good video btw.

1 Like

Is it an original STM32F103? I haven’t tried, but it should be possible to route both CAN and USB to different pins… in fact it is the default. Here a pic from the STM32CubeIDE…

Yes, it is an original STM32F103. The default assignment is PA12/PA11, but if you previously assign it to another peripheral, the alternative assignment is PB9 / PB9.

In my case even but even without assigning any pin to USB if you connect a USB then CAN it stops working. …so I have to chose between USB or CAN … or migrate to another MCU :slight_smile:

Hi @ erwin74 quote=ā€œerwin74, post:2, topic:407ā€]
DCAN_TxHeaderTypeDef TxHeader;
[/quote]

Hi @erwin74 I am trying to re implement your library so it can run on STM32F405RTG6. I have been able to get my implementation to work properly for sending messages but when I turn on notifications, if there are messages to receive it hangs. It happens indistinctly when there are messages generated by another device or when I put it in loopbkac mode. If you had a moment to review what I am doing wrong, would truly appreciate it :slight_smile:

PS: I have not come to implement the hadler part since just putting the callbakc crashes. The debugger says it receives an ā€œunexpected exceptionā€ and goes into an infinite loop.


SimpleCan.h

#ifndef __CAN__H
#define __CAN__H

#include "Arduino.h"
#include "stm32f4xx_hal_can.h"


// Value needed for prescaler. depends 
// on CLK configuration
enum CanSpeed
{
	Kbit500 = 5,
	Kbit250 = 10,
	Kbit125 = 20,
	Kbit100 = 25,
  Kbit50 =  50,
  Kbit20  = 125

};

enum CanMode
{
	NormalCAN = CAN_MODE_NORMAL,
	SilentCAN = CAN_MODE_SILENT,
	LoopBackCan = CAN_MODE_LOOPBACK,
	SilentLoopBackCAN = CAN_MODE_SILENT_LOOPBACK
};


typedef struct{
  uint8_t dlc;
  uint32_t msgID;
  bool isRTR;
  bool isStandard;
  uint8_t data[8];
}CanMessage;


CanMessage createMessage(void);
/**
 CAN wrapper for STM32F405RGT6 board.
*/
class SimpleCan
{
public:
/*
	class RxHandler
	{
	public:
		RxHandler(uint16_t dataLength, void(*callback)(CAN_RxHeaderTypeDef rxHeader, uint8_t *rxData));
		~RxHandler();
		void notify(CAN_HandleTypeDef *hcan1);
	
  private:
		CAN_RxHeaderTypeDef _rxHeader;
		uint8_t *_rxData;
		void(*_callback)(CAN_RxHeaderTypeDef, uint8_t *);
	};
*/
	SimpleCan();
	HAL_StatusTypeDef init(CanSpeed speed, CanMode mode);
	HAL_StatusTypeDef configFilter(CAN_FilterTypeDef *filterDef);
  HAL_StatusTypeDef configSnniferFilter();
	HAL_StatusTypeDef activateNotification(/*RxHandler *rxHandler*/);
	HAL_StatusTypeDef deactivateNotification();
	HAL_StatusTypeDef begin();
	HAL_StatusTypeDef stop();
	HAL_StatusTypeDef send(CanMessage message);
  //private: interrupt handler needs access to it
  CAN_HandleTypeDef hcan;
  //static RxHandler *_rxHandler;

};
#endif

SimpleCan.cpp

#include <SimpleCan.h>
#include <Arduino.h>

extern "C" HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *);
extern "C" HAL_StatusTypeDef HAL_CAN_Stop (CAN_HandleTypeDef *);
extern "C" HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *);
extern "C" HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *, uint32_t );
extern "C" void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *);

void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan1)
{
  GPIO_InitTypeDef GPIO_InitStruct = {0};
  if(hcan1->Instance==CAN1)
  {
  /* USER CODE BEGIN CAN1_MspInit 0 */

  /* USER CODE END CAN1_MspInit 0 */
    /* Peripheral clock enable */
    __HAL_RCC_CAN1_CLK_ENABLE();

    __HAL_RCC_GPIOB_CLK_ENABLE();
    /**CAN1 GPIO Configuration
    PB8     ------> CAN1_RX
    PB9     ------> CAN1_TX
    */
    GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9;
    GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
    GPIO_InitStruct.Pull = GPIO_NOPULL;
    GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
    GPIO_InitStruct.Alternate = GPIO_AF9_CAN1;
    HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);

    /* CAN1 interrupt Init */
    HAL_NVIC_SetPriority(CAN1_RX0_IRQn, 0, 0);
    HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn);
    /* USER CODE BEGIN CAN1_MspInit 1 */

    /* USER CODE END CAN1_MspInit 1 */
  }

}

CanMessage createMessage(){
  CanMessage message;
  message.dlc = 8;
  message.msgID = 200;
  message.isRTR = false;
  message.isStandard = true;
  uint8_t messageLoadBuffer[8] ={0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x23};
  memcpy(message.data, messageLoadBuffer, 8);
  
  return message;
}

SimpleCan::SimpleCan(){
    return;
}
HAL_StatusTypeDef SimpleCan::init(CanSpeed speed, CanMode mode){
  hcan.Instance = CAN1;
  hcan.Init.Prescaler = speed;
  hcan.Init.Mode = mode;
  hcan.Init.SyncJumpWidth = CAN_SJW_1TQ;
  hcan.Init.TimeSeg1 = CAN_BS1_8TQ;
  hcan.Init.TimeSeg2 = CAN_BS2_1TQ;
  hcan.Init.TimeTriggeredMode = DISABLE;
  hcan.Init.AutoBusOff = DISABLE;
  hcan.Init.AutoWakeUp = DISABLE;
  hcan.Init.AutoRetransmission = DISABLE;
  hcan.Init.ReceiveFifoLocked = DISABLE;
  hcan.Init.TransmitFifoPriority = DISABLE;
  
  return HAL_CAN_Init(&hcan);

}
HAL_StatusTypeDef SimpleCan::begin(){
    return HAL_CAN_Start(&hcan);

}
HAL_StatusTypeDef SimpleCan::stop(){
   	return HAL_CAN_Stop(&hcan);

}
HAL_StatusTypeDef SimpleCan::configFilter(CAN_FilterTypeDef *filterDef){

    // Default filter - accept all to CAN_FIFO*
    CAN_FilterTypeDef sFilterConfig;
    sFilterConfig.FilterBank = 0;
    sFilterConfig.FilterIdHigh = 0x00005;
    sFilterConfig.FilterBank = 0x0000;
    sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;
    sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
    sFilterConfig.FilterIdHigh = 0x00 ;  // HE TOCADO ESTO !!!!!!!
    sFilterConfig.FilterIdLow  = 0x0000;
    sFilterConfig.FilterMaskIdHigh = 0x0000;
    sFilterConfig.FilterMaskIdLow = 0x0000;
    sFilterConfig.FilterFIFOAssignment = CAN_FILTER_FIFO0;
    sFilterConfig.FilterActivation = ENABLE;

    return HAL_CAN_ConfigFilter(&hcan, &sFilterConfig);
}
HAL_StatusTypeDef SimpleCan::configSnniferFilter(){

    // Default filter - accept all to CAN_FIFO*
	  CAN_FilterTypeDef sFilterConfig;
	  sFilterConfig.FilterBank = 0;
	  sFilterConfig.FilterIdHigh = 0x00005;
	  sFilterConfig.FilterBank = 0x0000;
	  sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;
	  sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
	  sFilterConfig.FilterIdHigh = 0x200 << 5;  //11-bit ID, in top bits
	  sFilterConfig.FilterIdLow  = 0x0000;
	  sFilterConfig.FilterMaskIdHigh = 0x0000;
	  sFilterConfig.FilterMaskIdLow = 0x0000;
	  sFilterConfig.FilterFIFOAssignment = CAN_FILTER_FIFO0;
	  sFilterConfig.FilterActivation = ENABLE;

    return HAL_CAN_ConfigFilter(&hcan, &sFilterConfig);
}

HAL_StatusTypeDef SimpleCan::send(CanMessage message){
	uint32_t TxMailbox;
	CAN_TxHeaderTypeDef pHeader;
    pHeader.DLC= message.dlc;
    message.isStandard ? pHeader.IDE=CAN_ID_STD : pHeader.IDE=CAN_ID_EXT;
    message.isRTR ?  pHeader.RTR=CAN_RTR_REMOTE : pHeader.RTR=CAN_RTR_DATA;
    message.isStandard ? pHeader.StdId=0x200 : pHeader.ExtId=0x200;

    return HAL_CAN_AddTxMessage(&hcan, &pHeader, (uint8_t*)message.data, &TxMailbox);
}


HAL_StatusTypeDef SimpleCan::activateNotification( /*RxHandler *rxHandler*/)
{/*
    
	if (_rxHandler != NULL)
	{
		return HAL_ERROR;
	}
	_rxHandler = rxHandler;
    */
	return HAL_CAN_ActivateNotification(&hcan, CAN_IT_RX_FIFO0_MSG_PENDING);
}

HAL_StatusTypeDef SimpleCan::deactivateNotification(){
   // _rxHandler = NULL;
    return HAL_CAN_DeactivateNotification(&hcan, CAN_IT_RX_FIFO0_MSG_PENDING);
}
//       RxHandler   Implementation
/*
SimpleCan::RxHandler::RxHandler(uint16_t dataLength, void (*callback)(CAN_RxHeaderTypeDef, uint8_t *))
{
	_rxData = new byte[dataLength];
	_callback = callback;
}
SimpleCan::RxHandler::~RxHandler()
{
	delete[] _rxData;
}


void SimpleCan::RxHandler::notify(CAN_HandleTypeDef *hcan1)
{

    if (SimpleCan::_rxHandler == NULL)
    {
        return;
    }
    SimpleCan::_rxHandler->notify(hcan1);
}
*/
void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan1)
{
   digitalToggle(PC13);
/*
    if (SimpleCan::_rxHandler == NULL)
    {
        return;
    }
    SimpleCan:_rxHandler->notify(hcan1);
*/
}
---------

TestCan.cpp


#include <Arduino.h>
#include "stm32f4xx_hal_can.h"
#include <SimpleCan.h>

// This SystemClock_Config  is copy&paste from CubeIDE
void SystemClock_Config(void)
{
  RCC_OscInitTypeDef RCC_OscInitStruct = {0};
  RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};

  // Configure the main internal regulator output voltage
  //
  __HAL_RCC_PWR_CLK_ENABLE();
  __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
  // Initializes the RCC Oscillators according to the specified parameters
  // in the RCC_OscInitTypeDef structure.
  //
  RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
  RCC_OscInitStruct.HSIState = RCC_HSI_ON;
  RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
  RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
  RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
  RCC_OscInitStruct.PLL.PLLM = 8;
  RCC_OscInitStruct.PLL.PLLN = 100;
  RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
  RCC_OscInitStruct.PLL.PLLQ = 4;
  if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
  {
    Error_Handler();
  }
  // Initializes the CPU, AHB and APB buses clocks

  RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
                              |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
  RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
  RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
  RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
  RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;

  if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3) != HAL_OK)
  {
    Error_Handler();
  }
}
/*
static void handleCanMessage(CAN_RxHeaderTypeDef rxHeader, uint8_t *rxData)
{
	digitalToggle(PC13);
}

SimpleCan::RxHandler can1RxHandler(8, handleCanMessage);
*/
SimpleCan can;


void setup() {
    Serial1.begin(115200);
    pinMode(PC13,OUTPUT);
    can.init(Kbit250,LoopBackCAN);
    can.configSnniferFilter();
    can.activateNotification( /*&can1RxHandler*/);
    can.begin();
   

}
void loop() {
  Serial1.println("Hola Can !!!");
  //digitalToggle(PC13);
  CanMessage  msg = createMessage();
  can.send(msg);
  delay(10);
}

“““
platformio.ini

[env:genericSTM32F405RG]
platform = ststm32
board = genericSTM32F405RG
board_build.f_cpu = 100000000L
framework = arduino
debug_tool = stlink
upload_protocol = stlink
build_flags =
-D HSE_VALUE=8000000

-D HAVE_HWSERIAL1

-D PIN_WIRE_SDA=PB11
-D PIN_WIRE_SCL=PB10

-D PIN_SPI_MOSI=PA7
-D PIN_SPI_MISO=PA6
-D PIN_SPI_SCK=PA5
-D PIN_SPI_SS=PA4

-D HAL_CAN_MODULE_ENABLED

monitor_speed = 115200
lib_deps =
askuric/Simple FOC@^2.0.2
Wire
SPI

Have you tried polling instead of interrupts.

I.e use HAL_CAN_GetRxFifoFillLevel() and HAL_CAN_GetRxMessage()
Instead of callback.

I realise callback is preferable

I watched a (stmcubeide) video that suggested you have to implement
EXTI0_IRQHandler

@erwin74 wrote this code because an fdcan library for Arduino doesn’t exist.

I think librarys exist for normal CAn on stm32. Have you checked what is out there?
E.g
ā€œGitHub - nopnop2002/Arduino-STM32-CAN: Can Example for Arduino Core STM32ā€ GitHub - nopnop2002/Arduino-STM32-CAN: Can Example for Arduino Core STM32

That said, It would be cool if you could use erwins interface as then it would be cross compatible!

Hi @Owen_Williams ,

Thanks for the suggestion . It worked :slight_smile: Finally I have bidirectional CAN communication from the board.

I have tried to simulate busy conditions and I have found that the size of the circular FIFO queue is 3 elements. It works perfectly as long as you are able to have a reading frequency at least up to 3 times lower than the arrival frequency.

Yes, if I have seen that there are some libraries but I have not found any that have the capacity to support callbackack as @erwin74 semms to support. Do not know how to receive CAN1_RX0_IRQHandler related interrups without crashing.

Road stone removed;) Let’s see if hopefully I can be able to pay attention to interruption as an improvement. Thanks again.

2 Likes

Actual i only took an example from stm and wrote a wrapper for it - no magic at all. A discovery board with similar chip should be at home, and at weekend possibly i can find som time to take a look into it.

1 Like

Hi @erwin74, It would be great to have a SimpleCan library to work aside with SimpleFOC devices that support interrupts, as what I can been able to implement only supports reception by pooling and forces polling with at least 1/3 of the expected arrival message rate for do not lose any message.