APM:Libraries
CAN.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
3  *
4  * With modifications for Ardupilot CAN driver
5  * Copyright (C) 2017 Eugene Shamaev
6  */
7 
8 #include <AP_HAL/AP_HAL.h>
9 #include <AP_HAL/system.h>
10 
13 
14 #if HAL_WITH_UAVCAN
15 
16 #include <cassert>
17 #include <cstring>
18 #include "CAN.h"
19 
20 #include <nuttx/irq.h>
21 #include <unistd.h>
22 #include <drivers/drv_hrt.h>
23 
24 #include <arch/board/board.h>
25 
26 #include "Scheduler.h"
27 
28 /*
29  * FOR INVESTIGATION:
30  * AP_HAL::micros64() was called for monotonic time counter
31  * pavel-kirienko: This will work as long as we don't need to synchronize the autopilot's own clock with an external
32  * time base, e.g. a GNSS time provided by an external GNSS receiver. Libuavcan's STM32 driver supports automatic time
33  * synchronization only if it has a dedicated hardware timer to work with.
34  */
35 
36 extern const AP_HAL::HAL& hal;
37 
38 #include <AP_UAVCAN/AP_UAVCAN.h>
39 
40 extern "C" {
41  static int can1_irq(const int irq, void*);
42 #if CAN_STM32_NUM_IFACES > 1
43  static int can2_irq(const int irq, void*);
44 #endif
45 }
46 
47 using namespace PX4;
48 
50 {
51  return AP_HAL::micros64();
52 }
53 
54 uavcan::MonotonicTime clock::getMonotonic()
55 {
56  return uavcan::MonotonicTime::fromUSec(AP_HAL::micros64());
57 }
58 
59 BusEvent::BusEvent(PX4CANManager& can_driver) :
60  _signal(0)
61 {
62  sem_init(&_wait_semaphore, 0, 0);
63 }
64 
65 BusEvent::~BusEvent()
66 {
67 }
68 
69 bool BusEvent::wait(uavcan::MonotonicDuration duration)
70 {
71  struct hrt_call wait_call;
72 
73  irqstate_t irs = irqsave();
74  if (_signal) {
75  _signal = 0;
76  irqrestore(irs);
77  return true;
78  }
79 
80  sem_init(&_wait_semaphore, 0, 0);
81  irqrestore(irs);
82 
83  hrt_call_after(&wait_call, duration.toUSec(), (hrt_callout) signalFromCallOut, this);
84  sem_wait(&_wait_semaphore);
85 
86  hrt_cancel(&wait_call);
87 
88  irs = irqsave();
89  if (_signal) {
90  _signal = 0;
91  irqrestore(irs);
92 
93  return true;
94  }
95  irqrestore(irs);
96 
97  return false;
98 }
99 
100 void BusEvent::signalFromCallOut(BusEvent *sem)
101 {
102  sem_post(&sem->_wait_semaphore);
103 }
104 
105 void BusEvent::signalFromInterrupt()
106 {
107  _signal++;
108  sem_post(&_wait_semaphore);
109 }
110 
111 static void handleTxInterrupt(uint8_t iface_index)
112 {
113  if (iface_index < CAN_STM32_NUM_IFACES) {
114  uint64_t utc_usec = clock::getUtcUSecFromCanInterrupt();
115 
116  for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
117  if (hal.can_mgr[i] != nullptr) {
118  PX4CAN* iface = ((PX4CANManager*) hal.can_mgr[i])->getIface_out_to_in(iface_index);
119  if (iface != nullptr) {
120  iface->handleTxInterrupt(utc_usec);
121  }
122  }
123  }
124  }
125 }
126 
127 static void handleRxInterrupt(uint8_t iface_index, uint8_t fifo_index)
128 {
129  if (iface_index < CAN_STM32_NUM_IFACES) {
130  uint64_t utc_usec = clock::getUtcUSecFromCanInterrupt();
131 
132  for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
133  if (hal.can_mgr[i] != nullptr) {
134  PX4CAN* iface = ((PX4CANManager*) hal.can_mgr[i])->getIface_out_to_in(iface_index);
135  if (iface != nullptr) {
136  iface->handleRxInterrupt(fifo_index, utc_usec);
137  }
138  }
139  }
140  }
141 }
142 
143 const uint32_t PX4CAN::TSR_ABRQx[PX4CAN::NumTxMailboxes] = { bxcan::TSR_ABRQ0, bxcan::TSR_ABRQ1, bxcan::TSR_ABRQ2 };
144 
145 int PX4CAN::computeTimings(const uint32_t target_bitrate, Timings& out_timings)
146 {
147  if (target_bitrate < 1) {
148  return -ErrInvalidBitRate;
149  }
150 
151  /*
152  * Hardware configuration
153  */
154  const uint32_t pclk = STM32_PCLK1_FREQUENCY;
155 
156  static const uint8_t MaxBS1 = 16;
157  static const uint8_t MaxBS2 = 8;
158 
159  /*
160  * Ref. "Automatic Baudrate Detection in CANopen Networks", U. Koppe, MicroControl GmbH & Co. KG
161  * CAN in Automation, 2003
162  *
163  * According to the source, optimal quanta per bit are:
164  * Bitrate Optimal Maximum
165  * 1000 kbps 8 10
166  * 500 kbps 16 17
167  * 250 kbps 16 17
168  * 125 kbps 16 17
169  */
170  const uint8_t max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 17;
171 
172  if (max_quanta_per_bit > (MaxBS1 + MaxBS2)) {
173  if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
174  printf("PX4CAN::computeTimings max_quanta_per_bit problem\n\r");
175  }
176  }
177 
178  static const uint16_t MaxSamplePointLocation = 900;
179 
180  /*
181  * Computing (prescaler * BS):
182  * BITRATE = 1 / (PRESCALER * (1 / PCLK) * (1 + BS1 + BS2)) -- See the Reference Manual
183  * BITRATE = PCLK / (PRESCALER * (1 + BS1 + BS2)) -- Simplified
184  * let:
185  * BS = 1 + BS1 + BS2 -- Number of time quanta per bit
186  * PRESCALER_BS = PRESCALER * BS
187  * ==>
188  * PRESCALER_BS = PCLK / BITRATE
189  */
190  const uint32_t prescaler_bs = pclk / target_bitrate;
191 
192  /*
193  * Searching for such prescaler value so that the number of quanta per bit is highest.
194  */
195  uint8_t bs1_bs2_sum = uint8_t(max_quanta_per_bit - 1);
196 
197  while ((prescaler_bs % (1 + bs1_bs2_sum)) != 0) {
198  if (bs1_bs2_sum <= 2) {
199  return -ErrInvalidBitRate; // No solution
200  }
201  bs1_bs2_sum--;
202  }
203 
204  const uint32_t prescaler = prescaler_bs / (1 + bs1_bs2_sum);
205  if ((prescaler < 1U) || (prescaler > 1024U)) {
206  return -ErrInvalidBitRate; // No solution
207  }
208 
209  /*
210  * Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum.
211  * We need to find the values so that the sample point is as close as possible to the optimal value.
212  *
213  * Solve[(1 + bs1)/(1 + bs1 + bs2) == 7/8, bs2] (* Where 7/8 is 0.875, the recommended sample point location *)
214  * {{bs2 -> (1 + bs1)/7}}
215  *
216  * Hence:
217  * bs2 = (1 + bs1) / 7
218  * bs1 = (7 * bs1_bs2_sum - 1) / 8
219  *
220  * Sample point location can be computed as follows:
221  * Sample point location = (1 + bs1) / (1 + bs1 + bs2)
222  *
223  * Since the optimal solution is so close to the maximum, we prepare two solutions, and then pick the best one:
224  * - With rounding to nearest
225  * - With rounding to zero
226  */
227  struct BsPair {
228  uint8_t bs1;
229  uint8_t bs2;
230  uint16_t sample_point_permill;
231 
232  BsPair() :
233  bs1(0), bs2(0), sample_point_permill(0)
234  {
235  }
236 
237  BsPair(uint8_t bs1_bs2_sum, uint8_t arg_bs1) :
238  bs1(arg_bs1), bs2(uint8_t(bs1_bs2_sum - bs1)), sample_point_permill(
239  uint16_t(1000 * (1 + bs1) / (1 + bs1 + bs2)))
240  {
241  if (bs1_bs2_sum <= arg_bs1) {
242  if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
243  AP_HAL::panic("PX4CAN::computeTimings bs1_bs2_sum <= arg_bs1");
244  }
245  }
246  }
247 
248  bool isValid() const
249  {
250  return (bs1 >= 1) && (bs1 <= MaxBS1) && (bs2 >= 1) && (bs2 <= MaxBS2);
251  }
252  };
253 
254  // First attempt with rounding to nearest
255  BsPair solution(bs1_bs2_sum, uint8_t(((7 * bs1_bs2_sum - 1) + 4) / 8));
256 
257  if (solution.sample_point_permill > MaxSamplePointLocation || !solution.isValid()) {
258  // Second attempt with rounding to zero
259  solution = BsPair(bs1_bs2_sum, uint8_t((7 * bs1_bs2_sum - 1) / 8));
260 
261  if (!solution.isValid())
262  {
263  printf("PX4CAN::computeTimings second solution invalid\n\r");
264  return -ErrLogic;
265  }
266  }
267 
268  /*
269  * Final validation
270  */
271  if ((target_bitrate != (pclk / (prescaler * (1 + solution.bs1 + solution.bs2)))) || !solution.isValid()) {
272  if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
273  printf("PX4CAN::computeTimings target_bitrate error\n\r");
274  }
275  return -ErrLogic;
276  }
277 
278  if (AP_BoardConfig_CAN::get_can_debug() >= 2) {
279  printf("PX4CAN::computeTimings Timings: quanta/bit: %d, sample point location: %.1f%%\n\r",
280  int(1 + solution.bs1 + solution.bs2), double(solution.sample_point_permill / 10.0));
281  }
282 
283  out_timings.prescaler = uint16_t(prescaler - 1U);
284  out_timings.sjw = 0; // Which means one
285  out_timings.bs1 = uint8_t(solution.bs1 - 1);
286  out_timings.bs2 = uint8_t(solution.bs2 - 1);
287 
288  return 0;
289 }
290 
291 int16_t PX4CAN::send(const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags)
292 {
293  if (frame.isErrorFrame() || frame.dlc > 8) {
294  return -ErrUnsupportedFrame;
295  }
296 
297  /*
298  * Normally we should perform the same check as in @ref canAcceptNewTxFrame(), because
299  * it is possible that the highest-priority frame between select() and send() could have been
300  * replaced with a lower priority one due to TX timeout. But we don't do this check because:
301  *
302  * - It is a highly unlikely scenario.
303  *
304  * - Frames do not timeout on a properly functioning bus. Since frames do not timeout, the new
305  * frame can only have higher priority, which doesn't break the logic.
306  *
307  * - If high-priority frames are timing out in the TX queue, there's probably a lot of other
308  * issues to take care of before this one becomes relevant.
309  *
310  * - It takes CPU time. Not just CPU time, but critical section time, which is expensive.
311  */
313 
314  /*
315  * Seeking for an empty slot
316  */
317  uint8_t txmailbox = 0xFF;
318  if ((can_->TSR & bxcan::TSR_TME0) == bxcan::TSR_TME0) {
319  txmailbox = 0;
320  } else if ((can_->TSR & bxcan::TSR_TME1) == bxcan::TSR_TME1) {
321  txmailbox = 1;
322  } else if ((can_->TSR & bxcan::TSR_TME2) == bxcan::TSR_TME2) {
323  txmailbox = 2;
324  } else {
325  return 0; // No transmission for you.
326  }
327 
328  peak_tx_mailbox_index_ = uavcan::max(peak_tx_mailbox_index_, txmailbox); // Statistics
329 
330  /*
331  * Setting up the mailbox
332  */
333  bxcan::TxMailboxType& mb = can_->TxMailbox[txmailbox];
334  if (frame.isExtended()) {
335  mb.TIR = ((frame.id & uavcan::CanFrame::MaskExtID) << 3) | bxcan::TIR_IDE;
336  } else {
337  mb.TIR = ((frame.id & uavcan::CanFrame::MaskStdID) << 21);
338  }
339 
340  if (frame.isRemoteTransmissionRequest()) {
341  mb.TIR |= bxcan::TIR_RTR;
342  }
343 
344  mb.TDTR = frame.dlc;
345 
346  mb.TDHR = (uint32_t(frame.data[7]) << 24) | (uint32_t(frame.data[6]) << 16) | (uint32_t(frame.data[5]) << 8)
347  | (uint32_t(frame.data[4]) << 0);
348  mb.TDLR = (uint32_t(frame.data[3]) << 24) | (uint32_t(frame.data[2]) << 16) | (uint32_t(frame.data[1]) << 8)
349  | (uint32_t(frame.data[0]) << 0);
350 
351  mb.TIR |= bxcan::TIR_TXRQ; // Go.
352 
353  /*
354  * Registering the pending transmission so we can track its deadline and loopback it as needed
355  */
356  TxItem& txi = pending_tx_[txmailbox];
357  txi.deadline = tx_deadline;
358  txi.frame = frame;
359  txi.loopback = (flags & uavcan::CanIOFlagLoopback) != 0;
360  txi.abort_on_error = (flags & uavcan::CanIOFlagAbortOnError) != 0;
361  txi.pending = true;
362  return 1;
363 }
364 
365 int16_t PX4CAN::receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
366  uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags)
367 {
368  out_ts_monotonic = clock::getMonotonic(); // High precision is not required for monotonic timestamps
369  uint64_t utc_usec = 0;
370  {
372  if (rx_queue_.available() == 0) {
373  return 0;
374  }
375 
376  CanRxItem frm;
377  rx_queue_.pop(frm);
378  out_frame = frm.frame;
379  utc_usec = frm.utc_usec;
380  out_flags = frm.flags;
381  }
382  out_ts_utc = uavcan::UtcTime::fromUSec(utc_usec);
383  return 1;
384 }
385 
386 int16_t PX4CAN::configureFilters(const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs)
387 {
388  if (num_configs <= NumFilters) {
390 
391  can_->FMR |= bxcan::FMR_FINIT;
392 
393  // Slave (CAN2) gets half of the filters
394  can_->FMR = (can_->FMR & ~0x00003F00) | static_cast<uint32_t>(NumFilters) << 8;
395 
396  can_->FFA1R = 0x0AAAAAAA; // FIFO's are interleaved between filters
397  can_->FM1R = 0; // Identifier Mask mode
398  can_->FS1R = 0x7ffffff; // Single 32-bit for all
399 
400  const uint8_t filter_start_index = (self_index_ == 0) ? 0 : NumFilters;
401 
402  if (num_configs == 0) {
403  can_->FilterRegister[filter_start_index].FR1 = 0;
404  can_->FilterRegister[filter_start_index].FR2 = 0;
405  can_->FA1R = 1 << filter_start_index;
406  } else {
407  for (uint8_t i = 0; i < NumFilters; i++) {
408  if (i < num_configs) {
409  uint32_t id = 0;
410  uint32_t mask = 0;
411 
412  const uavcan::CanFilterConfig* const cfg = filter_configs + i;
413 
414  if ((cfg->id & uavcan::CanFrame::FlagEFF) || !(cfg->mask & uavcan::CanFrame::FlagEFF)) {
415  id = (cfg->id & uavcan::CanFrame::MaskExtID) << 3;
416  mask = (cfg->mask & uavcan::CanFrame::MaskExtID) << 3;
417  id |= bxcan::RIR_IDE;
418  } else {
419  id = (cfg->id & uavcan::CanFrame::MaskStdID) << 21;
420  mask = (cfg->mask & uavcan::CanFrame::MaskStdID) << 21;
421  }
422 
423  if (cfg->id & uavcan::CanFrame::FlagRTR) {
424  id |= bxcan::RIR_RTR;
425  }
426 
427  if (cfg->mask & uavcan::CanFrame::FlagEFF) {
428  mask |= bxcan::RIR_IDE;
429  }
430 
431  if (cfg->mask & uavcan::CanFrame::FlagRTR) {
432  mask |= bxcan::RIR_RTR;
433  }
434 
435  can_->FilterRegister[filter_start_index + i].FR1 = id;
436  can_->FilterRegister[filter_start_index + i].FR2 = mask;
437 
438  can_->FA1R |= (1 << (filter_start_index + i));
439  } else {
440  can_->FA1R &= ~(1 << (filter_start_index + i));
441  }
442  }
443  }
444 
445  can_->FMR &= ~bxcan::FMR_FINIT;
446 
447  return 0;
448  }
449 
450  return -ErrFilterNumConfigs;
451 }
452 
453 bool PX4CAN::waitMsrINakBitStateChange(bool target_state)
454 {
455  const unsigned Timeout = 1000;
456  for (unsigned wait_ack = 0; wait_ack < Timeout; wait_ack++) {
457  const bool state = (can_->MSR & bxcan::MSR_INAK) != 0;
458  if (state == target_state) {
459  return true;
460  }
461  hal.scheduler->delay_microseconds(1000);
462  }
463  return false;
464 }
465 
466 int PX4CAN::init(const uint32_t bitrate, const OperatingMode mode)
467 {
468  /* We need to silence the controller in the first order, otherwise it may interfere with the following operations. */
469 
470  {
472 
473  can_->MCR &= ~bxcan::MCR_SLEEP; // Exit sleep mode
474  can_->MCR |= bxcan::MCR_INRQ; // Request init
475 
476  can_->IER = 0; // Disable CAN interrupts while initialization is in progress
477  }
478 
479  if (!waitMsrINakBitStateChange(true)) {
480  if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
481  printf("PX4CAN::init MSR INAK not set\n\r");
482  }
483  can_->MCR = bxcan::MCR_RESET;
484  return -ErrMsrInakNotSet;
485  }
486 
487  /*
488  * Object state - CAN interrupts are disabled, so it's safe to modify it now
489  */
490  rx_queue_.clear();
491  error_cnt_ = 0;
492  served_aborts_cnt_ = 0;
493  uavcan::fill_n(pending_tx_, NumTxMailboxes, TxItem());
494  peak_tx_mailbox_index_ = 0;
495  had_activity_ = false;
496 
497  /*
498  * CAN timings for this bitrate
499  */
500  Timings timings;
501  const int timings_res = computeTimings(bitrate, timings);
502  if (timings_res < 0) {
503  can_->MCR = bxcan::MCR_RESET;
504  return timings_res;
505  }
506  if (AP_BoardConfig_CAN::get_can_debug() >= 2) {
507  printf("PX4CAN::init Timings: presc=%u sjw=%u bs1=%u bs2=%u\n\r", unsigned(timings.prescaler),
508  unsigned(timings.sjw), unsigned(timings.bs1), unsigned(timings.bs2));
509  }
510 
511  /*
512  * Hardware initialization (the hardware has already confirmed initialization mode, see above)
513  */
514  can_->MCR = bxcan::MCR_ABOM | bxcan::MCR_AWUM | bxcan::MCR_INRQ; // RM page 648
515 
516  can_->BTR = ((timings.sjw & 3U) << 24) | ((timings.bs1 & 15U) << 16) | ((timings.bs2 & 7U) << 20)
517  | (timings.prescaler & 1023U) | ((mode == SilentMode) ? bxcan::BTR_SILM : 0);
518 
519  can_->IER = bxcan::IER_TMEIE | // TX mailbox empty
520  bxcan::IER_FMPIE0 | // RX FIFO 0 is not empty
521  bxcan::IER_FMPIE1; // RX FIFO 1 is not empty
522 
523  can_->MCR &= ~bxcan::MCR_INRQ; // Leave init mode
524 
525  if (!waitMsrINakBitStateChange(false)) {
526  if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
527  printf("PX4CAN::init MSR INAK not cleared\n\r");
528  }
529  can_->MCR = bxcan::MCR_RESET;
530  return -ErrMsrInakNotCleared;
531  }
532 
533  /*
534  * Default filter configuration
535  */
536  if (self_index_ == 0) {
537  can_->FMR |= bxcan::FMR_FINIT;
538 
539  can_->FMR &= 0xFFFFC0F1;
540  can_->FMR |= static_cast<uint32_t>(NumFilters) << 8; // Slave (CAN2) gets half of the filters
541 
542  can_->FFA1R = 0; // All assigned to FIFO0 by default
543  can_->FM1R = 0; // Indentifier Mask mode
544 
545 #if CAN_STM32_NUM_IFACES > 1
546  can_->FS1R = 0x7ffffff; // Single 32-bit for all
547  can_->FilterRegister[0].FR1 = 0; // CAN1 accepts everything
548  can_->FilterRegister[0].FR2 = 0;
549  can_->FilterRegister[NumFilters].FR1 = 0; // CAN2 accepts everything
550  can_->FilterRegister[NumFilters].FR2 = 0;
551  can_->FA1R = 1 | (1 << NumFilters); // One filter per each iface
552 #else
553  can_->FS1R = 0x1fff;
554  can_->FilterRegister[0].FR1 = 0;
555  can_->FilterRegister[0].FR2 = 0;
556  can_->FA1R = 1;
557 #endif
558 
559  can_->FMR &= ~bxcan::FMR_FINIT;
560  }
561 
562  return 0;
563 }
564 
565 void PX4CAN::handleTxMailboxInterrupt(uint8_t mailbox_index, bool txok, const uint64_t utc_usec)
566 {
567  if (mailbox_index < NumTxMailboxes) {
568 
569  had_activity_ = had_activity_ || txok;
570 
571  TxItem& txi = pending_tx_[mailbox_index];
572 
573  if (txi.loopback && txok && txi.pending) {
574  CanRxItem frm;
575  frm.frame = txi.frame;
576  frm.flags = uavcan::CanIOFlagLoopback;
577  frm.utc_usec = utc_usec;
578  rx_queue_.push(frm);
579  }
580 
581  txi.pending = false;
582  }
583 }
584 
585 void PX4CAN::handleTxInterrupt(const uint64_t utc_usec)
586 {
587  // TXOK == false means that there was a hardware failure
588  if (can_->TSR & bxcan::TSR_RQCP0) {
589  const bool txok = can_->TSR & bxcan::TSR_TXOK0;
590  can_->TSR = bxcan::TSR_RQCP0;
591  handleTxMailboxInterrupt(0, txok, utc_usec);
592  }
593  if (can_->TSR & bxcan::TSR_RQCP1) {
594  const bool txok = can_->TSR & bxcan::TSR_TXOK1;
595  can_->TSR = bxcan::TSR_RQCP1;
596  handleTxMailboxInterrupt(1, txok, utc_usec);
597  }
598  if (can_->TSR & bxcan::TSR_RQCP2) {
599  const bool txok = can_->TSR & bxcan::TSR_TXOK2;
600  can_->TSR = bxcan::TSR_RQCP2;
601  handleTxMailboxInterrupt(2, txok, utc_usec);
602  }
603 
604  if(update_event_ != nullptr) {
605  update_event_->signalFromInterrupt();
606  }
607 
608  pollErrorFlagsFromISR();
609 }
610 
611 void PX4CAN::handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec)
612 {
613  if (fifo_index < 2) {
614 
615  volatile uint32_t* const rfr_reg = (fifo_index == 0) ? &can_->RF0R : &can_->RF1R;
616  if ((*rfr_reg & bxcan::RFR_FMP_MASK) == 0) {
617  return;
618  }
619 
620  /*
621  * Register overflow as a hardware error
622  */
623  if ((*rfr_reg & bxcan::RFR_FOVR) != 0) {
624  error_cnt_++;
625  }
626 
627  /*
628  * Read the frame contents
629  */
630  uavcan::CanFrame frame;
631  const bxcan::RxMailboxType& rf = can_->RxMailbox[fifo_index];
632 
633  if ((rf.RIR & bxcan::RIR_IDE) == 0) {
634  frame.id = uavcan::CanFrame::MaskStdID & (rf.RIR >> 21);
635  } else {
636  frame.id = uavcan::CanFrame::MaskExtID & (rf.RIR >> 3);
637  frame.id |= uavcan::CanFrame::FlagEFF;
638  }
639 
640  if ((rf.RIR & bxcan::RIR_RTR) != 0) {
641  frame.id |= uavcan::CanFrame::FlagRTR;
642  }
643 
644  frame.dlc = rf.RDTR & 15;
645 
646  frame.data[0] = uint8_t(0xFF & (rf.RDLR >> 0));
647  frame.data[1] = uint8_t(0xFF & (rf.RDLR >> 8));
648  frame.data[2] = uint8_t(0xFF & (rf.RDLR >> 16));
649  frame.data[3] = uint8_t(0xFF & (rf.RDLR >> 24));
650  frame.data[4] = uint8_t(0xFF & (rf.RDHR >> 0));
651  frame.data[5] = uint8_t(0xFF & (rf.RDHR >> 8));
652  frame.data[6] = uint8_t(0xFF & (rf.RDHR >> 16));
653  frame.data[7] = uint8_t(0xFF & (rf.RDHR >> 24));
654 
655  *rfr_reg = bxcan::RFR_RFOM | bxcan::RFR_FOVR | bxcan::RFR_FULL; // Release FIFO entry we just read
656 
657  /*
658  * Store with timeout into the FIFO buffer and signal update event
659  */
660  CanRxItem frm;
661  frm.frame = frame;
662  frm.flags = 0;
663  frm.utc_usec = utc_usec;
664  rx_queue_.push(frm);
665 
666  had_activity_ = true;
667  if(update_event_ != nullptr) {
668  update_event_->signalFromInterrupt();
669  }
670 
671  pollErrorFlagsFromISR();
672  }
673 }
674 
675 void PX4CAN::pollErrorFlagsFromISR()
676 {
677  const uint8_t lec = uint8_t((can_->ESR & bxcan::ESR_LEC_MASK) >> bxcan::ESR_LEC_SHIFT);
678  if (lec != 0) {
679  can_->ESR = 0;
680  error_cnt_++;
681 
682  // Serving abort requests
683  for (int i = 0; i < NumTxMailboxes; i++) { // Dear compiler, may I suggest you to unroll this loop please.
684  TxItem& txi = pending_tx_[i];
685  if (txi.pending && txi.abort_on_error) {
686  can_->TSR = TSR_ABRQx[i];
687  txi.pending = false;
688  served_aborts_cnt_++;
689  }
690  }
691  }
692 }
693 
694 void PX4CAN::discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time)
695 {
697  for (int i = 0; i < NumTxMailboxes; i++) {
698  TxItem& txi = pending_tx_[i];
699  if (txi.pending && txi.deadline < current_time) {
700  can_->TSR = TSR_ABRQx[i]; // Goodnight sweet transmission
701  txi.pending = false;
702  error_cnt_++;
703  }
704  }
705 }
706 
707 bool PX4CAN::canAcceptNewTxFrame(const uavcan::CanFrame& frame) const
708 {
709  /*
710  * We can accept more frames only if the following conditions are satisfied:
711  * - There is at least one TX mailbox free (obvious enough);
712  * - The priority of the new frame is higher than priority of all TX mailboxes.
713  */
714  {
715  static const uint32_t TME = bxcan::TSR_TME0 | bxcan::TSR_TME1 | bxcan::TSR_TME2;
716  const uint32_t tme = can_->TSR & TME;
717 
718  if (tme == TME) { // All TX mailboxes are free (as in freedom).
719  return true;
720  }
721 
722  if (tme == 0) { // All TX mailboxes are busy transmitting.
723  return false;
724  }
725  }
726 
727  /*
728  * The second condition requires a critical section.
729  */
731 
732  for (int mbx = 0; mbx < NumTxMailboxes; mbx++) {
733  if (pending_tx_[mbx].pending && !frame.priorityHigherThan(pending_tx_[mbx].frame)) {
734  return false; // There's a mailbox whose priority is higher or equal the priority of the new frame.
735  }
736  }
737 
738  return true; // This new frame will be added to a free TX mailbox in the next @ref send().
739 }
740 
741 bool PX4CAN::isRxBufferEmpty() const
742 {
744  return rx_queue_.available() == 0;
745 }
746 
747 uint64_t PX4CAN::getErrorCount() const
748 {
750  return error_cnt_;
751  //TODO: + rx_queue_.getOverflowCount();
752 }
753 
754 unsigned PX4CAN::getRxQueueLength() const
755 {
757  return rx_queue_.available();
758 }
759 
760 bool PX4CAN::hadActivity()
761 {
763  const bool ret = had_activity_;
764  had_activity_ = false;
765  return ret;
766 }
767 
768 bool PX4CAN::begin(uint32_t bitrate)
769 {
770  if (init(bitrate, OperatingMode::NormalMode) == 0) {
771  bitrate_ = bitrate;
772  initialized_ = true;
773  } else {
774  initialized_ = false;
775  }
776  return initialized_;
777 }
778 
779 void PX4CAN::reset()
780 {
781  if (initialized_ && bitrate_ != 0) {
782  init(bitrate_, OperatingMode::NormalMode);
783  }
784 }
785 
786 bool PX4CAN::is_initialized()
787 {
788  return initialized_;
789 }
790 
791 int32_t PX4CAN::available()
792 {
793  if (initialized_) {
794  return getRxQueueLength();
795  } else {
796  return -1;
797  }
798 }
799 
800 int32_t PX4CAN::tx_pending()
801 {
802  int32_t ret = -1;
803 
804  if (initialized_) {
805  ret = 0;
807 
808  for (int mbx = 0; mbx < NumTxMailboxes; mbx++) {
809  if (pending_tx_[mbx].pending) {
810  ret++;
811  }
812  }
813  }
814 
815  return ret;
816 }
817 
818 /*
819  * CanDriver
820  */
821 
822 PX4CANManager::PX4CANManager() :
823  AP_HAL::CANManager(this), update_event_(*this), if0_(bxcan::Can[0], nullptr, 0, CAN_STM32_RX_QUEUE_SIZE), if1_(
824  bxcan::Can[1], nullptr, 1, CAN_STM32_RX_QUEUE_SIZE), initialized_(false), p_uavcan(nullptr)
825 {
826  uavcan::StaticAssert<(CAN_STM32_RX_QUEUE_SIZE <= PX4CAN::MaxRxQueueCapacity)>::check();
827 
828  for(uint8_t i = 0; i < CAN_STM32_NUM_IFACES; i++) {
829  _ifaces_out_to_in[i] = UINT8_MAX;
830  }
831 }
832 
833 uavcan::CanSelectMasks PX4CANManager::makeSelectMasks(const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces]) const
834 {
835  uavcan::CanSelectMasks msk;
836 
837  for (uint8_t i = 0; i < _ifaces_num; i++) {
838  if (ifaces[i] != nullptr) {
839  if (!ifaces[i]->isRxBufferEmpty()) {
840  msk.read |= 1 << i;
841  }
842 
843  if (pending_tx[i] != nullptr) {
844  if (ifaces[i]->canAcceptNewTxFrame(*pending_tx[i])) {
845  msk.write |= 1 << i;
846  }
847  }
848  }
849  }
850 
851  return msk;
852 }
853 
854 bool PX4CANManager::hasReadableInterfaces() const
855 {
856  bool ret = false;
857 
858  for (uint8_t i = 0; i < _ifaces_num; i++) {
859  if (ifaces[i] != nullptr) {
860  ret |= !ifaces[i]->isRxBufferEmpty();
861  }
862  }
863 
864  return ret;
865 }
866 
867 int16_t PX4CANManager::select(uavcan::CanSelectMasks& inout_masks,
868  const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces], const uavcan::MonotonicTime blocking_deadline)
869 {
870  const uavcan::CanSelectMasks in_masks = inout_masks;
871  const uavcan::MonotonicTime time = clock::getMonotonic();
872 
873  for (uint8_t i = 0; i < _ifaces_num; i++) {
874  if (ifaces[i] != nullptr) {
875  ifaces[i]->discardTimedOutTxMailboxes(time);
876  {
877  CriticalSectionLocker cs_locker;
878  ifaces[i]->pollErrorFlagsFromISR();
879  }
880  }
881  }
882 
883  inout_masks = makeSelectMasks(pending_tx); // Check if we already have some of the requested events
884  if ((inout_masks.read & in_masks.read) != 0 || (inout_masks.write & in_masks.write) != 0) {
885  return 1;
886  }
887 
888  (void) update_event_.wait(blocking_deadline - time); // Block until timeout expires or any iface updates
889  inout_masks = makeSelectMasks(pending_tx); // Return what we got even if none of the requested events are set
890  return 1; // Return value doesn't matter as long as it is non-negative
891 }
892 
893 void PX4CANManager::initOnce(uint8_t can_number)
894 {
895  {
897  if (can_number == 0) {
898  modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_CAN1EN);
899  }
900 #if CAN_STM32_NUM_IFACES > 1
901  if (can_number == 1) {
902  modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_CAN2EN);
903  }
904 #endif
905  }
906 
907  if (can_number == 0) {
908 #if defined(GPIO_CAN1_RX) && defined(GPIO_CAN1_TX)
909  stm32_configgpio(GPIO_CAN1_RX);
910  stm32_configgpio(GPIO_CAN1_TX);
911 #else
912 # error "Need to define GPIO_CAN1_RX/TX"
913 #endif
914  }
915 #if CAN_STM32_NUM_IFACES > 1
916  if (can_number == 1) {
917 #if defined(GPIO_CAN2_RX) && defined(GPIO_CAN2_TX)
918  stm32_configgpio(GPIO_CAN2_RX | GPIO_PULLUP);
919  stm32_configgpio(GPIO_CAN2_TX);
920 #else
921 # error "Need to define GPIO_CAN2_RX/TX"
922 #endif // defined(GPIO_CAN2_RX) && defined(GPIO_CAN2_TX)
923  }
924 #endif // CAN_STM32_NUM_IFACES > 1
925 
926  /*
927  * IRQ
928  */
929  if (can_number == 0) {
930 #if defined(STM32_IRQ_CAN1TX) && defined(STM32_IRQ_CAN1RX0) && defined(STM32_IRQ_CAN1RX1)
931  CAN_IRQ_ATTACH(STM32_IRQ_CAN1TX, can1_irq);
932  CAN_IRQ_ATTACH(STM32_IRQ_CAN1RX0, can1_irq);
933  CAN_IRQ_ATTACH(STM32_IRQ_CAN1RX1, can1_irq);
934 #else
935 # error "Need to define STM32_IRQ_CAN1TX/RX0/RX1"
936 #endif
937  }
938 
939 #if CAN_STM32_NUM_IFACES > 1
940  if (can_number == 1) {
941 #if defined(STM32_IRQ_CAN2TX) && defined(STM32_IRQ_CAN2RX0) && defined(STM32_IRQ_CAN2RX1)
942  CAN_IRQ_ATTACH(STM32_IRQ_CAN2TX, can2_irq);
943  CAN_IRQ_ATTACH(STM32_IRQ_CAN2RX0, can2_irq);
944  CAN_IRQ_ATTACH(STM32_IRQ_CAN2RX1, can2_irq);
945 #else
946 # error "Need to define STM32_IRQ_CAN2TX/RX0/RX1"
947 #endif // defined(STM32_IRQ_CAN2TX) && defined(STM32_IRQ_CAN2RX0) && defined(STM32_IRQ_CAN2RX1)
948  }
949 #endif // CAN_STM32_NUM_IFACES > 1
950 }
951 
952 int PX4CANManager::init(const uint32_t bitrate, const PX4CAN::OperatingMode mode, uint8_t can_number)
953 {
954  int res = -ErrNotImplemented;
955  static bool initialized_once[CAN_STM32_NUM_IFACES];
956 
957  if (can_number < CAN_STM32_NUM_IFACES) {
958  res = 0;
959 
960  if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) {
961  printf("PX4CANManager::init Bitrate %lu mode %d bus %d\n\r", static_cast<unsigned long>(bitrate),
962  static_cast<int>(mode), static_cast<int>(can_number));
963  }
964 
965  // If this outside physical interface was never inited - do this and add it to in/out conversion tables
966  if (!initialized_once[can_number]) {
967  initialized_once[can_number] = true;
968  _ifaces_num++;
969  _ifaces_out_to_in[can_number] = _ifaces_num - 1;
970 
971  if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) {
972  printf("PX4CANManager::init First initialization bus %d\n\r", static_cast<int>(can_number));
973  }
974 
975  initOnce(can_number);
976  }
977 
978  /*
979  * CAN1
980  */
981  if (can_number == 0) {
982  if (AP_BoardConfig_CAN::get_can_debug(0) >= 2) {
983  printf("PX4CANManager::init Initing iface 0...\n\r");
984  }
985  ifaces[_ifaces_out_to_in[can_number]] = &if0_; // This link must be initialized first,
986  }
987 
988 #if CAN_STM32_NUM_IFACES > 1
989  /*
990  * CAN2
991  */
992  if (can_number == 1) {
993  if (AP_BoardConfig_CAN::get_can_debug(1) >= 2) {
994  printf("PX4CANManager::init Initing iface 1...\n\r");
995  }
996  ifaces[_ifaces_out_to_in[can_number]] = &if1_; // Same thing here.
997  }
998 #endif
999 
1000  ifaces[_ifaces_out_to_in[can_number]]->set_update_event(&update_event_);
1001  res = ifaces[_ifaces_out_to_in[can_number]]->init(bitrate, mode);
1002  if (res < 0) {
1003  ifaces[_ifaces_out_to_in[can_number]] = nullptr;
1004  return res;
1005  }
1006 
1007  if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) {
1008  printf("PX4CANManager::init CAN drv init OK, res = %d\n\r", res);
1009  }
1010  }
1011 
1012  return res;
1013 }
1014 
1015 PX4CAN* PX4CANManager::getIface(uint8_t iface_index)
1016 {
1017  if (iface_index < _ifaces_num) {
1018  return ifaces[iface_index];
1019  }
1020 
1021  return nullptr;
1022 }
1023 
1024 PX4CAN* PX4CANManager::getIface_out_to_in(uint8_t iface_index)
1025 {
1026  // Find which internal interface corresponds to required outside physical interface
1027  if (iface_index < CAN_STM32_NUM_IFACES) {
1028  if (_ifaces_out_to_in[iface_index] != UINT8_MAX) {
1029  return ifaces[_ifaces_out_to_in[iface_index]];
1030  }
1031  }
1032 
1033  return nullptr;
1034 }
1035 
1036 bool PX4CANManager::hadActivity()
1037 {
1038  bool ret = false;
1039 
1040  // Go through all interfaces that are present in this manager
1041  for (uint8_t i = 0; i < _ifaces_num; i++)
1042  {
1043  if (ifaces[i] != nullptr) {
1044  ret |= ifaces[i]->hadActivity();
1045  }
1046  }
1047 
1048  return ret;
1049 }
1050 
1051 bool PX4CANManager::begin(uint32_t bitrate, uint8_t can_number)
1052 {
1053  // Try to init outside physical interface 'can_number'
1054  if (init(bitrate, PX4CAN::OperatingMode::NormalMode, can_number) >= 0) {
1055  return true;
1056  }
1057 
1058  return false;
1059 }
1060 
1061 bool PX4CANManager::is_initialized()
1062 {
1063  return initialized_;
1064 }
1065 
1066 void PX4CANManager::initialized(bool val)
1067 {
1068  initialized_ = val;
1069 }
1070 
1071 AP_UAVCAN *PX4CANManager::get_UAVCAN(void)
1072 {
1073  return p_uavcan;
1074 }
1075 
1076 void PX4CANManager::set_UAVCAN(AP_UAVCAN *uavcan)
1077 {
1078  p_uavcan = uavcan;
1079 }
1080 
1081 /*
1082  * Interrupt handlers
1083  */
1084 extern "C" {
1085  static int can1_irq(const int irq, void*)
1086  {
1087  if (irq == STM32_IRQ_CAN1TX) {
1088  handleTxInterrupt(0);
1089  } else if (irq == STM32_IRQ_CAN1RX0) {
1090  handleRxInterrupt(0, 0);
1091  } else if (irq == STM32_IRQ_CAN1RX1) {
1092  handleRxInterrupt(0, 1);
1093  } else {
1094  printf("can1_irq unhandled");
1095  }
1096  return 0;
1097  }
1098 
1099 #if CAN_STM32_NUM_IFACES > 1
1100  static int can2_irq(const int irq, void*)
1101  {
1102  if (irq == STM32_IRQ_CAN2TX) {
1103  handleTxInterrupt(1);
1104  } else if (irq == STM32_IRQ_CAN2RX0) {
1105  handleRxInterrupt(1, 0);
1106  } else if (irq == STM32_IRQ_CAN2RX1) {
1107  handleRxInterrupt(1, 1);
1108  } else {
1109  printf("can2_irq unhandled");
1110  }
1111  return 0;
1112  }
1113 #endif
1114 
1115 } // extern "C"
1116 
1117 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
volatile uint32_t RIR
Definition: bxcan.h:52
volatile uint32_t TDLR
Definition: bxcan.h:47
constexpr unsigned long TSR_RQCP0
Definition: bxcan.h:120
constexpr unsigned long TIR_IDE
Definition: bxcan.h:210
volatile uint32_t RDTR
Definition: bxcan.h:53
constexpr unsigned long TIR_RTR
Definition: bxcan.h:209
constexpr unsigned long TSR_ABRQ0
Definition: bxcan.h:124
constexpr unsigned long TSR_TXOK2
Definition: bxcan.h:131
static const int16_t ErrLogic
Internal logic error.
Definition: CAN.h:35
constexpr unsigned long IER_FMPIE0
Definition: bxcan.h:155
uint64_t utc_usec
Definition: CAN.h:47
constexpr unsigned long FMR_FINIT
Definition: bxcan.h:288
constexpr unsigned long TIR_TXRQ
Definition: bxcan.h:208
volatile uint32_t TDHR
Definition: bxcan.h:48
uavcan::CanIOFlags flags
Definition: CAN.h:49
static int max(int a, int b)
Definition: compat.h:35
void reset()
constexpr unsigned long TSR_TME2
Definition: bxcan.h:139
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define CAN_STM32_RX_QUEUE_SIZE
Definition: CAN.h:25
constexpr unsigned long MCR_RESET
Definition: bxcan.h:103
constexpr unsigned long IER_TMEIE
Definition: bxcan.h:154
#define CAN_IRQ_ATTACH(irq, handler)
Definition: bxcan.h:36
uavcan::MonotonicTime getMonotonic()
constexpr unsigned long MCR_AWUM
Definition: bxcan.h:100
OperatingMode
Definition: CAN.h:164
constexpr unsigned long MSR_INAK
Definition: bxcan.h:108
constexpr unsigned long TSR_RQCP1
Definition: bxcan.h:125
constexpr unsigned long TSR_TXOK1
Definition: bxcan.h:126
volatile uint32_t TIR
Definition: bxcan.h:45
AP_HAL::CANManager ** can_mgr
Definition: HAL.h:120
constexpr unsigned long RFR_RFOM
Definition: bxcan.h:150
constexpr unsigned long ESR_LEC_SHIFT
Definition: bxcan.h:174
constexpr unsigned long TSR_ABRQ2
Definition: bxcan.h:134
constexpr unsigned long RIR_IDE
Definition: bxcan.h:249
constexpr unsigned long IER_FMPIE1
Definition: bxcan.h:158
constexpr unsigned long RFR_FULL
Definition: bxcan.h:148
#define CAN_STM32_NUM_IFACES
Definition: CAN.h:22
constexpr unsigned long TSR_TME0
Definition: bxcan.h:137
static const int16_t ErrMsrInakNotSet
INAK bit of the MSR register is not 1.
Definition: CAN.h:37
static const int16_t ErrMsrInakNotCleared
INAK bit of the MSR register is not 0.
Definition: CAN.h:38
bool hadActivity()
volatile uint32_t TDTR
Definition: bxcan.h:46
constexpr unsigned long RFR_FOVR
Definition: bxcan.h:149
static const int16_t ErrInvalidBitRate
Bit rate not supported.
Definition: CAN.h:34
uint64_t micros64()
Definition: system.cpp:162
static int state
Definition: Util.cpp:20
volatile uint32_t RDLR
Definition: bxcan.h:54
constexpr unsigned long MCR_ABOM
Definition: bxcan.h:101
static const int16_t ErrNotImplemented
Feature not implemented.
Definition: CAN.h:33
constexpr unsigned long ESR_LEC_MASK
Definition: bxcan.h:175
uint64_t getUtcUSecFromCanInterrupt()
constexpr unsigned long TSR_TXOK0
Definition: bxcan.h:121
constexpr unsigned long TSR_RQCP2
Definition: bxcan.h:130
static const int16_t ErrFilterNumConfigs
Auto bit rate detection could not be finished.
Definition: CAN.h:40
BusEvent(PX4CANManager &can_driver)
void handleTxInterrupt(uint64_t utc_usec)
void init()
Generic board initialization function.
Definition: system.cpp:136
virtual void delay_microseconds(uint16_t us)=0
constexpr unsigned long RFR_FMP_MASK
Definition: bxcan.h:147
volatile uint32_t RDHR
Definition: bxcan.h:55
constexpr unsigned long TSR_ABRQ1
Definition: bxcan.h:129
constexpr unsigned long BTR_SILM
Definition: bxcan.h:200
constexpr unsigned long MCR_INRQ
Definition: bxcan.h:95
constexpr unsigned long TSR_TME1
Definition: bxcan.h:138
constexpr unsigned long MCR_SLEEP
Definition: bxcan.h:96
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
constexpr unsigned long RIR_RTR
Definition: bxcan.h:248
sem_t _wait_semaphore
Definition: CAN.h:84
CanType *const Can[2]
Definition: bxcan.h:91
static const int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc)
Definition: CAN.h:36
uavcan::CanFrame frame
Definition: CAN.h:48
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
void handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec)