uc_stm32_can.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
3  */
4 
5 #include <cassert>
6 #include <cstring>
7 #include <uavcan_stm32/can.hpp>
8 #include <uavcan_stm32/clock.hpp>
9 #include "internal.hpp"
10 
11 #if UAVCAN_STM32_CHIBIOS
12 # include <hal.h>
13 #elif UAVCAN_STM32_NUTTX
14 # include <nuttx/arch.h>
15 # include <nuttx/irq.h>
16 # include <arch/board/board.h>
17 #elif UAVCAN_STM32_BAREMETAL
18 #include <chip.h> // See http://uavcan.org/Implementations/Libuavcan/Platforms/STM32/
19 #elif UAVCAN_STM32_FREERTOS
20 #else
21 # error "Unknown OS"
22 #endif
23 
24 #if (UAVCAN_STM32_CHIBIOS && CH_KERNEL_MAJOR == 2) || UAVCAN_STM32_BAREMETAL
25 # if !(defined(STM32F10X_CL) || defined(STM32F2XX) || defined(STM32F3XX) || defined(STM32F4XX))
26 // IRQ numbers
27 # define CAN1_RX0_IRQn USB_LP_CAN1_RX0_IRQn
28 # define CAN1_TX_IRQn USB_HP_CAN1_TX_IRQn
29 // IRQ vectors
30 # if !defined(CAN1_RX0_IRQHandler) || !defined(CAN1_TX_IRQHandler)
31 # define CAN1_TX_IRQHandler USB_HP_CAN1_TX_IRQHandler
32 # define CAN1_RX0_IRQHandler USB_LP_CAN1_RX0_IRQHandler
33 # endif
34 # endif
35 #endif
36 
37 #if (UAVCAN_STM32_CHIBIOS && (CH_KERNEL_MAJOR == 3 || CH_KERNEL_MAJOR == 4 || CH_KERNEL_MAJOR == 5))
38 #define CAN1_TX_IRQHandler STM32_CAN1_TX_HANDLER
39 #define CAN1_RX0_IRQHandler STM32_CAN1_RX0_HANDLER
40 #define CAN1_RX1_IRQHandler STM32_CAN1_RX1_HANDLER
41 #define CAN2_TX_IRQHandler STM32_CAN2_TX_HANDLER
42 #define CAN2_RX0_IRQHandler STM32_CAN2_RX0_HANDLER
43 #define CAN2_RX1_IRQHandler STM32_CAN2_RX1_HANDLER
44 #endif
45 
46 #if UAVCAN_STM32_NUTTX
47 # if !defined(STM32_IRQ_CAN1TX) && !defined(STM32_IRQ_CAN1RX0)
48 # define STM32_IRQ_CAN1TX STM32_IRQ_USBHPCANTX
49 # define STM32_IRQ_CAN1RX0 STM32_IRQ_USBLPCANRX0
50 # endif
51 extern "C"
52 {
53 static int can1_irq(const int irq, void*, void*);
54 #if UAVCAN_STM32_NUM_IFACES > 1
55 static int can2_irq(const int irq, void*, void*);
56 #endif
57 }
58 #endif
59 
60 /* STM32F3's only CAN inteface does not have a number. */
61 #if defined(STM32F3XX)
62 #define RCC_APB1ENR_CAN1EN RCC_APB1ENR_CANEN
63 #define RCC_APB1RSTR_CAN1RST RCC_APB1RSTR_CANRST
64 #define CAN1_TX_IRQn CAN_TX_IRQn
65 #define CAN1_RX0_IRQn CAN_RX0_IRQn
66 #define CAN1_RX1_IRQn CAN_RX1_IRQn
67 # if UAVCAN_STM32_BAREMETAL
68 # define CAN1_TX_IRQHandler CAN_TX_IRQHandler
69 # define CAN1_RX0_IRQHandler CAN_RX0_IRQHandler
70 # define CAN1_RX1_IRQHandler CAN_RX1_IRQHandler
71 # endif
72 #endif
73 
74 
75 namespace uavcan_stm32
76 {
77 namespace
78 {
79 
80 CanIface* ifaces[UAVCAN_STM32_NUM_IFACES] =
81 {
83 #if UAVCAN_STM32_NUM_IFACES > 1
85 #endif
86 };
87 
88 inline void handleTxInterrupt(uavcan::uint8_t iface_index)
89 {
90  UAVCAN_ASSERT(iface_index < UAVCAN_STM32_NUM_IFACES);
92  if (utc_usec > 0)
93  {
94  utc_usec--;
95  }
96  if (ifaces[iface_index] != UAVCAN_NULLPTR)
97  {
98  ifaces[iface_index]->handleTxInterrupt(utc_usec);
99  }
100  else
101  {
102  UAVCAN_ASSERT(0);
103  }
104 }
105 
106 inline void handleRxInterrupt(uavcan::uint8_t iface_index, uavcan::uint8_t fifo_index)
107 {
108  UAVCAN_ASSERT(iface_index < UAVCAN_STM32_NUM_IFACES);
110  if (utc_usec > 0)
111  {
112  utc_usec--;
113  }
114  if (ifaces[iface_index] != UAVCAN_NULLPTR)
115  {
116  ifaces[iface_index]->handleRxInterrupt(fifo_index, utc_usec);
117  }
118  else
119  {
120  UAVCAN_ASSERT(0);
121  }
122 }
123 
124 } // namespace
125 
126 /*
127  * CanIface::RxQueue
128  */
130 {
131  if (overflow_cnt_ < 0xFFFFFFFF)
132  {
133  overflow_cnt_++;
134  }
135 }
136 
138 {
139  buf_[in_].frame = frame;
140  buf_[in_].utc_usec = utc_usec;
141  buf_[in_].flags = flags;
142  in_++;
143  if (in_ >= capacity_)
144  {
145  in_ = 0;
146  }
147  len_++;
148  if (len_ > capacity_)
149  {
150  len_ = capacity_;
151  registerOverflow();
152  out_++;
153  if (out_ >= capacity_)
154  {
155  out_ = 0;
156  }
157  }
158 }
159 
161 {
162  if (len_ > 0)
163  {
164  out_frame = buf_[out_].frame;
165  out_utc_usec = buf_[out_].utc_usec;
166  out_flags = buf_[out_].flags;
167  out_++;
168  if (out_ >= capacity_)
169  {
170  out_ = 0;
171  }
172  len_--;
173  }
174  else { UAVCAN_ASSERT(0); }
175 }
176 
178 {
179  in_ = 0;
180  out_ = 0;
181  len_ = 0;
182  overflow_cnt_ = 0;
183 }
184 
185 /*
186  * CanIface
187  */
189 {
193 };
194 
195 int CanIface::computeTimings(const uavcan::uint32_t target_bitrate, Timings& out_timings)
196 {
197  if (target_bitrate < 1)
198  {
199  return -ErrInvalidBitRate;
200  }
201 
202  /*
203  * Hardware configuration
204  */
205 #if UAVCAN_STM32_BAREMETAL
206  const uavcan::uint32_t pclk = STM32_PCLK1;
207 #elif UAVCAN_STM32_CHIBIOS
208  const uavcan::uint32_t pclk = STM32_PCLK1;
209 #elif UAVCAN_STM32_NUTTX
210  const uavcan::uint32_t pclk = STM32_PCLK1_FREQUENCY;
211 #elif UAVCAN_STM32_FREERTOS
212  const uavcan::uint32_t pclk = HAL_RCC_GetPCLK1Freq();
213 #else
214 # error "Unknown OS"
215 #endif
216 
217  static const int MaxBS1 = 16;
218  static const int MaxBS2 = 8;
219 
220  /*
221  * Ref. "Automatic Baudrate Detection in CANopen Networks", U. Koppe, MicroControl GmbH & Co. KG
222  * CAN in Automation, 2003
223  *
224  * According to the source, optimal quanta per bit are:
225  * Bitrate Optimal Maximum
226  * 1000 kbps 8 10
227  * 500 kbps 16 17
228  * 250 kbps 16 17
229  * 125 kbps 16 17
230  */
231  const int max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 17;
232 
233  UAVCAN_ASSERT(max_quanta_per_bit <= (MaxBS1 + MaxBS2));
234 
235  static const int MaxSamplePointLocation = 900;
236 
237  /*
238  * Computing (prescaler * BS):
239  * BITRATE = 1 / (PRESCALER * (1 / PCLK) * (1 + BS1 + BS2)) -- See the Reference Manual
240  * BITRATE = PCLK / (PRESCALER * (1 + BS1 + BS2)) -- Simplified
241  * let:
242  * BS = 1 + BS1 + BS2 -- Number of time quanta per bit
243  * PRESCALER_BS = PRESCALER * BS
244  * ==>
245  * PRESCALER_BS = PCLK / BITRATE
246  */
247  const uavcan::uint32_t prescaler_bs = pclk / target_bitrate;
248 
249  /*
250  * Searching for such prescaler value so that the number of quanta per bit is highest.
251  */
252  uavcan::uint8_t bs1_bs2_sum = uavcan::uint8_t(max_quanta_per_bit - 1);
253 
254  while ((prescaler_bs % (1 + bs1_bs2_sum)) != 0)
255  {
256  if (bs1_bs2_sum <= 2)
257  {
258  return -ErrInvalidBitRate; // No solution
259  }
260  bs1_bs2_sum--;
261  }
262 
263  const uavcan::uint32_t prescaler = prescaler_bs / (1 + bs1_bs2_sum);
264  if ((prescaler < 1U) || (prescaler > 1024U))
265  {
266  return -ErrInvalidBitRate; // No solution
267  }
268 
269  /*
270  * Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum.
271  * We need to find the values so that the sample point is as close as possible to the optimal value.
272  *
273  * Solve[(1 + bs1)/(1 + bs1 + bs2) == 7/8, bs2] (* Where 7/8 is 0.875, the recommended sample point location *)
274  * {{bs2 -> (1 + bs1)/7}}
275  *
276  * Hence:
277  * bs2 = (1 + bs1) / 7
278  * bs1 = (7 * bs1_bs2_sum - 1) / 8
279  *
280  * Sample point location can be computed as follows:
281  * Sample point location = (1 + bs1) / (1 + bs1 + bs2)
282  *
283  * Since the optimal solution is so close to the maximum, we prepare two solutions, and then pick the best one:
284  * - With rounding to nearest
285  * - With rounding to zero
286  */
287  struct BsPair
288  {
289  uavcan::uint8_t bs1;
290  uavcan::uint8_t bs2;
291  uavcan::uint16_t sample_point_permill;
292 
293  BsPair() :
294  bs1(0),
295  bs2(0),
296  sample_point_permill(0)
297  { }
298 
299  BsPair(uavcan::uint8_t bs1_bs2_sum, uavcan::uint8_t arg_bs1) :
300  bs1(arg_bs1),
301  bs2(uavcan::uint8_t(bs1_bs2_sum - bs1)),
302  sample_point_permill(uavcan::uint16_t(1000 * (1 + bs1) / (1 + bs1 + bs2)))
303  {
304  UAVCAN_ASSERT(bs1_bs2_sum > arg_bs1);
305  }
306 
307  bool isValid() const { return (bs1 >= 1) && (bs1 <= MaxBS1) && (bs2 >= 1) && (bs2 <= MaxBS2); }
308  };
309 
310  // First attempt with rounding to nearest
311  BsPair solution(bs1_bs2_sum, uavcan::uint8_t(((7 * bs1_bs2_sum - 1) + 4) / 8));
312 
313  if (solution.sample_point_permill > MaxSamplePointLocation)
314  {
315  // Second attempt with rounding to zero
316  solution = BsPair(bs1_bs2_sum, uavcan::uint8_t((7 * bs1_bs2_sum - 1) / 8));
317  }
318 
319  /*
320  * Final validation
321  * Helpful Python:
322  * def sample_point_from_btr(x):
323  * assert 0b0011110010000000111111000000000 & x == 0
324  * ts2,ts1,brp = (x>>20)&7, (x>>16)&15, x&511
325  * return (1+ts1+1)/(1+ts1+1+ts2+1)
326  *
327  */
328  if ((target_bitrate != (pclk / (prescaler * (1 + solution.bs1 + solution.bs2)))) || !solution.isValid())
329  {
330  UAVCAN_ASSERT(0);
331  return -ErrLogic;
332  }
333 
334  UAVCAN_STM32_LOG("Timings: quanta/bit: %d, sample point location: %.1f%%",
335  int(1 + solution.bs1 + solution.bs2), float(solution.sample_point_permill) / 10.F);
336 
337  out_timings.prescaler = uavcan::uint16_t(prescaler - 1U);
338  out_timings.sjw = 0; // Which means one
339  out_timings.bs1 = uavcan::uint8_t(solution.bs1 - 1);
340  out_timings.bs2 = uavcan::uint8_t(solution.bs2 - 1);
341  return 0;
342 }
343 
345  uavcan::CanIOFlags flags)
346 {
347  if (frame.isErrorFrame() || frame.dlc > 8)
348  {
349  return -ErrUnsupportedFrame;
350  }
351 
352  /*
353  * Normally we should perform the same check as in @ref canAcceptNewTxFrame(), because
354  * it is possible that the highest-priority frame between select() and send() could have been
355  * replaced with a lower priority one due to TX timeout. But we don't do this check because:
356  *
357  * - It is a highly unlikely scenario.
358  *
359  * - Frames do not timeout on a properly functioning bus. Since frames do not timeout, the new
360  * frame can only have higher priority, which doesn't break the logic.
361  *
362  * - If high-priority frames are timing out in the TX queue, there's probably a lot of other
363  * issues to take care of before this one becomes relevant.
364  *
365  * - It takes CPU time. Not just CPU time, but critical section time, which is expensive.
366  */
367  CriticalSectionLocker lock;
368 
369  /*
370  * Seeking for an empty slot
371  */
372  uavcan::uint8_t txmailbox = 0xFF;
374  {
375  txmailbox = 0;
376  }
377  else if ((can_->TSR & bxcan::TSR_TME1) == bxcan::TSR_TME1)
378  {
379  txmailbox = 1;
380  }
381  else if ((can_->TSR & bxcan::TSR_TME2) == bxcan::TSR_TME2)
382  {
383  txmailbox = 2;
384  }
385  else
386  {
387  return 0; // No transmission for you.
388  }
389 
390  peak_tx_mailbox_index_ = uavcan::max(peak_tx_mailbox_index_, txmailbox); // Statistics
391 
392  /*
393  * Setting up the mailbox
394  */
395  bxcan::TxMailboxType& mb = can_->TxMailbox[txmailbox];
396  if (frame.isExtended())
397  {
399  }
400  else
401  {
402  mb.TIR = ((frame.id & uavcan::CanFrame::MaskStdID) << 21);
403  }
404 
406  {
407  mb.TIR |= bxcan::TIR_RTR;
408  }
409 
410  mb.TDTR = frame.dlc;
411 
412  mb.TDHR = (uavcan::uint32_t(frame.data[7]) << 24) |
413  (uavcan::uint32_t(frame.data[6]) << 16) |
414  (uavcan::uint32_t(frame.data[5]) << 8) |
415  (uavcan::uint32_t(frame.data[4]) << 0);
416  mb.TDLR = (uavcan::uint32_t(frame.data[3]) << 24) |
417  (uavcan::uint32_t(frame.data[2]) << 16) |
418  (uavcan::uint32_t(frame.data[1]) << 8) |
419  (uavcan::uint32_t(frame.data[0]) << 0);
420 
421  mb.TIR |= bxcan::TIR_TXRQ; // Go.
422 
423  /*
424  * Registering the pending transmission so we can track its deadline and loopback it as needed
425  */
426  TxItem& txi = pending_tx_[txmailbox];
427  txi.deadline = tx_deadline;
428  txi.frame = frame;
429  txi.loopback = (flags & uavcan::CanIOFlagLoopback) != 0;
430  txi.abort_on_error = (flags & uavcan::CanIOFlagAbortOnError) != 0;
431  txi.pending = true;
432  return 1;
433 }
434 
436  uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags)
437 {
438  out_ts_monotonic = clock::getMonotonic(); // High precision is not required for monotonic timestamps
440  {
441  CriticalSectionLocker lock;
442  if (rx_queue_.getLength() == 0)
443  {
444  return 0;
445  }
446  rx_queue_.pop(out_frame, utc_usec, out_flags);
447  }
448  out_ts_utc = uavcan::UtcTime::fromUSec(utc_usec);
449  return 1;
450 }
451 
453  uavcan::uint16_t num_configs)
454 {
455  if (num_configs <= NumFilters)
456  {
457  CriticalSectionLocker lock;
458 
460 
461  // Slave (CAN2) gets half of the filters
462  can_->FMR &= ~0x00003F00UL;
463  can_->FMR |= static_cast<uint32_t>(NumFilters) << 8;
464 
465  can_->FFA1R = 0x0AAAAAAA; // FIFO's are interleaved between filters
466  can_->FM1R = 0; // Identifier Mask mode
467  can_->FS1R = 0x7ffffff; // Single 32-bit for all
468 
469  const uint8_t filter_start_index = (self_index_ == 0) ? 0 : NumFilters;
470 
471  if (num_configs == 0)
472  {
473  can_->FilterRegister[filter_start_index].FR1 = 0;
474  can_->FilterRegister[filter_start_index].FR2 = 0;
475  // We can't directly overwrite FA1R because that breaks the other CAN interface
476  can_->FA1R |= 1U << filter_start_index; // Other filters may still be enabled, we don't care
477  }
478  else
479  {
480  for (uint8_t i = 0; i < NumFilters; i++)
481  {
482  if (i < num_configs)
483  {
484  uint32_t id = 0;
485  uint32_t mask = 0;
486 
487  const uavcan::CanFilterConfig* const cfg = filter_configs + i;
488 
490  {
491  id = (cfg->id & uavcan::CanFrame::MaskExtID) << 3;
492  mask = (cfg->mask & uavcan::CanFrame::MaskExtID) << 3;
493  id |= bxcan::RIR_IDE;
494  }
495  else
496  {
497  id = (cfg->id & uavcan::CanFrame::MaskStdID) << 21; // Regular std frames, nothing fancy.
498  mask = (cfg->mask & uavcan::CanFrame::MaskStdID) << 21; // Boring.
499  }
500 
501  if (cfg->id & uavcan::CanFrame::FlagRTR)
502  {
503  id |= bxcan::RIR_RTR;
504  }
505 
506  if (cfg->mask & uavcan::CanFrame::FlagEFF)
507  {
508  mask |= bxcan::RIR_IDE;
509  }
510 
511  if (cfg->mask & uavcan::CanFrame::FlagRTR)
512  {
513  mask |= bxcan::RIR_RTR;
514  }
515 
516  can_->FilterRegister[filter_start_index + i].FR1 = id;
517  can_->FilterRegister[filter_start_index + i].FR2 = mask;
518 
519  can_->FA1R |= (1 << (filter_start_index + i));
520  }
521  else
522  {
523  can_->FA1R &= ~(1 << (filter_start_index + i));
524  }
525  }
526  }
527 
528  can_->FMR &= ~bxcan::FMR_FINIT;
529 
530  return 0;
531  }
532 
533  return -ErrFilterNumConfigs;
534 }
535 
536 bool CanIface::waitMsrINakBitStateChange(bool target_state)
537 {
538 #if UAVCAN_STM32_NUTTX || UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_FREERTOS
539  const unsigned Timeout = 1000;
540 #else
541  const unsigned Timeout = 2000000;
542 #endif
543  for (unsigned wait_ack = 0; wait_ack < Timeout; wait_ack++)
544  {
545  const bool state = (can_->MSR & bxcan::MSR_INAK) != 0;
546  if (state == target_state)
547  {
548  return true;
549  }
550 #if UAVCAN_STM32_NUTTX
551  ::usleep(1000);
552 #endif
553 #if UAVCAN_STM32_CHIBIOS
554 #ifdef MS2ST
555  ::chThdSleep(MS2ST(1));
556 #else
557  ::chThdSleep(TIME_MS2I(1));
558 #endif
559 #endif
560 #if UAVCAN_STM32_FREERTOS
561  ::osDelay(1);
562 #endif
563  }
564  return false;
565 }
566 
567 int CanIface::init(const uavcan::uint32_t bitrate, const OperatingMode mode)
568 {
569  /*
570  * We need to silence the controller in the first order, otherwise it may interfere with the following operations.
571  */
572  {
573  CriticalSectionLocker lock;
574 
575  can_->MCR &= ~bxcan::MCR_SLEEP; // Exit sleep mode
576  can_->MCR |= bxcan::MCR_INRQ; // Request init
577 
578  can_->IER = 0; // Disable interrupts while initialization is in progress
579  }
580 
581  if (!waitMsrINakBitStateChange(true))
582  {
583  UAVCAN_STM32_LOG("MSR INAK not set");
585  return -ErrMsrInakNotSet;
586  }
587 
588  /*
589  * Object state - interrupts are disabled, so it's safe to modify it now
590  */
591  rx_queue_.reset();
592  error_cnt_ = 0;
593  served_aborts_cnt_ = 0;
596  had_activity_ = false;
597 
598  /*
599  * CAN timings for this bitrate
600  */
601  Timings timings;
602  const int timings_res = computeTimings(bitrate, timings);
603  if (timings_res < 0)
604  {
606  return timings_res;
607  }
608  UAVCAN_STM32_LOG("Timings: presc=%u sjw=%u bs1=%u bs2=%u",
609  unsigned(timings.prescaler), unsigned(timings.sjw), unsigned(timings.bs1), unsigned(timings.bs2));
610 
611  /*
612  * Hardware initialization (the hardware has already confirmed initialization mode, see above)
613  */
615 
616  can_->BTR = ((timings.sjw & 3U) << 24) |
617  ((timings.bs1 & 15U) << 16) |
618  ((timings.bs2 & 7U) << 20) |
619  (timings.prescaler & 1023U) |
620  ((mode == SilentMode) ? bxcan::BTR_SILM : 0);
621 
622  can_->IER = bxcan::IER_TMEIE | // TX mailbox empty
623  bxcan::IER_FMPIE0 | // RX FIFO 0 is not empty
624  bxcan::IER_FMPIE1; // RX FIFO 1 is not empty
625 
626  can_->MCR &= ~bxcan::MCR_INRQ; // Leave init mode
627 
628  if (!waitMsrINakBitStateChange(false))
629  {
630  UAVCAN_STM32_LOG("MSR INAK not cleared");
632  return -ErrMsrInakNotCleared;
633  }
634 
635  /*
636  * Default filter configuration
637  */
638  if (self_index_ == 0)
639  {
641 
642  can_->FMR &= 0xFFFFC0F1;
643  can_->FMR |= static_cast<uavcan::uint32_t>(NumFilters) << 8; // Slave (CAN2) gets half of the filters
644 
645  can_->FFA1R = 0; // All assigned to FIFO0 by default
646  can_->FM1R = 0; // Indentifier Mask mode
647 
648 #if UAVCAN_STM32_NUM_IFACES > 1
649  can_->FS1R = 0x7ffffff; // Single 32-bit for all
650  can_->FilterRegister[0].FR1 = 0; // CAN1 accepts everything
651  can_->FilterRegister[0].FR2 = 0;
652  can_->FilterRegister[NumFilters].FR1 = 0; // CAN2 accepts everything
654  can_->FA1R = 1 | (1 << NumFilters); // One filter per each iface
655 #else
656  can_->FS1R = 0x1fff;
657  can_->FilterRegister[0].FR1 = 0;
658  can_->FilterRegister[0].FR2 = 0;
659  can_->FA1R = 1;
660 #endif
661 
662  can_->FMR &= ~bxcan::FMR_FINIT;
663  }
664 
665  return 0;
666 }
667 
669 {
670  UAVCAN_ASSERT(mailbox_index < NumTxMailboxes);
671 
672  had_activity_ = had_activity_ || txok;
673 
674  TxItem& txi = pending_tx_[mailbox_index];
675 
676  if (txi.loopback && txok && txi.pending)
677  {
679  }
680 
681  txi.pending = false;
682 }
683 
685 {
686  // TXOK == false means that there was a hardware failure
687  if (can_->TSR & bxcan::TSR_RQCP0)
688  {
689  const bool txok = can_->TSR & bxcan::TSR_TXOK0;
692  }
693  if (can_->TSR & bxcan::TSR_RQCP1)
694  {
695  const bool txok = can_->TSR & bxcan::TSR_TXOK1;
698  }
699  if (can_->TSR & bxcan::TSR_RQCP2)
700  {
701  const bool txok = can_->TSR & bxcan::TSR_TXOK2;
704  }
705  update_event_.signalFromInterrupt();
706 
708 
709  #if UAVCAN_STM32_FREERTOS
710  update_event_.yieldFromISR();
711  #endif
712 }
713 
715 {
716  UAVCAN_ASSERT(fifo_index < 2);
717 
718  volatile uavcan::uint32_t* const rfr_reg = (fifo_index == 0) ? &can_->RF0R : &can_->RF1R;
719  if ((*rfr_reg & bxcan::RFR_FMP_MASK) == 0)
720  {
721  UAVCAN_ASSERT(0); // Weird, IRQ is here but no data to read
722  return;
723  }
724 
725  /*
726  * Register overflow as a hardware error
727  */
728  if ((*rfr_reg & bxcan::RFR_FOVR) != 0)
729  {
730  error_cnt_++;
731  }
732 
733  /*
734  * Read the frame contents
735  */
737  const bxcan::RxMailboxType& rf = can_->RxMailbox[fifo_index];
738 
739  if ((rf.RIR & bxcan::RIR_IDE) == 0)
740  {
741  frame.id = uavcan::CanFrame::MaskStdID & (rf.RIR >> 21);
742  }
743  else
744  {
745  frame.id = uavcan::CanFrame::MaskExtID & (rf.RIR >> 3);
747  }
748 
749  if ((rf.RIR & bxcan::RIR_RTR) != 0)
750  {
752  }
753 
754  frame.dlc = rf.RDTR & 15;
755 
756  frame.data[0] = uavcan::uint8_t(0xFF & (rf.RDLR >> 0));
757  frame.data[1] = uavcan::uint8_t(0xFF & (rf.RDLR >> 8));
758  frame.data[2] = uavcan::uint8_t(0xFF & (rf.RDLR >> 16));
759  frame.data[3] = uavcan::uint8_t(0xFF & (rf.RDLR >> 24));
760  frame.data[4] = uavcan::uint8_t(0xFF & (rf.RDHR >> 0));
761  frame.data[5] = uavcan::uint8_t(0xFF & (rf.RDHR >> 8));
762  frame.data[6] = uavcan::uint8_t(0xFF & (rf.RDHR >> 16));
763  frame.data[7] = uavcan::uint8_t(0xFF & (rf.RDHR >> 24));
764 
765  *rfr_reg = bxcan::RFR_RFOM | bxcan::RFR_FOVR | bxcan::RFR_FULL; // Release FIFO entry we just read
766 
767  /*
768  * Store with timeout into the FIFO buffer and signal update event
769  */
771  had_activity_ = true;
772  update_event_.signalFromInterrupt();
773 
775 
776  #if UAVCAN_STM32_FREERTOS
777  update_event_.yieldFromISR();
778  #endif
779 }
780 
782 {
784  if (lec != 0)
785  {
786  can_->ESR = 0;
787  error_cnt_++;
788 
789  // Serving abort requests
790  for (int i = 0; i < NumTxMailboxes; i++) // Dear compiler, may I suggest you to unroll this loop please.
791  {
792  TxItem& txi = pending_tx_[i];
793  if (txi.pending && txi.abort_on_error)
794  {
795  can_->TSR = TSR_ABRQx[i];
796  txi.pending = false;
798  }
799  }
800  }
801 }
802 
804 {
805  CriticalSectionLocker lock;
806  for (int i = 0; i < NumTxMailboxes; i++)
807  {
808  TxItem& txi = pending_tx_[i];
809  if (txi.pending && txi.deadline < current_time)
810  {
811  can_->TSR = TSR_ABRQx[i]; // Goodnight sweet transmission
812  txi.pending = false;
813  error_cnt_++;
814  }
815  }
816 }
817 
819 {
820  /*
821  * We can accept more frames only if the following conditions are satisfied:
822  * - There is at least one TX mailbox free (obvious enough);
823  * - The priority of the new frame is higher than priority of all TX mailboxes.
824  */
825  {
827  const uavcan::uint32_t tme = can_->TSR & TME;
828 
829  if (tme == TME) // All TX mailboxes are free (as in freedom).
830  {
831  return true;
832  }
833 
834  if (tme == 0) // All TX mailboxes are busy transmitting.
835  {
836  return false;
837  }
838  }
839 
840  /*
841  * The second condition requires a critical section.
842  */
843  CriticalSectionLocker lock;
844 
845  for (int mbx = 0; mbx < NumTxMailboxes; mbx++)
846  {
847  if (pending_tx_[mbx].pending && !frame.priorityHigherThan(pending_tx_[mbx].frame))
848  {
849  return false; // There's a mailbox whose priority is higher or equal the priority of the new frame.
850  }
851  }
852 
853  return true; // This new frame will be added to a free TX mailbox in the next @ref send().
854 }
855 
857 {
858  CriticalSectionLocker lock;
859  return rx_queue_.getLength() == 0;
860 }
861 
863 {
864  CriticalSectionLocker lock;
866 }
867 
869 {
870  CriticalSectionLocker lock;
871  return rx_queue_.getLength();
872 }
873 
875 {
876  CriticalSectionLocker lock;
877  const bool ret = had_activity_;
878  had_activity_ = false;
879  return ret;
880 }
881 
882 /*
883  * CanDriver
884  */
886 {
888 
889  // Iface 0
890  msk.read = if0_.isRxBufferEmpty() ? 0 : 1;
891 
892  if (pending_tx[0] != UAVCAN_NULLPTR)
893  {
894  msk.write = if0_.canAcceptNewTxFrame(*pending_tx[0]) ? 1 : 0;
895  }
896 
897  // Iface 1
898 #if UAVCAN_STM32_NUM_IFACES > 1
899  if (!if1_.isRxBufferEmpty())
900  {
901  msk.read |= 1 << 1;
902  }
903 
904  if (pending_tx[1] != UAVCAN_NULLPTR)
905  {
906  if (if1_.canAcceptNewTxFrame(*pending_tx[1]))
907  {
908  msk.write |= 1 << 1;
909  }
910  }
911 #endif
912  return msk;
913 }
914 
916 {
917 #if UAVCAN_STM32_NUM_IFACES == 1
918  return !if0_.isRxBufferEmpty();
919 #elif UAVCAN_STM32_NUM_IFACES == 2
920  return !if0_.isRxBufferEmpty() || !if1_.isRxBufferEmpty();
921 #else
922 # error UAVCAN_STM32_NUM_IFACES
923 #endif
924 }
925 
927  const uavcan::CanFrame* (& pending_tx)[uavcan::MaxCanIfaces],
928  const uavcan::MonotonicTime blocking_deadline)
929 {
930  const uavcan::CanSelectMasks in_masks = inout_masks;
932 
933  if0_.discardTimedOutTxMailboxes(time); // Check TX timeouts - this may release some TX slots
934  {
935  CriticalSectionLocker cs_locker;
936  if0_.pollErrorFlagsFromISR();
937  }
938 
939 #if UAVCAN_STM32_NUM_IFACES > 1
940  if1_.discardTimedOutTxMailboxes(time);
941  {
942  CriticalSectionLocker cs_locker;
943  if1_.pollErrorFlagsFromISR();
944  }
945 #endif
946 
947  inout_masks = makeSelectMasks(pending_tx); // Check if we already have some of the requested events
948  if ((inout_masks.read & in_masks.read) != 0 ||
949  (inout_masks.write & in_masks.write) != 0)
950  {
951  return 1;
952  }
953 
954  (void)update_event_.wait(blocking_deadline - time); // Block until timeout expires or any iface updates
955  inout_masks = makeSelectMasks(pending_tx); // Return what we got even if none of the requested events are set
956  return 1; // Return value doesn't matter as long as it is non-negative
957 }
958 
959 
960 #if UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
961 
962 static void nvicEnableVector(IRQn_Type irq, uint8_t prio)
963 {
964  #if !defined (USE_HAL_DRIVER)
965  NVIC_InitTypeDef NVIC_InitStructure;
966  NVIC_InitStructure.NVIC_IRQChannel = irq;
967  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = prio;
968  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
969  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
970  NVIC_Init(&NVIC_InitStructure);
971  #else
972  HAL_NVIC_SetPriority(irq, prio, 0);
973  HAL_NVIC_EnableIRQ(irq);
974  #endif
975 }
976 
977 #endif
978 
980 {
981  /*
982  * CAN1, CAN2
983  */
984  {
985  CriticalSectionLocker lock;
986 #if defined(STM32L4xx)
987 #if UAVCAN_STM32_NUTTX
988  modifyreg32(STM32_RCC_APB1ENR1, 0, RCC_APB1ENR1_CAN1EN);
989  modifyreg32(STM32_RCC_APB1RSTR1, 0, RCC_APB1RSTR1_CAN1RST);
990  modifyreg32(STM32_RCC_APB1RSTR1, RCC_APB1RSTR1_CAN1RST, 0);
991 # if UAVCAN_STM32_NUM_IFACES > 1
992  modifyreg32(STM32_RCC_APB1ENR1, 0, RCC_APB1ENR1_CAN2EN);
993  modifyreg32(STM32_RCC_APB1RSTR1, 0, RCC_APB1RSTR1_CAN2RST);
994  modifyreg32(STM32_RCC_APB1RSTR1, RCC_APB1RSTR1_CAN2RST, 0);
995 # endif
996 # else
997  RCC->APB1ENR1 |= RCC_APB1ENR1_CAN1EN;
998  RCC->APB1RSTR1 |= RCC_APB1RSTR1_CAN1RST;
999  RCC->APB1RSTR1 &= ~RCC_APB1RSTR1_CAN1RST;
1000 # if UAVCAN_STM32_NUM_IFACES > 1
1001  RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
1002  RCC->APB1RSTR |= RCC_APB1RSTR_CAN2RST;
1003  RCC->APB1RSTR &= ~RCC_APB1RSTR_CAN2RST;
1004 # endif
1005 # endif
1006 #else
1007 # if UAVCAN_STM32_NUTTX
1008  modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_CAN1EN);
1009  modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_CAN1RST);
1010  modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_CAN1RST, 0);
1011 # if UAVCAN_STM32_NUM_IFACES > 1
1012  modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_CAN2EN);
1013  modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_CAN2RST);
1014  modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_CAN2RST, 0);
1015 # endif
1016 # else
1017  RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
1018  RCC->APB1RSTR |= RCC_APB1RSTR_CAN1RST;
1019  RCC->APB1RSTR &= ~RCC_APB1RSTR_CAN1RST;
1020 # if UAVCAN_STM32_NUM_IFACES > 1
1021  RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
1022  RCC->APB1RSTR |= RCC_APB1RSTR_CAN2RST;
1023  RCC->APB1RSTR &= ~RCC_APB1RSTR_CAN2RST;
1024 # endif
1025 # endif
1026 #endif
1027  }
1028 
1029  /*
1030  * IRQ
1031  */
1032 #if UAVCAN_STM32_NUTTX
1033 # define IRQ_ATTACH(irq, handler) \
1034  { \
1035  const int res = irq_attach(irq, handler, NULL); \
1036  (void)res; \
1037  assert(res >= 0); \
1038  up_enable_irq(irq); \
1039  }
1040  IRQ_ATTACH(STM32_IRQ_CAN1TX, can1_irq);
1041  IRQ_ATTACH(STM32_IRQ_CAN1RX0, can1_irq);
1042  IRQ_ATTACH(STM32_IRQ_CAN1RX1, can1_irq);
1043 # if UAVCAN_STM32_NUM_IFACES > 1
1044  IRQ_ATTACH(STM32_IRQ_CAN2TX, can2_irq);
1045  IRQ_ATTACH(STM32_IRQ_CAN2RX0, can2_irq);
1046  IRQ_ATTACH(STM32_IRQ_CAN2RX1, can2_irq);
1047 # endif
1048 # undef IRQ_ATTACH
1049 #elif UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
1050  {
1051  CriticalSectionLocker lock;
1052  nvicEnableVector(CAN1_TX_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1053  nvicEnableVector(CAN1_RX0_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1054  nvicEnableVector(CAN1_RX1_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1055 # if UAVCAN_STM32_NUM_IFACES > 1
1056  nvicEnableVector(CAN2_TX_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1057  nvicEnableVector(CAN2_RX0_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1058  nvicEnableVector(CAN2_RX1_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1059 # endif
1060  }
1061 #endif
1062 }
1063 
1065 {
1066  int res = 0;
1067 
1068  UAVCAN_STM32_LOG("Bitrate %lu mode %d", static_cast<unsigned long>(bitrate), static_cast<int>(mode));
1069 
1070  static bool initialized_once = false;
1071  if (!initialized_once)
1072  {
1073  initialized_once = true;
1074  UAVCAN_STM32_LOG("First initialization");
1075  initOnce();
1076  }
1077 
1078  /*
1079  * CAN1
1080  */
1081  UAVCAN_STM32_LOG("Initing iface 0...");
1082  ifaces[0] = &if0_; // This link must be initialized first,
1083  res = if0_.init(bitrate, mode); // otherwise an IRQ may fire while the interface is not linked yet;
1084  if (res < 0) // a typical race condition.
1085  {
1086  UAVCAN_STM32_LOG("Iface 0 init failed %i", res);
1087  ifaces[0] = UAVCAN_NULLPTR;
1088  goto fail;
1089  }
1090 
1091  /*
1092  * CAN2
1093  */
1094 #if UAVCAN_STM32_NUM_IFACES > 1
1095  UAVCAN_STM32_LOG("Initing iface 1...");
1096  ifaces[1] = &if1_; // Same thing here.
1097  res = if1_.init(bitrate, mode);
1098  if (res < 0)
1099  {
1100  UAVCAN_STM32_LOG("Iface 1 init failed %i", res);
1101  ifaces[1] = UAVCAN_NULLPTR;
1102  goto fail;
1103  }
1104 #endif
1105 
1106  UAVCAN_STM32_LOG("CAN drv init OK");
1107  UAVCAN_ASSERT(res >= 0);
1108  return res;
1109 
1110 fail:
1111  UAVCAN_STM32_LOG("CAN drv init failed %i", res);
1112  UAVCAN_ASSERT(res < 0);
1113  return res;
1114 }
1115 
1117 {
1118  if (iface_index < UAVCAN_STM32_NUM_IFACES)
1119  {
1120  return ifaces[iface_index];
1121  }
1122  return UAVCAN_NULLPTR;
1123 }
1124 
1126 {
1127  bool ret = if0_.hadActivity();
1128 #if UAVCAN_STM32_NUM_IFACES > 1
1129  ret |= if1_.hadActivity();
1130 #endif
1131  return ret;
1132 }
1133 
1134 } // namespace uavcan_stm32
1135 
1136 /*
1137  * Interrupt handlers
1138  */
1139 extern "C"
1140 {
1141 
1142 #if UAVCAN_STM32_NUTTX
1143 
1144 static int can1_irq(const int irq, void*, void*)
1145 {
1146  if (irq == STM32_IRQ_CAN1TX)
1147  {
1148  uavcan_stm32::handleTxInterrupt(0);
1149  }
1150  else if (irq == STM32_IRQ_CAN1RX0)
1151  {
1152  uavcan_stm32::handleRxInterrupt(0, 0);
1153  }
1154  else if (irq == STM32_IRQ_CAN1RX1)
1155  {
1156  uavcan_stm32::handleRxInterrupt(0, 1);
1157  }
1158  else
1159  {
1160  PANIC();
1161  }
1162  return 0;
1163 }
1164 
1165 # if UAVCAN_STM32_NUM_IFACES > 1
1166 
1167 static int can2_irq(const int irq, void*, void*)
1168 {
1169  if (irq == STM32_IRQ_CAN2TX)
1170  {
1171  uavcan_stm32::handleTxInterrupt(1);
1172  }
1173  else if (irq == STM32_IRQ_CAN2RX0)
1174  {
1175  uavcan_stm32::handleRxInterrupt(1, 0);
1176  }
1177  else if (irq == STM32_IRQ_CAN2RX1)
1178  {
1179  uavcan_stm32::handleRxInterrupt(1, 1);
1180  }
1181  else
1182  {
1183  PANIC();
1184  }
1185  return 0;
1186 }
1187 
1188 # endif
1189 
1190 #else // UAVCAN_STM32_NUTTX
1191 
1192 #if !defined(CAN1_TX_IRQHandler) ||\
1193  !defined(CAN1_RX0_IRQHandler) ||\
1194  !defined(CAN1_RX1_IRQHandler)
1195 # error "Misconfigured build"
1196 #endif
1197 
1198 UAVCAN_STM32_IRQ_HANDLER(CAN1_TX_IRQHandler);
1199 UAVCAN_STM32_IRQ_HANDLER(CAN1_TX_IRQHandler)
1200 {
1202  uavcan_stm32::handleTxInterrupt(0);
1204 }
1205 
1206 UAVCAN_STM32_IRQ_HANDLER(CAN1_RX0_IRQHandler);
1207 UAVCAN_STM32_IRQ_HANDLER(CAN1_RX0_IRQHandler)
1208 {
1210  uavcan_stm32::handleRxInterrupt(0, 0);
1212 }
1213 
1214 UAVCAN_STM32_IRQ_HANDLER(CAN1_RX1_IRQHandler);
1215 UAVCAN_STM32_IRQ_HANDLER(CAN1_RX1_IRQHandler)
1216 {
1218  uavcan_stm32::handleRxInterrupt(0, 1);
1220 }
1221 
1222 # if UAVCAN_STM32_NUM_IFACES > 1
1223 
1224 #if !defined(CAN2_TX_IRQHandler) ||\
1225  !defined(CAN2_RX0_IRQHandler) ||\
1226  !defined(CAN2_RX1_IRQHandler)
1227 # error "Misconfigured build"
1228 #endif
1229 
1230 UAVCAN_STM32_IRQ_HANDLER(CAN2_TX_IRQHandler);
1231 UAVCAN_STM32_IRQ_HANDLER(CAN2_TX_IRQHandler)
1232 {
1234  uavcan_stm32::handleTxInterrupt(1);
1236 }
1237 
1238 UAVCAN_STM32_IRQ_HANDLER(CAN2_RX0_IRQHandler);
1239 UAVCAN_STM32_IRQ_HANDLER(CAN2_RX0_IRQHandler)
1240 {
1242  uavcan_stm32::handleRxInterrupt(1, 0);
1244 }
1245 
1246 UAVCAN_STM32_IRQ_HANDLER(CAN2_RX1_IRQHandler);
1247 UAVCAN_STM32_IRQ_HANDLER(CAN2_RX1_IRQHandler)
1248 {
1250  uavcan_stm32::handleRxInterrupt(1, 1);
1252 }
1253 
1254 # endif
1255 #endif // UAVCAN_STM32_NUTTX
1256 
1257 } // extern "C"
uavcan_stm32::CanIface::RxQueue::pop
void pop(uavcan::CanFrame &out_frame, uavcan::uint64_t &out_utc_usec, uavcan::CanIOFlags &out_flags)
Definition: uc_stm32_can.cpp:160
uavcan_stm32::CanIface::TSR_ABRQx
static const uavcan::uint32_t TSR_ABRQx[NumTxMailboxes]
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:113
uavcan::CanFrame::MaskStdID
static const uint32_t MaskStdID
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:26
uavcan_stm32::CanIface::SilentMode
@ SilentMode
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:148
uavcan_stm32::bxcan::RFR_FULL
constexpr unsigned long RFR_FULL
Definition: bxcan.hpp:142
uavcan_stm32::CanIface::RxQueue::reset
void reset()
Definition: uc_stm32_can.cpp:177
uavcan::CanFrame::FlagEFF
static const uint32_t FlagEFF
Extended frame format.
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:28
uavcan_stm32::CanIface::RxQueue::push
void push(const uavcan::CanFrame &frame, const uint64_t &utc_usec, uavcan::CanIOFlags flags)
Definition: uc_stm32_can.cpp:137
UAVCAN_NULLPTR
#define UAVCAN_NULLPTR
Definition: libuavcan/libuavcan/include/uavcan/build_config.hpp:51
overflow_cnt_
std::uint32_t overflow_cnt_
Definition: can.cpp:82
uavcan_stm32::ErrInvalidBitRate
static const uavcan::int16_t ErrInvalidBitRate
Bit rate not supported.
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:20
uavcan_stm32::CanDriver::hadActivity
bool hadActivity()
Definition: uc_stm32_can.cpp:1125
uavcan::uint64_t
std::uint64_t uint64_t
Definition: std.hpp:27
uavcan_stm32::CanIface::RxQueue::getLength
unsigned getLength() const
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:75
in_
std::uint8_t in_
Definition: can.cpp:83
uavcan_stm32::bxcan::CanType::RF0R
volatile uint32_t RF0R
Definition: bxcan.hpp:54
uavcan_stm32::bxcan::RxMailboxType
Definition: bxcan.hpp:35
uavcan_stm32::bxcan::TSR_TXOK2
constexpr unsigned long TSR_TXOK2
Definition: bxcan.hpp:125
uavcan::uint32_t
std::uint32_t uint32_t
Definition: std.hpp:26
uavcan_stm32::bxcan::TxMailboxType::TIR
volatile uint32_t TIR
Definition: bxcan.hpp:29
uavcan::UtcTime
Implicitly convertible to/from uavcan.Timestamp.
Definition: time.hpp:191
uavcan_stm32::bxcan::CanType::FA1R
volatile uint32_t FA1R
Definition: bxcan.hpp:70
uavcan_stm32::CanIface::TxItem::abort_on_error
bool abort_on_error
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:101
uavcan_stm32::bxcan::MCR_AWUM
constexpr unsigned long MCR_AWUM
Definition: bxcan.hpp:94
uavcan_stm32::CanIface::handleTxMailboxInterrupt
void handleTxMailboxInterrupt(uavcan::uint8_t mailbox_index, bool txok, uavcan::uint64_t utc_usec)
Definition: uc_stm32_can.cpp:668
uavcan_stm32::CanIface::init
int init(const uavcan::uint32_t bitrate, const OperatingMode mode)
Definition: uc_stm32_can.cpp:567
uavcan_stm32::CanIface::TxItem::deadline
uavcan::MonotonicTime deadline
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:97
uavcan_stm32::bxcan::TSR_ABRQ0
constexpr unsigned long TSR_ABRQ0
Definition: bxcan.hpp:118
uavcan_stm32::bxcan::RxMailboxType::RDTR
volatile uint32_t RDTR
Definition: bxcan.hpp:38
uavcan_stm32::ErrMsrInakNotSet
static const uavcan::int16_t ErrMsrInakNotSet
INAK bit of the MSR register is not 1.
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:23
UAVCAN_STM32_LOG
#define UAVCAN_STM32_LOG(...)
Definition: stm32/libuavcan/driver/src/internal.hpp:34
uavcan_stm32::bxcan::IER_FMPIE0
constexpr unsigned long IER_FMPIE0
Definition: bxcan.hpp:149
uavcan_stm32::bxcan::CanType::ESR
volatile uint32_t ESR
Definition: bxcan.hpp:57
can.hpp
uavcan_stm32::bxcan::FMR_FINIT
constexpr unsigned long FMR_FINIT
Definition: bxcan.hpp:282
uavcan_stm32::CanIface::NumFilters
@ NumFilters
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:111
uavcan_stm32::bxcan::RxMailboxType::RDLR
volatile uint32_t RDLR
Definition: bxcan.hpp:39
uavcan_stm32
Definition: bxcan.hpp:22
uavcan_stm32::CanIface::self_index_
const uavcan::uint8_t self_index_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:122
uavcan_stm32::bxcan::MCR_ABOM
constexpr unsigned long MCR_ABOM
Definition: bxcan.hpp:95
uavcan_stm32::ErrMsrInakNotCleared
static const uavcan::int16_t ErrMsrInakNotCleared
INAK bit of the MSR register is not 0.
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:24
uavcan_stm32::bxcan::ESR_LEC_MASK
constexpr unsigned long ESR_LEC_MASK
Definition: bxcan.hpp:169
uavcan_stm32::bxcan::CanType::FFA1R
volatile uint32_t FFA1R
Definition: bxcan.hpp:68
uavcan_stm32::bxcan::CanType::IER
volatile uint32_t IER
Definition: bxcan.hpp:56
uavcan_stm32::bxcan::IER_FMPIE1
constexpr unsigned long IER_FMPIE1
Definition: bxcan.hpp:152
uavcan::CanFilterConfig
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:99
uavcan_stm32::CanIface::RxQueue::registerOverflow
void registerOverflow()
Definition: uc_stm32_can.cpp:129
IRQ_ATTACH
#define IRQ_ATTACH(irq, handler)
uavcan::CanFrame
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:24
internal.hpp
uavcan_stm32::CanIface::peak_tx_mailbox_index_
uavcan::uint8_t peak_tx_mailbox_index_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:121
uavcan::CanFrame::dlc
uint8_t dlc
Data Length Code.
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:36
uavcan::CanIOFlagLoopback
static const CanIOFlags CanIOFlagLoopback
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:141
uavcan_stm32::bxcan::TxMailboxType::TDLR
volatile uint32_t TDLR
Definition: bxcan.hpp:31
uavcan_stm32::CanIface::update_event_
BusEvent & update_event_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:119
uavcan_stm32::CanIface::waitMsrINakBitStateChange
bool waitMsrINakBitStateChange(bool target_state)
Definition: uc_stm32_can.cpp:536
uavcan_stm32::bxcan::TSR_ABRQ1
constexpr unsigned long TSR_ABRQ1
Definition: bxcan.hpp:123
uavcan_stm32::CanDriver::getIface
virtual CanIface * getIface(uavcan::uint8_t iface_index)
Definition: uc_stm32_can.cpp:1116
uavcan_stm32::bxcan::RxMailboxType::RDHR
volatile uint32_t RDHR
Definition: bxcan.hpp:40
uavcan_stm32::CanIface::had_activity_
bool had_activity_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:123
uavcan_stm32::CanIface::configureFilters
virtual uavcan::int16_t configureFilters(const uavcan::CanFilterConfig *filter_configs, uavcan::uint16_t num_configs)
Definition: uc_stm32_can.cpp:452
uavcan_stm32::CanIface::OperatingMode
OperatingMode
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:145
uavcan::CanFrame::id
uint32_t id
CAN ID with flags (above)
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:34
uavcan_stm32::CanIface::getErrorCount
virtual uavcan::uint64_t getErrorCount() const
Definition: uc_stm32_can.cpp:862
uavcan_stm32::CanIface::hadActivity
bool hadActivity()
Definition: uc_stm32_can.cpp:874
uavcan::fill_n
UAVCAN_EXPORT void fill_n(OutputIt first, std::size_t n, const T &value)
Definition: templates.hpp:268
uavcan::MaxCanIfaces
@ MaxCanIfaces
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:19
uavcan_stm32::CanIface::Timings::prescaler
uavcan::uint16_t prescaler
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:82
uavcan_stm32::CanDriver::init
int init(const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode)
Definition: uc_stm32_can.cpp:1064
uavcan::CanFrame::isErrorFrame
bool isErrorFrame() const
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:72
uavcan_stm32::CanIface::handleTxInterrupt
void handleTxInterrupt(uavcan::uint64_t utc_usec)
Definition: uc_stm32_can.cpp:684
uavcan::uint16_t
std::uint16_t uint16_t
Definition: std.hpp:25
uavcan_stm32::ErrUnsupportedFrame
static const uavcan::int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc)
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:22
uavcan_stm32::ErrLogic
static const uavcan::int16_t ErrLogic
Internal logic error.
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:21
uavcan_stm32::bxcan::RIR_IDE
constexpr unsigned long RIR_IDE
Definition: bxcan.hpp:243
uavcan_stm32::CanIface::rx_queue_
RxQueue rx_queue_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:115
uavcan_stm32::bxcan::RxMailboxType::RIR
volatile uint32_t RIR
Definition: bxcan.hpp:37
uavcan_stm32::bxcan::ESR_LEC_SHIFT
constexpr unsigned long ESR_LEC_SHIFT
Definition: bxcan.hpp:168
uavcan::int16_t
std::int16_t int16_t
Definition: std.hpp:30
uavcan_stm32::bxcan::TSR_TME1
constexpr unsigned long TSR_TME1
Definition: bxcan.hpp:132
uavcan::TimeBase< UtcTime, UtcDuration >::fromUSec
static UtcTime fromUSec(uint64_t us)
Definition: time.hpp:112
uavcan::CanSelectMasks::read
uint8_t read
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:121
uavcan_stm32::bxcan::MCR_SLEEP
constexpr unsigned long MCR_SLEEP
Definition: bxcan.hpp:90
uavcan_stm32::bxcan::CanType::RF1R
volatile uint32_t RF1R
Definition: bxcan.hpp:55
uavcan_stm32::CanIface
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:47
uavcan::uint8_t
std::uint8_t uint8_t
Definition: std.hpp:24
uavcan_stm32::CanIface::TxItem::loopback
bool loopback
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:100
uavcan_stm32::bxcan::TSR_TME2
constexpr unsigned long TSR_TME2
Definition: bxcan.hpp:133
uavcan_stm32::bxcan::TIR_RTR
constexpr unsigned long TIR_RTR
Definition: bxcan.hpp:203
uavcan_stm32::CanIface::TxItem
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:95
uavcan::CanFilterConfig::mask
uint32_t mask
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:102
uavcan_stm32::bxcan::RFR_FOVR
constexpr unsigned long RFR_FOVR
Definition: bxcan.hpp:143
uavcan::max
const UAVCAN_EXPORT T & max(const T &a, const T &b)
Definition: templates.hpp:291
uavcan_stm32::bxcan::CanType::FM1R
volatile uint32_t FM1R
Definition: bxcan.hpp:64
uavcan_lpc11c24::clock::fail
static void fail()
Definition: clock.cpp:38
uavcan_stm32::bxcan::CanType::MSR
volatile uint32_t MSR
Definition: bxcan.hpp:52
uavcan_stm32::bxcan::MCR_RESET
constexpr unsigned long MCR_RESET
Definition: bxcan.hpp:97
uavcan::CanFrame::MaskExtID
static const uint32_t MaskExtID
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:27
uavcan::CanSelectMasks
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:119
uavcan_stm32::CanIface::isRxBufferEmpty
bool isRxBufferEmpty() const
Definition: uc_stm32_can.cpp:856
uavcan_stm32::CanIface::Timings::bs2
uavcan::uint8_t bs2
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:85
uavcan_stm32::bxcan::TSR_RQCP0
constexpr unsigned long TSR_RQCP0
Definition: bxcan.hpp:114
uavcan_stm32::CanDriver::select
virtual uavcan::int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline)
Definition: uc_stm32_can.cpp:926
uavcan_stm32::CanIface::TxItem::pending
bool pending
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:99
uavcan_stm32::CanIface::served_aborts_cnt_
uavcan::uint32_t served_aborts_cnt_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:118
UAVCAN_STM32_IRQ_HANDLER
UAVCAN_STM32_IRQ_HANDLER(CAN1_TX_IRQHandler)
Definition: uc_stm32_can.cpp:1199
uavcan::CanSelectMasks::write
uint8_t write
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:122
uavcan_stm32::CanIface::computeTimings
int computeTimings(uavcan::uint32_t target_bitrate, Timings &out_timings)
Definition: uc_stm32_can.cpp:195
uavcan_stm32::bxcan::CanType::FilterRegister
FilterRegisterType FilterRegister[28]
Definition: bxcan.hpp:72
uavcan::CanFrame::isRemoteTransmissionRequest
bool isRemoteTransmissionRequest() const
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:71
uavcan_stm32::bxcan::CanType::MCR
volatile uint32_t MCR
Definition: bxcan.hpp:51
uavcan_stm32::CanIface::canAcceptNewTxFrame
bool canAcceptNewTxFrame(const uavcan::CanFrame &frame) const
Definition: uc_stm32_can.cpp:818
uavcan_stm32::CanIface::NumTxMailboxes
@ NumTxMailboxes
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:110
uavcan_stm32::bxcan::TxMailboxType::TDHR
volatile uint32_t TDHR
Definition: bxcan.hpp:32
uavcan_stm32::CanIface::Timings::sjw
uavcan::uint8_t sjw
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:83
uavcan_stm32::bxcan::TSR_TXOK0
constexpr unsigned long TSR_TXOK0
Definition: bxcan.hpp:115
len_
std::uint8_t len_
Definition: can.cpp:85
uavcan::CanFrame::data
uint8_t data[MaxDataLen]
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:35
clock.hpp
out_
std::uint8_t out_
Definition: can.cpp:84
uavcan_stm32::bxcan::IER_TMEIE
constexpr unsigned long IER_TMEIE
Definition: bxcan.hpp:148
uavcan_stm32::bxcan::TSR_TXOK1
constexpr unsigned long TSR_TXOK1
Definition: bxcan.hpp:120
uavcan_stm32::clock::getMonotonic
uavcan::MonotonicTime getMonotonic()
Definition: clock.cpp:83
uavcan_stm32::bxcan::MCR_INRQ
constexpr unsigned long MCR_INRQ
Definition: bxcan.hpp:89
frame
uavcan::CanFrame frame
Definition: can.cpp:78
uavcan_stm32::bxcan::TIR_IDE
constexpr unsigned long TIR_IDE
Definition: bxcan.hpp:204
uavcan_stm32::bxcan::CanType::FMR
volatile uint32_t FMR
Definition: bxcan.hpp:63
uavcan::CanFrame::isExtended
bool isExtended() const
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:70
UAVCAN_STM32_IRQ_EPILOGUE
#define UAVCAN_STM32_IRQ_EPILOGUE()
Definition: stm32/libuavcan/driver/src/internal.hpp:52
uavcan_stm32::bxcan::CanType::RxMailbox
RxMailboxType RxMailbox[2]
Definition: bxcan.hpp:61
uavcan_stm32::clock::getUtcUSecFromCanInterrupt
uavcan::uint64_t getUtcUSecFromCanInterrupt()
Definition: clock.cpp:78
uavcan_stm32::CanIface::can_
bxcan::CanType *const can_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:116
UAVCAN_STM32_IRQ_PROLOGUE
#define UAVCAN_STM32_IRQ_PROLOGUE()
Definition: stm32/libuavcan/driver/src/internal.hpp:51
uavcan_stm32::CanDriver::initOnce
static void initOnce()
Definition: uc_stm32_can.cpp:979
uavcan_stm32::bxcan::MSR_INAK
constexpr unsigned long MSR_INAK
Definition: bxcan.hpp:102
uavcan_stm32::bxcan::RIR_RTR
constexpr unsigned long RIR_RTR
Definition: bxcan.hpp:242
uavcan_stm32::bxcan::CanType::FS1R
volatile uint32_t FS1R
Definition: bxcan.hpp:66
buf_
Item buf_[UAVCAN_LPC11C24_RX_QUEUE_LEN]
Definition: can.cpp:81
uavcan_stm32::CanIface::error_cnt_
uavcan::uint64_t error_cnt_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:117
uavcan_stm32::bxcan::FilterRegisterType::FR2
volatile uint32_t FR2
Definition: bxcan.hpp:46
uavcan_stm32::CanIface::discardTimedOutTxMailboxes
void discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time)
Definition: uc_stm32_can.cpp:803
uavcan_stm32::bxcan::CanType::TSR
volatile uint32_t TSR
Definition: bxcan.hpp:53
uavcan_stm32::bxcan::RFR_RFOM
constexpr unsigned long RFR_RFOM
Definition: bxcan.hpp:144
uavcan_stm32::CanIface::receive
virtual uavcan::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags)
Definition: uc_stm32_can.cpp:435
uavcan::CanIOFlags
uint16_t CanIOFlags
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:140
uavcan_stm32::CanIface::Timings::bs1
uavcan::uint8_t bs1
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:84
chip.h
uavcan_stm32::bxcan::CanType::BTR
volatile uint32_t BTR
Definition: bxcan.hpp:58
uavcan_stm32::bxcan::TSR_RQCP1
constexpr unsigned long TSR_RQCP1
Definition: bxcan.hpp:119
uavcan_stm32::CanDriver::makeSelectMasks
uavcan::CanSelectMasks makeSelectMasks(const uavcan::CanFrame *(&pending_tx)[uavcan::MaxCanIfaces]) const
Definition: uc_stm32_can.cpp:885
uavcan_stm32::bxcan::TIR_TXRQ
constexpr unsigned long TIR_TXRQ
Definition: bxcan.hpp:202
uavcan_stm32::CanIface::handleRxInterrupt
void handleRxInterrupt(uavcan::uint8_t fifo_index, uavcan::uint64_t utc_usec)
Definition: uc_stm32_can.cpp:714
uavcan_stm32::CanIface::RxQueue::overflow_cnt_
uavcan::uint32_t overflow_cnt_
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:56
uavcan_stm32::bxcan::TSR_RQCP2
constexpr unsigned long TSR_RQCP2
Definition: bxcan.hpp:124
uavcan_stm32::bxcan::TxMailboxType
Definition: bxcan.hpp:27
uavcan::MonotonicTime
Definition: time.hpp:184
uavcan_stm32::CanIface::getRxQueueLength
unsigned getRxQueueLength() const
Definition: uc_stm32_can.cpp:868
uavcan::CanFrame::priorityHigherThan
bool priorityHigherThan(const CanFrame &rhs) const
Definition: uc_can.cpp:19
uavcan_stm32::CanIface::TxItem::frame
uavcan::CanFrame frame
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:98
uavcan_stm32::CanIface::pollErrorFlagsFromISR
void pollErrorFlagsFromISR()
Definition: uc_stm32_can.cpp:781
ENABLE
@ ENABLE
Definition: lpc_types.h:68
uavcan::CanFilterConfig::id
uint32_t id
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:101
uavcan_stm32::bxcan::TSR_TME0
constexpr unsigned long TSR_TME0
Definition: bxcan.hpp:131
utc_usec
std::uint64_t utc_usec
Definition: can.cpp:77
uavcan::CanIOFlagAbortOnError
static const CanIOFlags CanIOFlagAbortOnError
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:142
uavcan_stm32::CanDriver::hasReadableInterfaces
bool hasReadableInterfaces() const
Definition: uc_stm32_can.cpp:915
uavcan_stm32::bxcan::FilterRegisterType::FR1
volatile uint32_t FR1
Definition: bxcan.hpp:45
uavcan_stm32::bxcan::RFR_FMP_MASK
constexpr unsigned long RFR_FMP_MASK
Definition: bxcan.hpp:141
uavcan_stm32::CanIface::RxQueue::getOverflowCount
uavcan::uint32_t getOverflowCount() const
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:77
uavcan_stm32::bxcan::CanType::TxMailbox
TxMailboxType TxMailbox[3]
Definition: bxcan.hpp:60
uavcan_stm32::CanIface::send
virtual uavcan::int16_t send(const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags)
Definition: uc_stm32_can.cpp:344
uavcan_stm32::CanIface::pending_tx_
TxItem pending_tx_[NumTxMailboxes]
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:120
uavcan_stm32::bxcan::BTR_SILM
constexpr unsigned long BTR_SILM
Definition: bxcan.hpp:194
uavcan_stm32::bxcan::TSR_ABRQ2
constexpr unsigned long TSR_ABRQ2
Definition: bxcan.hpp:128
uavcan_stm32::ErrFilterNumConfigs
static const uavcan::int16_t ErrFilterNumConfigs
Number of filters is more than supported.
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:26
UAVCAN_ASSERT
#define UAVCAN_ASSERT(x)
Definition: libuavcan/libuavcan/include/uavcan/build_config.hpp:184
uavcan_stm32::CanIface::Timings
Definition: platform_specific_components/stm32/libuavcan/driver/include/uavcan_stm32/can.hpp:80
uavcan::CanFrame::FlagRTR
static const uint32_t FlagRTR
Remote transmission request.
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:29
uavcan_stm32::bxcan::TxMailboxType::TDTR
volatile uint32_t TDTR
Definition: bxcan.hpp:30


uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:03