-
Notifications
You must be signed in to change notification settings - Fork 10
/
STM32_SimpleCAN.cpp
598 lines (468 loc) · 19.1 KB
/
STM32_SimpleCAN.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
/*
Portable CAN bus library - implementation for STM B-G431B-ESC1 board.
This module implements the SimpleCan interface for a specific platorm.
This code was strongly inspired by the discussions and proposals on the SimplFOC forum, especially
by work provided by erwin74, JorgeMaker and Owen_Williams of the SimpleFOC community (see this thread: https://community.simplefoc.com/t/can-bus-support/407/21).
The code versions provided by erwin74 and Owen_Williams were the basis for this derived work which attempts
to be more modular and portable. Actually, most of the code in this specific module is their work.
(c) 2022 Christian Schmidmer, use is subject to MIT license
*/
/*
Note: In xxx\.platformio\packages\framework-arduinoststm32\system\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_fdcan.c apply the following change:
Line 3493
for (ByteCounter = 0; ByteCounter < DLCtoBytes[pTxHeader->DataLength >> 16U]; ByteCounter += 4U)
{
*TxAddress = (((uint32_t)pTxData[ByteCounter + 3U] << 24U) |
((uint32_t)pTxData[ByteCounter + 2U] << 16U) |
((uint32_t)pTxData[ByteCounter + 1U] << 8U) |
(uint32_t)pTxData[ByteCounter]);
TxAddress++;
}
-> Change to:
if (!(pTxHeader->TxFrameType&&FDCAN_REMOTE_FRAME))
{
for (ByteCounter = 0; ByteCounter < DLCtoBytes[pTxHeader->DataLength >> 16U]; ByteCounter += 4U)
{
*TxAddress = (((uint32_t)pTxData[ByteCounter + 3U] << 24U) |
((uint32_t)pTxData[ByteCounter + 2U] << 16U) |
((uint32_t)pTxData[ByteCounter + 1U] << 8U) |
(uint32_t)pTxData[ByteCounter]);
TxAddress++;
}
}
*/
#include <Arduino.h>
#include "ThreadSafeQueue.h"
#include "SimpleCAN.h"
// #define STM32G4xx
#if defined(STM32G4xx)
#ifdef Error_Handler
#undef Error_Handler
void Error_Handler(int Code=-1)
{
Serial.printf("\nError SimpleCan_STM32G4xx %d\n", Code);
}
#endif
#define HALSTATUS2CANSTATUS(s) (static_cast<SCCanStatus>(s))
// Utility function to convert filter definition types from SimpleCan to stm32 definition.
SCCanStatus SC2STM32_Filter(FilterDefinition *SCFilter, FDCAN_FilterTypeDef* STMFilter)
{
STMFilter->FilterIndex = SCFilter->FilterIndex;
STMFilter->FilterID1 = SCFilter->FilterID1;
STMFilter->FilterID2 = SCFilter->FilterID2;
switch(SCFilter->IdType)
{
case CAN_STDID: STMFilter->IdType = FDCAN_STANDARD_ID; break;
case CAN_EXTID: STMFilter->IdType = FDCAN_EXTENDED_ID; break;
default: return CAN_UNSUPPORTED;
}
switch(SCFilter->FilterType)
{
case CAN_FILTER_RANGE: STMFilter->FilterType = FDCAN_FILTER_RANGE; break;
case CAN_FILTER_DUAL: STMFilter->FilterType = FDCAN_FILTER_DUAL; break;
case CAN_FILTER_MASK: STMFilter->FilterType = FDCAN_FILTER_MASK; break;
case CAN_FILTER_RANGE_NO_EIDM: STMFilter->FilterType = FDCAN_FILTER_RANGE_NO_EIDM; break;
default: return CAN_UNSUPPORTED;
}
switch(SCFilter->FilterConfig)
{
case CAN_FILTER_DISABLE: STMFilter->FilterConfig = FDCAN_FILTER_DISABLE; break;
case CAN_FILTER_TO_RXFIFO0: STMFilter->FilterConfig = FDCAN_FILTER_TO_RXFIFO0; break;
case CAN_FILTER_TO_RXFIFO1: STMFilter->FilterConfig = FDCAN_FILTER_TO_RXFIFO1; break;
case CAN_FILTER_REJECT: STMFilter->FilterConfig = FDCAN_FILTER_REJECT; break;
case CAN_FILTER_HP: STMFilter->FilterConfig = FDCAN_FILTER_HP; break;
case CAN_FILTER_TO_RXFIFO0_HP: STMFilter->FilterConfig = FDCAN_FILTER_TO_RXFIFO0_HP; break;
case CAN_FILTER_TO_RXFIFO1_HP: STMFilter->FilterConfig = FDCAN_FILTER_TO_RXFIFO1_HP; break;
default: return CAN_UNSUPPORTED;
}
return CAN_OK;
}
class RxHandlerSTM32 : public RxHandlerBase
{
public:
// Note: The constructor here is a must in order to initialize the base class.
RxHandlerSTM32(uint16_t dataLength) : RxHandlerBase(dataLength) {};
bool CANReadFrame(SimpleCanRxHeader* SCHeader, uint8_t* pData, int MaxDataLen);
void ReleaseRcvBuffer();
private:
FDCAN_RxHeaderTypeDef _rxHeader;
};
class SimpleCan_STM32G4xx : public SimpleCan
{
public:
SimpleCan_STM32G4xx(uint32_t PinTx, uint32_t PinRx);
//*******************************************************
//*** Implementation of pure virtual methods ************
// Initialize the CAN controller
SCCanStatus Init(SCCanSpeed speed, CanIDFilter IDFilterFunc=0);
// Register/deregister a callback function for message received events.
// The notification handler is platform specific, that is why it's needed here.
// These functions may be overloaded if required.
SCCanStatus ActivateNotification(uint16_t dataLength, RxCallback callback, void* userData);
SCCanStatus DeactivateNotification();
// Set bus termination on/off (may not be available on all platforms).
// Default is on.
SCCanStatus SetBusTermination(bool On);
// Start and stop all activities. Changing acceptance filters requires stop()
// before doing so on some platforms.
SCCanStatus Start();
SCCanStatus Stop();
// Modify the global filter to reject everything which is not matching the other filters and to accept all remote frames.
SCCanStatus ConfigGlobalFilter();
// Modify the acceptance filter. This may be forbidden while the controller is active.
SCCanStatus ConfigFilter(FilterDefinition *filterDef);
// Start sending messages from the queue to the CAN bus, until the TX queue is emty.
bool TriggerSending() { return SendNextMessageFromQueue();};
//*******************************************************
//*** Other methods ************
static bool SendNextMessageFromQueue();
// Sending an RTR frame is exactly the same as SendMessage(), except for setting the RTR bit in the header
// and to not send any data bytes as payload. NumBytes/DLC must be set to the number of bytes expected in the
// return payload. The answer to the RTR frame will be received and handled like any other CAN message.
// bool RequestMessage(int NumBytes, int CanID, bool UseEFF=false);
static bool SendRequestMessage(int NumBytes, int CanID, bool UseEFF);
SCCanStatus ConfigGlobalFilter(uint32_t nonMatchingStd, uint32_t nonMatchingExt, uint32_t rejectRemoteStd, uint32_t rejectRemoteExt);
SCCanStatus AddMessageToTxFifoQ(FDCAN_TxHeaderTypeDef *pTxHeader, uint8_t *pTxData);
bool Loop();
static FDCAN_HandleTypeDef _hfdcan1;
uint8_t TxData[8];
static RxHandlerSTM32 *RxHandlerP;
private:
static CanIDFilter SendIDFilterFunc;
};
CanIDFilter SimpleCan_STM32G4xx::SendIDFilterFunc;
static RxHandlerSTM32 Can1RxHandler(8); // Preferably this should be allocated by the HAL, just paramterized here!
RxHandlerSTM32* SimpleCan_STM32G4xx::RxHandlerP=nullptr; // Presumably this must be static because of IRQs????
SimpleCan* CreateCanLib(uint32_t PinTx, uint32_t PinRx)
{
return (SimpleCan*) new SimpleCan_STM32G4xx(PinTx, PinRx);
}
static const uint8_t DLCtoBytes[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64};
// Copy max _rxDataLength bytes from received frame to _rxData.
bool RxHandlerSTM32::CANReadFrame(SimpleCanRxHeader* SCHeader, uint8_t* pData, int MaxDataLen)
{
if (HAL_FDCAN_GetRxMessage(&SimpleCan_STM32G4xx::_hfdcan1, FDCAN_RX_FIFO0, &_rxHeader, pData) != HAL_OK) //!!! Data length not checked!!!
{
Error_Handler(1);
return false;
}
if (ProfileCallback != NULL)
{
// Convert the header
SCHeader->Identifier = _rxHeader.Identifier;
SCHeader->DataLength = DLCtoBytes[_rxHeader.DataLength>>16];
SCHeader->RxTimestamp = _rxHeader.RxTimestamp;
SCHeader->FilterIndex = _rxHeader.FilterIndex;
SCHeader->IsFilterMatchingFrame = _rxHeader.IsFilterMatchingFrame;
SCHeader->IdType = (_rxHeader.IdType==FDCAN_EXTENDED_ID) ? SCIdType::CAN_EXTID : SCIdType::CAN_STDID;
SCHeader->Format = (_rxHeader.FDFormat==FDCAN_CLASSIC_CAN) ? SCCanType::CAN_CLASSIC : SCCanType::CAN_FDFCAN;
SCHeader->RxFrameType = (_rxHeader.RxFrameType==FDCAN_DATA_FRAME) ? SCFrameType::CAN_DATA_FRAME : SCFrameType::CAN_REMOTE_FRAME;
}
else return false;
return true;
}
// Let the hardware know the frame has been read.
void RxHandlerSTM32::ReleaseRcvBuffer()
{
// Nothing to do for STM32;
}
// will be called from: HAL_FDCAN_Init (all defined as weak functiions in HAL).
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);
extern "C" void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes);
FDCAN_HandleTypeDef SimpleCan_STM32G4xx::_hfdcan1 = { };
// Pin numbers used for the FDCAN1 device are global, since they are required by a callback
// function from the HAL which has no access to the classes :-(.
uint32_t PinCANRx=-1;
uint32_t PinCANTx=-1;
SimpleCan_STM32G4xx::SimpleCan_STM32G4xx(uint32_t PinTx, uint32_t PinRx) : SimpleCan(PinTx, PinRx)
{
if (_hfdcan1.Instance != NULL)
Error_Handler(2);
_hfdcan1.Instance = FDCAN1;
PinCANRx = PinRx;
PinCANTx = PinTx;
#ifdef ARDUINO_B_G431B_ESC1
pinMode(A_CAN_SHDN, OUTPUT);
pinMode(A_CAN_TERM, OUTPUT);
// Bus termination is on by default.
digitalWrite(A_CAN_TERM, HIGH);
#endif
SendIDFilterFunc = 0;
}
#ifdef ARDUINO_B_G431B_ESC1
SCCanStatus SimpleCan_STM32G4xx::SetBusTermination(bool On)
{
digitalWrite(A_CAN_TERM, On ? HIGH : LOW);
return CAN_OK;
}
#else // ARDUINO_PT_SENSOR
SCCanStatus SimpleCan_STM32G4xx::SetBusTermination(bool On)
{
return CAN_UNSUPPORTED;
}
#endif
SCCanStatus SimpleCan_STM32G4xx::Start(void)
{
#ifdef ARDUINO_B_G431B_ESC1
digitalWrite(A_CAN_SHDN, LOW);
#endif
return HALSTATUS2CANSTATUS(HAL_FDCAN_Start(&_hfdcan1));
}
SCCanStatus SimpleCan_STM32G4xx::Stop(void)
{
#ifdef ARDUINO_B_G431B_ESC1
digitalWrite(A_CAN_SHDN, HIGH);
#endif
return HALSTATUS2CANSTATUS(HAL_FDCAN_Stop(&_hfdcan1));
}
SCCanStatus SimpleCan_STM32G4xx::Init(SCCanSpeed speed, CanIDFilter IDFilterFunc)
{
Serial.println("SimpleCan_STM32G4xx::Init()"); delay(200);
if (IDFilterFunc) SendIDFilterFunc = IDFilterFunc;
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 = 1;
init->TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
return HALSTATUS2CANSTATUS(HAL_FDCAN_Init(&_hfdcan1));
}
SCCanStatus SimpleCan_STM32G4xx::ConfigFilter(FilterDefinition *SCFilter)
{
// Convert the filter definition
FDCAN_FilterTypeDef STMFilter;
SCCanStatus rc = SC2STM32_Filter(SCFilter, &STMFilter);
if (CAN_OK!=rc) return rc;
return HALSTATUS2CANSTATUS(HAL_FDCAN_ConfigFilter(&_hfdcan1, &STMFilter));
}
// Specify what to do with non-matching frames.
SCCanStatus SimpleCan_STM32G4xx::ConfigGlobalFilter(uint32_t nonMatchingStd, uint32_t nonMatchingExt, uint32_t rejectRemoteStd, uint32_t rejectRemoteExt)
{
return HALSTATUS2CANSTATUS(HAL_FDCAN_ConfigGlobalFilter(&_hfdcan1, nonMatchingStd, nonMatchingExt, rejectRemoteStd, rejectRemoteExt));
}
// Modify the global filter to reject everything which is not matching the other filters and acceopt all remote frames.
SCCanStatus SimpleCan_STM32G4xx::ConfigGlobalFilter()
{
return ConfigGlobalFilter(FDCAN_REJECT, FDCAN_REJECT, FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE);
}
SCCanStatus SimpleCan_STM32G4xx::ActivateNotification(uint16_t dataLength, RxCallback callback, void* userData)
{
if (RxHandlerP != NULL)
{
return HALSTATUS2CANSTATUS(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
RxHandlerP = &Can1RxHandler;
RxHandlerP->SetProfileCallback(dataLength, callback, userData);
Serial.println("CAN: notifications activated");
return HALSTATUS2CANSTATUS(HAL_FDCAN_ActivateNotification(&_hfdcan1, FDCAN_IT_RX_FIFO0_NEW_MESSAGE | FDCAN_IT_TX_COMPLETE, FDCAN_TX_BUFFER0));
}
SCCanStatus SimpleCan_STM32G4xx::DeactivateNotification()
{
RxHandlerP = NULL;
return HALSTATUS2CANSTATUS(HAL_FDCAN_DeactivateNotification(&_hfdcan1, FDCAN_IT_RX_FIFO0_NEW_MESSAGE));
}
SCCanStatus SimpleCan_STM32G4xx::AddMessageToTxFifoQ(FDCAN_TxHeaderTypeDef *pTxHeader, uint8_t *pTxData)
{
// Serial.printf(F("Sending CAN message ID=%d\n"), pTxHeader->Identifier);
return HALSTATUS2CANSTATUS(HAL_FDCAN_AddMessageToTxFifoQ(&_hfdcan1, pTxHeader, pTxData));
}
void ArduinoPinToHAL(uint32_t APin, uint32_t* HALPin, GPIO_TypeDef** HALPort)
{
uint32_t Pin = digitalPinToPinName(APin);
*HALPort = get_GPIO_Port(STM_PORT(Pin));
*HALPin = STM_LL_GPIO_PIN(Pin);
}
// Note: This is a weakly bound callback from the HAL.
// The only connection to SimplCanLib is through global variables (if required).
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(3);
}
// Peripheral clock enable
__HAL_RCC_FDCAN_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
// FDCAN1 GPIO Configuration
// PA11 ------> FDCAN1_RX
uint32_t Pin;
GPIO_TypeDef* Port;
GPIO_InitTypeDef GPIO_InitStruct = { 0 };
ArduinoPinToHAL(PinCANRx, &Pin, &Port);
GPIO_InitStruct.Pin = Pin;
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(Port, &GPIO_InitStruct);
// PB9/PA12 ------> FDCAN1_TX
ArduinoPinToHAL(PinCANTx, &Pin, &Port);
GPIO_InitStruct.Pin = Pin;
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(Port, &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_STM32G4xx::_hfdcan1);
if (SimpleCan_STM32G4xx::RxHandlerP)
SimpleCan_STM32G4xx::RxHandlerP->CANBusACtivityDetected();
}
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs)
{
// Serial.println("cb");
if ((RxFifo0ITs & FDCAN_IT_RX_FIFO0_NEW_MESSAGE) != RESET)
{
if (SimpleCan_STM32G4xx::RxHandlerP == NULL)
{
return;
}
SimpleCan_STM32G4xx::RxHandlerP->Notify(/*hfdcan*/); // handle!!
}
}
void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes)
{
// If there are still data in the TxQueue, shuffle them to the HAL Tx queue
// Serial.println("HAL_FDCAN_TxBufferCompleteCallback");
SimpleCan_STM32G4xx::SendNextMessageFromQueue();
}
bool SimpleCan_STM32G4xx::SendNextMessageFromQueue()
{
// Serial.println("CAN: SendNextMessageFromQueue)");
if(TxQueue.NumElements && !(_hfdcan1.Instance->TXFQS & FDCAN_TXFQS_TFQF))
{
CANTxMessage Msg;
if (!TxQueue.Dequeue(&Msg))
// Nothing to send...
return true;
// Serial.printf("CAN (STM32): Sending %d bytes with ID 0x%x as %s frame\n", Msg.Size, Msg.CanID, Msg.EFF?"EFF":"std");
if (Msg.RTR)
{
// The queued message was an RTR
SendRequestMessage(Msg.Size, Msg.CanID, Msg.EFF);
}
else
{
// Skip command if sender ID is disabled.
if ( SendIDFilterFunc && !SendIDFilterFunc(Msg.CanID) )
return true;
bool TxOk=true;
FDCAN_TxHeaderTypeDef TxHeader;
TxHeader.Identifier = Msg.CanID;
TxHeader.IdType = Msg.EFF ? FDCAN_EXTENDED_ID : FDCAN_STANDARD_ID;
TxHeader.TxFrameType = FDCAN_DATA_FRAME;
TxHeader.ErrorStateIndicator = FDCAN_ESI_ACTIVE;
TxHeader.BitRateSwitch = FDCAN_BRS_OFF;
TxHeader.FDFormat = FDCAN_CLASSIC_CAN;
TxHeader.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
TxHeader.MessageMarker = 0;
switch(Msg.Size)
{
case 0: TxHeader.DataLength = FDCAN_DLC_BYTES_0; break;
case 1: TxHeader.DataLength = FDCAN_DLC_BYTES_1; break;
case 2: TxHeader.DataLength = FDCAN_DLC_BYTES_2; break;
case 3: TxHeader.DataLength = FDCAN_DLC_BYTES_3; break;
case 4: TxHeader.DataLength = FDCAN_DLC_BYTES_4; break;
case 5: TxHeader.DataLength = FDCAN_DLC_BYTES_5; break;
case 6: TxHeader.DataLength = FDCAN_DLC_BYTES_6; break;
case 7: TxHeader.DataLength = FDCAN_DLC_BYTES_7; break;
case 8: TxHeader.DataLength = FDCAN_DLC_BYTES_8; break;
default: Serial.print("CAN: Invalid message length!\n");
TxOk = false;
}
if (TxOk)
{
// Serial.printf("Tx %d", TxQueue.NumElements);
TxOk = (HALSTATUS2CANSTATUS(HAL_FDCAN_AddMessageToTxFifoQ(&_hfdcan1, &TxHeader, Msg.Data)) == CAN_OK);
}
if (!TxOk)
Serial.printf("CAN: sending message failed (0x%lx)!\n", _hfdcan1.ErrorCode);
}
}
return true;
}
// Sending an RTR frame is exactly the same as SendMessage(), except for setting the RTR bit in the header
// and to not send any data bytes as payload. NumBytes/DLC must be set to the number of bytes expected in the
// return payload. The answer to the RTR frame will be received and handled like any other CAN message.
// So, in principle, no data array is required, but unfortunately the STM32 HAL routines expect it...
uint8_t DummyData[8];
bool SimpleCan_STM32G4xx::SendRequestMessage(int NumBytes, int CanID, bool UseEFF)
{
// Skip command if sender ID is disabled.
if (SendIDFilterFunc && !SendIDFilterFunc(CanID)) return true;
bool TxOk=true;
FDCAN_TxHeaderTypeDef TxHeader;
TxHeader.Identifier = CanID;
TxHeader.IdType = UseEFF ? FDCAN_EXTENDED_ID : FDCAN_STANDARD_ID;
TxHeader.TxFrameType = FDCAN_REMOTE_FRAME;
TxHeader.ErrorStateIndicator = FDCAN_ESI_ACTIVE;
TxHeader.BitRateSwitch = FDCAN_BRS_OFF;
TxHeader.FDFormat = FDCAN_CLASSIC_CAN;
TxHeader.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
TxHeader.MessageMarker = 0;
switch(NumBytes)
{
case 0: TxHeader.DataLength = FDCAN_DLC_BYTES_0; break;
case 1: TxHeader.DataLength = FDCAN_DLC_BYTES_1; break;
case 2: TxHeader.DataLength = FDCAN_DLC_BYTES_2; break;
case 3: TxHeader.DataLength = FDCAN_DLC_BYTES_3; break;
case 4: TxHeader.DataLength = FDCAN_DLC_BYTES_4; break;
case 5: TxHeader.DataLength = FDCAN_DLC_BYTES_5; break;
case 6: TxHeader.DataLength = FDCAN_DLC_BYTES_6; break;
case 7: TxHeader.DataLength = FDCAN_DLC_BYTES_7; break;
case 8: TxHeader.DataLength = FDCAN_DLC_BYTES_8; break;
default: Serial.print("CAN: Invalid message length!\n");
TxOk = false;
}
if (TxOk)
{
// Serial.print("CAN: x!\n");
TxOk = (HALSTATUS2CANSTATUS(HAL_FDCAN_AddMessageToTxFifoQ(&_hfdcan1, &TxHeader, DummyData)) == CAN_OK);
}
if (!TxOk)
Serial.print("CAN: sending message failed!\n");
return true;
}
bool SimpleCan_STM32G4xx::Loop()
{
return RxHandlerP->Loop();
}
#endif