can.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
3  */
4 
8 #include <chip.h>
9 #include "c_can.hpp"
10 #include "internal.hpp"
11 
15 #ifndef UAVCAN_LPC11C24_RX_QUEUE_LEN
16 # define UAVCAN_LPC11C24_RX_QUEUE_LEN 8
17 #endif
18 
19 #if UAVCAN_LPC11C24_RX_QUEUE_LEN > 254
20 # error UAVCAN_LPC11C24_RX_QUEUE_LEN is too large
21 #endif
22 
23 extern "C" void canRxCallback(std::uint8_t msg_obj_num);
24 extern "C" void canTxCallback(std::uint8_t msg_obj_num);
25 extern "C" void canErrorCallback(std::uint32_t error_info);
26 
27 namespace uavcan_lpc11c24
28 {
29 namespace
30 {
38 constexpr unsigned NumberOfMessageObjects = 32;
39 constexpr unsigned NumberOfTxMessageObjects = 1;
40 constexpr unsigned NumberOfRxMessageObjects = NumberOfMessageObjects - NumberOfTxMessageObjects;
41 constexpr unsigned TxMessageObjectNumber = 1;
42 
47 volatile std::uint32_t error_cnt = 0;
48 
52 volatile bool tx_pending = false;
53 
57 volatile bool tx_abort_on_error = false;
58 
62 volatile std::uint64_t last_irq_utc_timestamp = 0;
63 
67 volatile bool had_activity = false;
68 
73 class RxQueue
74 {
75  struct Item
76  {
79  };
80 
86 
87 public:
88  void push(const uavcan::CanFrame& frame, const volatile std::uint64_t& utc_usec)
89  {
90  buf_[in_].frame = frame;
91  buf_[in_].utc_usec = utc_usec;
92  in_++;
94  {
95  in_ = 0;
96  }
97  len_++;
99  {
101  if (overflow_cnt_ < 0xFFFFFFFF)
102  {
103  overflow_cnt_++;
104  }
105  out_++;
107  {
108  out_ = 0;
109  }
110  }
111  }
112 
113  void pop(uavcan::CanFrame& out_frame, std::uint64_t& out_utc_usec)
114  {
115  if (len_ > 0)
116  {
117  out_frame = buf_[out_].frame;
118  out_utc_usec = buf_[out_].utc_usec;
119  out_++;
121  {
122  out_ = 0;
123  }
124  len_--;
125  }
126  }
127 
128  unsigned getLength() const { return len_; }
129 
130  std::uint32_t getOverflowCount() const { return overflow_cnt_; }
131 };
132 
133 RxQueue rx_queue;
134 
135 
136 struct BitTimingSettings
137 {
140 
141  bool isValid() const { return canbtr != 0; }
142 };
143 
147 BitTimingSettings computeBitTimings(std::uint32_t bitrate)
148 {
149  if (Chip_Clock_GetSystemClockRate() == 48000000) // 48 MHz is optimal for CAN timings
150  {
151  switch (bitrate)
152  {
153  case 1000000: return BitTimingSettings{ 0, 0x0505 }; // 8 quanta, 87.5%
154  case 500000: return BitTimingSettings{ 0, 0x1c05 }; // 16 quanta, 87.5%
155  case 250000: return BitTimingSettings{ 0, 0x1c0b }; // 16 quanta, 87.5%
156  case 125000: return BitTimingSettings{ 0, 0x1c17 }; // 16 quanta, 87.5%
157  case 100000: return BitTimingSettings{ 0, 0x1c1d }; // 16 quanta, 87.5%
158  default: return BitTimingSettings{ 0, 0 };
159  }
160  }
161  else
162  {
163  return BitTimingSettings{ 0, 0 };
164  }
165 }
166 
167 } // namespace
168 
169 CanDriver CanDriver::self;
170 
172 {
173  static constexpr uavcan::uint32_t BitRatesToTry[] =
174  {
175  1000000,
176  500000,
177  250000,
178  125000,
179  100000
180  };
181 
182  const auto ListeningDuration = uavcan::MonotonicDuration::fromMSec(1050);
183 
185  Chip_Clock_EnablePeriphClock(SYSCTL_CLOCK_CAN);
186 
187  for (auto bitrate : BitRatesToTry)
188  {
189  // Computing bit timings
190  const auto bit_timings = computeBitTimings(bitrate);
191  if (!bit_timings.isValid())
192  {
193  return 0;
194  }
195 
196  // Configuring the CAN controller
197  {
198  CriticalSectionLocker locker;
199 
200  LPC_SYSCTL->PRESETCTRL |= (1U << RESET_CAN0);
201 
202  // Entering initialization mode
204 
205  while ((c_can::CAN.CNTL & c_can::CNTL_INIT) == 0)
206  {
207  ; // Nothing to do
208  }
209 
210  // Configuring bit rate
211  c_can::CAN.CLKDIV = bit_timings.canclkdiv;
212  c_can::CAN.BT = bit_timings.canbtr;
213  c_can::CAN.BRPE = 0;
214 
215  // Configuring silent mode
218 
219  // Configuring status monitor
221 
222  // Leaving initialization mode
224 
225  while ((c_can::CAN.CNTL & c_can::CNTL_INIT) != 0)
226  {
227  ; // Nothing to do
228  }
229  }
230 
231  // Listening
232  const auto deadline = clock::getMonotonic() + ListeningDuration;
233  bool match_detected = false;
234  while (clock::getMonotonic() < deadline)
235  {
236  if (idle_callback != nullptr)
237  {
238  idle_callback();
239  }
240 
241  const auto LastErrorCode = (c_can::CAN.STAT >> c_can::STAT_LEC_SHIFT) & c_can::STAT_LEC_MASK;
242 
243  if (LastErrorCode == unsigned(c_can::StatLec::NoError))
244  {
245  match_detected = true;
246  break;
247  }
248  }
249 
250  // De-configuring the CAN controller back to reset state
251  {
252  CriticalSectionLocker locker;
253 
255 
256  while ((c_can::CAN.CNTL & c_can::CNTL_INIT) == 0)
257  {
258  ; // Nothing to do
259  }
260 
261  LPC_SYSCTL->PRESETCTRL &= ~(1U << RESET_CAN0);
262  }
263 
264  // Termination condition
265  if (match_detected)
266  {
267  return bitrate;
268  }
269  }
270 
271  return 0; // No match
272 }
273 
275 {
276  {
277  auto bit_timings = computeBitTimings(bitrate);
278  if (!bit_timings.isValid())
279  {
280  return -1;
281  }
282 
283  CriticalSectionLocker locker;
284 
285  error_cnt = 0;
286  tx_abort_on_error = false;
287  tx_pending = false;
288  last_irq_utc_timestamp = 0;
289  had_activity = false;
290 
291  /*
292  * C_CAN init
293  */
294  Chip_Clock_EnablePeriphClock(SYSCTL_CLOCK_CAN);
295 
296  LPC_CCAN_API->init_can(reinterpret_cast<std::uint32_t*>(&bit_timings), true);
297 
298  static CCAN_CALLBACKS_T ccan_callbacks =
299  {
303  nullptr,
304  nullptr,
305  nullptr,
306  nullptr,
307  nullptr
308  };
309  LPC_CCAN_API->config_calb(&ccan_callbacks);
310 
311  /*
312  * Interrupts
313  */
314  c_can::CAN.CNTL |= c_can::CNTL_SIE; // This is necessary for transmission aborts on error
315 
317  }
318 
319  /*
320  * Applying default filter configuration (accept all)
321  */
322  if (configureFilters(nullptr, 0) < 0)
323  {
324  return -1;
325  }
326 
327  return 0;
328 }
329 
331 {
332  CriticalSectionLocker locker;
333  return rx_queue.getLength() > 0;
334 }
335 
337 {
338  CriticalSectionLocker locker;
339  return !tx_pending;
340 }
341 
343 {
344  CriticalSectionLocker locker;
345  const bool ret = had_activity;
346  had_activity = false;
347  return ret;
348 }
349 
351 {
352  CriticalSectionLocker locker;
353  return rx_queue.getOverflowCount();
354 }
355 
357 {
358  return (c_can::CAN.STAT & c_can::STAT_BOFF) != 0;
359 }
360 
362  uavcan::CanIOFlags flags)
363 {
364  if (frame.isErrorFrame() ||
365  frame.dlc > 8 ||
366  (flags & uavcan::CanIOFlagLoopback) != 0) // TX timestamping is not supported by this driver.
367  {
368  return -1;
369  }
370 
371  /*
372  * Frame conversion
373  */
374  CCAN_MSG_OBJ_T msgobj = CCAN_MSG_OBJ_T();
376  if (frame.isExtended())
377  {
378  msgobj.mode_id |= CAN_MSGOBJ_EXT;
379  }
381  {
382  msgobj.mode_id |= CAN_MSGOBJ_RTR;
383  }
384  msgobj.dlc = frame.dlc;
386 
387  /*
388  * Transmission
389  */
390  (void)tx_deadline; // TX timeouts are not supported by this driver yet (and hardly going to be).
391 
392  CriticalSectionLocker locker;
393 
394  if (!tx_pending)
395  {
396  tx_pending = true; // Mark as pending - will be released in TX callback
397  tx_abort_on_error = (flags & uavcan::CanIOFlagAbortOnError) != 0;
398  msgobj.msgobj = TxMessageObjectNumber;
399  LPC_CCAN_API->can_transmit(&msgobj);
400  return 1;
401  }
402  return 0;
403 }
404 
406  uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags)
407 {
408  out_ts_monotonic = clock::getMonotonic();
409  out_flags = 0; // We don't support any IO flags
410 
411  CriticalSectionLocker locker;
412  if (rx_queue.getLength() == 0)
413  {
414  return 0;
415  }
416  std::uint64_t ts_utc = 0;
417  rx_queue.pop(out_frame, ts_utc);
418  out_ts_utc = uavcan::UtcTime::fromUSec(ts_utc);
419  return 1;
420 }
421 
424  uavcan::MonotonicTime blocking_deadline)
425 {
426  const bool bus_off = isInBusOffState();
427  if (bus_off) // Recover automatically on bus-off
428  {
429  CriticalSectionLocker locker;
430  if ((c_can::CAN.CNTL & c_can::CNTL_INIT) != 0)
431  {
432  c_can::CAN.CNTL &= ~c_can::CNTL_INIT;
433  }
434  }
435 
436  const bool noblock = ((inout_masks.read == 1) && hasReadyRx()) ||
437  ((inout_masks.write == 1) && hasEmptyTx());
438 
439  if (!noblock && (clock::getMonotonic() > blocking_deadline))
440  {
441 #if defined(UAVCAN_LPC11C24_USE_WFE) && UAVCAN_LPC11C24_USE_WFE
442  /*
443  * It's not cool (literally) to burn cycles in a busyloop, and we have no OS to pass control to other
444  * tasks, thus solution is to halt the core until a hardware event occurs - e.g. clock timer overflow.
445  * Upon such event the select() call will return, even if no requested IO operations became available.
446  * It's OK to do that, libuavcan can handle such behavior.
447  *
448  * Note that it is not possible to precisely control the sleep duration with WFE, since we can't predict when
449  * the next hardware event occurs. Worst case conditions:
450  * - WFE gets executed right after the clock timer interrupt;
451  * - CAN bus is completely silent (no traffic);
452  * - User's application has no interrupts and generates no hardware events.
453  * In such scenario execution will stuck here for one period of the clock timer interrupt, even if
454  * blocking_deadline expires sooner.
455  * If the user's application requires higher timing precision, an extra dummy IRQ can be added just to
456  * break WFE every once in a while.
457  */
458  __WFE();
459 #endif
460  }
461 
462  inout_masks.read = hasReadyRx() ? 1 : 0;
463 
464  inout_masks.write = (hasEmptyTx() && !bus_off) ? 1 : 0; // Disable write while in bus-off
465 
466  return 0; // Return value doesn't matter as long as it is non-negative
467 }
468 
470  uavcan::uint16_t num_configs)
471 {
472  CriticalSectionLocker locker;
473 
474  /*
475  * If C_CAN is active (INIT=0) and the CAN bus has intensive traffic, RX object configuration may fail.
476  * The solution is to disable the controller while configuration is in progress.
477  * The documentation, as always, doesn't bother to mention this detail. Shame on you, NXP.
478  */
479  struct RAIIDisabler
480  {
481  RAIIDisabler()
482  {
484  }
485  ~RAIIDisabler()
486  {
487  c_can::CAN.CNTL &= ~c_can::CNTL_INIT;
488  }
489  } can_disabler; // Must be instantiated AFTER the critical section locker
490 
491  if (num_configs == 0)
492  {
493  auto msg_obj = CCAN_MSG_OBJ_T();
494  msg_obj.msgobj = NumberOfTxMessageObjects + 1;
495  LPC_CCAN_API->config_rxmsgobj(&msg_obj); // all STD frames
496 
497  msg_obj.mode_id = CAN_MSGOBJ_EXT;
498  msg_obj.msgobj = NumberOfTxMessageObjects + 2;
499  LPC_CCAN_API->config_rxmsgobj(&msg_obj); // all EXT frames
500  }
501  else if (num_configs <= NumberOfRxMessageObjects)
502  {
503  // Making sure the configs use only EXT frames; otherwise we can't accept them
504  for (unsigned i = 0; i < num_configs; i++)
505  {
506  auto& f = filter_configs[i];
507  if ((f.id & f.mask & uavcan::CanFrame::FlagEFF) == 0)
508  {
509  return -1;
510  }
511  }
512 
513  // Installing the configuration
514  for (unsigned i = 0; i < NumberOfRxMessageObjects; i++)
515  {
516  auto msg_obj = CCAN_MSG_OBJ_T();
517  msg_obj.msgobj = std::uint8_t(i + 1U + NumberOfTxMessageObjects); // Message objects are numbered from 1
518 
519  if (i < num_configs)
520  {
521  msg_obj.mode_id = (filter_configs[i].id & uavcan::CanFrame::MaskExtID) | CAN_MSGOBJ_EXT; // Only EXT
522  msg_obj.mask = filter_configs[i].mask & uavcan::CanFrame::MaskExtID;
523  }
524  else
525  {
526  msg_obj.mode_id = CAN_MSGOBJ_RTR; // Using this configuration to disable the object
527  msg_obj.mask = uavcan::CanFrame::MaskStdID;
528  }
529 
530  LPC_CCAN_API->config_rxmsgobj(&msg_obj);
531  }
532  }
533  else
534  {
535  return -1;
536  }
537 
538  return 0;
539 }
540 
542 {
543  CriticalSectionLocker locker;
544  return std::uint64_t(error_cnt) + std::uint64_t(rx_queue.getOverflowCount());
545 }
546 
548 {
549  return NumberOfRxMessageObjects;
550 }
551 
553 {
554  return (iface_index == 0) ? this : nullptr;
555 }
556 
558 {
559  return 1;
560 }
561 
562 }
563 
564 /*
565  * C_CAN handlers
566  */
567 extern "C"
568 {
569 
570 void canRxCallback(std::uint8_t msg_obj_num)
571 {
572  using namespace uavcan_lpc11c24;
573 
574  auto msg_obj = CCAN_MSG_OBJ_T();
575  msg_obj.msgobj = msg_obj_num;
576  LPC_CCAN_API->can_receive(&msg_obj);
577 
579 
580  // CAN ID, EXT or not
581  if (msg_obj.mode_id & CAN_MSGOBJ_EXT)
582  {
583  frame.id = msg_obj.mode_id & uavcan::CanFrame::MaskExtID;
585  }
586  else
587  {
588  frame.id = msg_obj.mode_id & uavcan::CanFrame::MaskStdID;
589  }
590 
591  // RTR
592  if (msg_obj.mode_id & CAN_MSGOBJ_RTR)
593  {
595  }
596 
597  // Payload
598  frame.dlc = msg_obj.dlc;
599  uavcan::copy(msg_obj.data, msg_obj.data + msg_obj.dlc, frame.data);
600 
601  rx_queue.push(frame, last_irq_utc_timestamp);
602  had_activity = true;
603 }
604 
605 void canTxCallback(std::uint8_t msg_obj_num)
606 {
607  using namespace uavcan_lpc11c24;
608 
609  (void)msg_obj_num;
610 
611  tx_pending = false;
612  had_activity = true;
613 }
614 
616 {
617  using namespace uavcan_lpc11c24;
618 
619  // Updating the error counter
620  if ((error_info != 0) && (error_cnt < 0xFFFFFFFFUL))
621  {
622  error_cnt++;
623  }
624 
625  // Serving abort requests
626  if (tx_pending && tx_abort_on_error)
627  {
628  tx_pending = false;
629  tx_abort_on_error = false;
630 
631  // Using the first interface, because this approach seems to be compliant with the BASIC mode (just in case)
632  c_can::CAN.IF[0].CMDREQ = TxMessageObjectNumber;
633  c_can::CAN.IF[0].CMDMSK.W = c_can::IF_CMDMSK_W_WR_RD; // Clearing IF_CMDMSK_W_TXRQST
634  c_can::CAN.IF[0].MCTRL &= ~c_can::IF_MCTRL_TXRQST; // Clearing IF_MCTRL_TXRQST
635  }
636 }
637 
638 void CAN_IRQHandler();
639 
641 {
642  using namespace uavcan_lpc11c24;
643 
644  last_irq_utc_timestamp = clock::getUtcUSecFromCanInterrupt();
645 
646  LPC_CCAN_API->isr();
647 }
648 
649 }
uavcan_lpc11c24::c_can::CNTL_SIE
static constexpr std::uint32_t CNTL_SIE
Definition: c_can.hpp:114
uavcan_lpc11c24::CanDriver::getNumFilters
uavcan::uint16_t getNumFilters() const override
Definition: can.cpp:547
uavcan_lpc11c24::c_can::MsgIfaceType::W
std::uint32_t W
Definition: c_can.hpp:23
uavcan::CanFrame::MaskStdID
static const uint32_t MaskStdID
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:26
uavcan_lpc11c24::c_can::MsgIfaceType::MCTRL
std::uint32_t MCTRL
Definition: c_can.hpp:33
uavcan::CanFrame::FlagEFF
static const uint32_t FlagEFF
Extended frame format.
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:28
LPC_SYSCTL
#define LPC_SYSCTL
Definition: chip.h:181
overflow_cnt_
std::uint32_t overflow_cnt_
Definition: can.cpp:82
uavcan::uint64_t
std::uint64_t uint64_t
Definition: std.hpp:27
templates.hpp
canTxCallback
void canTxCallback(std::uint8_t msg_obj_num)
Definition: can.cpp:605
CAN_MSGOBJ_EXT
#define CAN_MSGOBJ_EXT
Definition: ccand_11xx.h:62
in_
std::uint8_t in_
Definition: can.cpp:83
uavcan_lpc11c24::clock::getMonotonic
uavcan::MonotonicTime getMonotonic()
Definition: clock.cpp:83
CCAN_MSG_OBJ::data
uint8_t data[8]
Definition: ccand_11xx.h:69
uavcan_lpc11c24::c_can::Type::STAT
std::uint32_t STAT
Definition: c_can.hpp:56
uavcan::uint32_t
std::uint32_t uint32_t
Definition: std.hpp:26
uavcan::UtcTime
Implicitly convertible to/from uavcan.Timestamp.
Definition: time.hpp:191
canErrorCallback
void canErrorCallback(std::uint32_t error_info)
Definition: can.cpp:615
CCAN_MSG_OBJ::mode_id
uint32_t mode_id
Definition: ccand_11xx.h:67
uavcan_lpc11c24::c_can::TEST_SILENT
static constexpr std::uint32_t TEST_SILENT
Definition: c_can.hpp:125
uavcan_lpc11c24::c_can::MsgIfaceType::CMDMSK
union uavcan_lpc11c24::c_can::MsgIfaceType::@168 CMDMSK
uavcan_lpc11c24::c_can::STAT_BOFF
static constexpr std::uint32_t STAT_BOFF
Definition: c_can.hpp:140
CCAN_MSG_OBJ
Definition: ccand_11xx.h:66
uavcan_lpc11c24::CanDriver::configureFilters
uavcan::int16_t configureFilters(const uavcan::CanFilterConfig *filter_configs, uavcan::uint16_t num_configs) override
Definition: can.cpp:469
uavcan_lpc11c24::CanDriver::self
static CanDriver self
Definition: platform_specific_components/lpc11c24/libuavcan/driver/include/uavcan_lpc11c24/can.hpp:21
uavcan::DurationBase< MonotonicDuration >::fromMSec
static MonotonicDuration fromMSec(int64_t ms)
Definition: time.hpp:41
uavcan_lpc11c24::CanDriver::isInBusOffState
bool isInBusOffState() const
Definition: can.cpp:356
uavcan_lpc11c24::c_can::CNTL_CCE
static constexpr std::uint32_t CNTL_CCE
Definition: c_can.hpp:111
uavcan_lpc11c24::CanDriver::hadActivity
bool hadActivity()
Definition: can.cpp:342
uavcan_lpc11c24::CanDriver::send
uavcan::int16_t send(const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags) override
Definition: can.cpp:361
canRxCallback
void canRxCallback(std::uint8_t msg_obj_num)
Definition: can.cpp:570
uavcan::CanFilterConfig
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:99
uavcan_lpc11c24::clock::getUtcUSecFromCanInterrupt
std::uint64_t getUtcUSecFromCanInterrupt()
Definition: clock.cpp:78
uavcan::CanFrame
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:24
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
canclkdiv
std::uint32_t canclkdiv
Definition: can.cpp:138
uavcan::CanFrame::id
uint32_t id
CAN ID with flags (above)
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:34
uavcan_lpc11c24::c_can::Type::CNTL
std::uint32_t CNTL
Definition: c_can.hpp:55
uavcan::MaxCanIfaces
@ MaxCanIfaces
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:19
uavcan::CanFrame::isErrorFrame
bool isErrorFrame() const
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:72
f
f
uavcan_lpc11c24::c_can::IF_MCTRL_TXRQST
static constexpr std::uint32_t IF_MCTRL_TXRQST
Definition: c_can.hpp:186
NVIC_DisableIRQ
__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
Disable External Interrupt.
Definition: core_cm0.h:512
Chip_Clock_EnablePeriphClock
STATIC INLINE void Chip_Clock_EnablePeriphClock(CHIP_SYSCTL_CLOCK_T clk)
Enable a system or peripheral clock.
Definition: clock_11xx.h:295
uavcan::uint16_t
std::uint16_t uint16_t
Definition: std.hpp:25
NVIC_EnableIRQ
__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
Enable External Interrupt.
Definition: core_cm0.h:500
uavcan::int16_t
std::int16_t int16_t
Definition: std.hpp:30
uavcan_lpc11c24::c_can::CNTL_TEST
static constexpr std::uint32_t CNTL_TEST
Definition: c_can.hpp:110
CCAN_MSG_OBJ_T
struct CCAN_MSG_OBJ CCAN_MSG_OBJ_T
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_lpc11c24::c_can::Type::BRPE
std::uint32_t BRPE
Definition: c_can.hpp:61
can.hpp
canbtr
std::uint32_t canbtr
Definition: can.cpp:139
CCAN_MSG_OBJ::msgobj
uint8_t msgobj
Definition: ccand_11xx.h:71
uavcan::uint8_t
std::uint8_t uint8_t
Definition: std.hpp:24
uavcan_lpc11c24::c_can::Type::TEST
std::uint32_t TEST
Definition: c_can.hpp:60
uavcan_lpc11c24::c_can::MsgIfaceType::CMDREQ
std::uint32_t CMDREQ
Definition: c_can.hpp:19
CCAN_MSG_OBJ::dlc
uint8_t dlc
Definition: ccand_11xx.h:70
uavcan_lpc11c24::CanDriver::hasReadyRx
bool hasReadyRx() const
Definition: can.cpp:330
uavcan::CanFilterConfig::mask
uint32_t mask
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:102
CAN_IRQn
@ CAN_IRQn
Definition: cmsis_11cxx.h:100
uavcan::CanFrame::MaskExtID
static const uint32_t MaskExtID
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:27
uavcan_lpc11c24::c_can::Type::CLKDIV
std::uint32_t CLKDIV
Definition: c_can.hpp:85
uavcan::CanSelectMasks
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:119
uavcan::CanSelectMasks::write
uint8_t write
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:122
uavcan_lpc11c24::c_can::IF_CMDMSK_W_WR_RD
static constexpr std::uint32_t IF_CMDMSK_W_WR_RD
Definition: c_can.hpp:174
uavcan_lpc11c24::c_can::Type::BT
std::uint32_t BT
Definition: c_can.hpp:58
uavcan::CanFrame::isRemoteTransmissionRequest
bool isRemoteTransmissionRequest() const
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:71
uavcan_lpc11c24::CanDriver::getIface
uavcan::ICanIface * getIface(uavcan::uint8_t iface_index) override
Definition: can.cpp:552
CAN_MSGOBJ_RTR
#define CAN_MSGOBJ_RTR
Definition: ccand_11xx.h:64
uavcan_lpc11c24::CanDriver::select
uavcan::int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
Definition: can.cpp:422
uavcan_lpc11c24::CanDriver::init
int init(uavcan::uint32_t bitrate)
Definition: can.cpp:274
len_
std::uint8_t len_
Definition: can.cpp:85
Chip_Clock_GetSystemClockRate
uint32_t Chip_Clock_GetSystemClockRate(void)
Return system clock rate.
Definition: clock_11xx.c:281
uavcan::CanFrame::data
uint8_t data[MaxDataLen]
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:35
uavcan_lpc11c24::CanDriver::getNumIfaces
uavcan::uint8_t getNumIfaces() const override
Definition: can.cpp:557
out_
std::uint8_t out_
Definition: can.cpp:84
c_can.hpp
internal.hpp
UAVCAN_LPC11C24_RX_QUEUE_LEN
#define UAVCAN_LPC11C24_RX_QUEUE_LEN
Definition: can.cpp:16
frame
uavcan::CanFrame frame
Definition: can.cpp:78
clock.hpp
uavcan::CanFrame::isExtended
bool isExtended() const
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:70
uavcan_lpc11c24::c_can::StatLec::NoError
@ NoError
LPC_CCAN_API
#define LPC_CCAN_API
Definition: ccand_11xx.h:161
uavcan_lpc11c24::CriticalSectionLocker
Definition: lpc11c24/libuavcan/driver/src/internal.hpp:27
CAN_IRQHandler
void CAN_IRQHandler()
Definition: can.cpp:640
RESET_CAN0
@ RESET_CAN0
Definition: sysctl_11xx.h:140
buf_
Item buf_[UAVCAN_LPC11C24_RX_QUEUE_LEN]
Definition: can.cpp:81
uavcan_lpc11c24::c_can::STAT_LEC_SHIFT
static constexpr std::uint32_t STAT_LEC_SHIFT
Definition: c_can.hpp:146
uavcan::CanIOFlags
uint16_t CanIOFlags
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:140
uavcan_lpc11c24::c_can::CNTL_INIT
static constexpr std::uint32_t CNTL_INIT
Definition: c_can.hpp:116
uavcan_lpc11c24
Definition: platform_specific_components/lpc11c24/libuavcan/driver/include/uavcan_lpc11c24/can.hpp:9
chip.h
uavcan_lpc11c24::c_can::Type::IF
MsgIfaceType IF[2]
Definition: c_can.hpp:65
uavcan_lpc11c24::c_can::StatLec::Unused
@ Unused
uavcan::MonotonicTime
Definition: time.hpp:184
uavcan_lpc11c24::CanDriver::hasEmptyTx
bool hasEmptyTx() const
Definition: can.cpp:336
uavcan::ICanIface
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:147
uavcan::copy
UAVCAN_EXPORT OutputIt copy(InputIt first, InputIt last, OutputIt result)
Definition: templates.hpp:238
uavcan::CanFilterConfig::id
uint32_t id
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:101
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_lpc11c24::c_can::CAN
volatile Type & CAN
Definition: c_can.hpp:104
CCAN_CALLBACKS
Definition: ccand_11xx.h:137
uavcan_lpc11c24::CanDriver::receive
uavcan::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
Definition: can.cpp:405
uavcan_lpc11c24::CanDriver::getRxQueueOverflowCount
uavcan::uint32_t getRxQueueOverflowCount() const
Definition: can.cpp:350
uavcan_lpc11c24::c_can::STAT_LEC_MASK
static constexpr std::uint32_t STAT_LEC_MASK
Definition: c_can.hpp:145
uavcan_lpc11c24::CanDriver::getErrorCount
uavcan::uint64_t getErrorCount() const override
Definition: can.cpp:541
uavcan::CanFrame::FlagRTR
static const uint32_t FlagRTR
Remote transmission request.
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:29
uavcan_lpc11c24::CanDriver::detectBitRate
static uavcan::uint32_t detectBitRate(void(*idle_callback)()=nullptr)
Definition: can.cpp:171


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