PX4 Firmware
PX4 Autopilot Software http://px4.io
can.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014, 2018 Pavel Kirienko <pavel.kirienko@gmail.com>
3  * Kinetis Port Author David Sidrane <david_s5@nscdg.com>
4  */
5 
6 #pragma once
7 
10 #include <uavcan/driver/can.hpp>
12 
13 namespace uavcan_kinetis
14 {
15 /**
16  * Driver error codes.
17  * These values can be returned from driver functions negated.
18  */
19 //static const uavcan::int16_t ErrUnknown = 1000; ///< Reserved for future use
20 static const uavcan::int16_t ErrNotImplemented = 1001; ///< Feature not implemented
21 static const uavcan::int16_t ErrInvalidBitRate = 1002; ///< Bit rate not supported
22 static const uavcan::int16_t ErrLogic = 1003; ///< Internal logic error
23 static const uavcan::int16_t ErrUnsupportedFrame = 1004; ///< Frame not supported (e.g. RTR, CAN FD, etc)
24 static const uavcan::int16_t ErrMcrLPMAckNotSet = 1005; ///< MCR_LPMACK bit of the MCR register is not 1
25 static const uavcan::int16_t ErrMcrLPMAckNotCleared = 1006; ///< MCR_LPMACK bit of the MCR register is not 0
26 static const uavcan::int16_t ErrMcrFRZACKAckNotSet = 1007; ///< MCR_FRZACK bit of the MCR register is not 1
27 static const uavcan::int16_t ErrMcrFRZACKAckNotCleared = 1008; ///< MCR_FRZACK bit of the MCR register is not 0
28 static const uavcan::int16_t ErrBitRateNotDetected = 1009; ///< Auto bit rate detection could not be finished
29 static const uavcan::int16_t ErrFilterNumConfigs = 1010; ///< Number of filters is more than supported
30 static const uavcan::int16_t ErrMcrSOFTRSTNotCleared = 1011; ///< MCR_SOFTRST bit of the MCR register is not 0
31 /**
32  * RX queue item.
33  * The application shall not use this directly.
34  */
35 struct CanRxItem {
36  uavcan::uint64_t utc_usec;
37  uavcan::CanFrame frame;
38  uavcan::CanIOFlags flags;
40  : utc_usec(0),
41  flags(0)
42  {
43  }
44 };
45 
46 /**
47  * Single CAN iface.
48  * The application shall not use this directly.
49  */
50 class CanIface : public uavcan::ICanIface
51  , uavcan::Noncopyable
52 {
53  const uavcan::uint32_t FIFO_IFLAG1 = flexcan::CAN_FIFO_NE | flexcan::CAN_FIFO_WARN | flexcan::CAN_FIFO_OV;
54  class RxQueue
55  {
56  CanRxItem *const buf_;
57  const uavcan::uint8_t capacity_;
58  uavcan::uint8_t in_;
59  uavcan::uint8_t out_;
60  uavcan::uint8_t len_;
61  uavcan::uint32_t overflow_cnt_;
62 
63  void registerOverflow();
64 
65  public:
66  RxQueue(CanRxItem *buf, uavcan::uint8_t capacity)
67  : buf_(buf),
68  capacity_(capacity),
69  in_(0),
70  out_(0),
71  len_(0),
72  overflow_cnt_(0)
73  {
74  }
75 
76  void push(const uavcan::CanFrame &frame, const uint64_t &utc_usec, uavcan::CanIOFlags flags);
77  void pop(uavcan::CanFrame &out_frame, uavcan::uint64_t &out_utc_usec, uavcan::CanIOFlags &out_flags);
78 
79  void reset();
80  unsigned getLength() const
81  {
82  return len_;
83  }
84 
85  uavcan::uint32_t getOverflowCount() const
86  {
87  return overflow_cnt_;
88  }
89  };
90 
91  struct Timings {
92  uavcan::uint8_t prescaler;
93  uavcan::uint8_t rjw;
94  uavcan::uint8_t pseg1;
95  uavcan::uint8_t pseg2;
96  uavcan::uint8_t propseg;
97 
99  : prescaler(0),
100  rjw(0),
101  pseg1(0),
102  pseg2(0),
103  propseg(0)
104  {
105  }
106  };
107 
108  struct TxItem {
109  uavcan::MonotonicTime deadline;
110  uavcan::CanFrame frame;
111  enum {free = 0, busy, abort } pending;
112  bool loopback;
114 
116  : pending(free),
117  loopback(false),
118  abort_on_error(false)
119  {
120  }
121  };
122 
123  enum { NumTxMesgBuffers = 6 };
124  enum { NumFilters = 16 };
125 
126  uavcan::uint8_t MaxMB;
127 
130  uavcan::uint64_t error_cnt_;
131  uavcan::uint64_t fifo_warn_cnt_;
132  uavcan::uint32_t pending_aborts_;
133  uavcan::uint32_t served_aborts_cnt_;
135  TxItem pending_tx_[NumTxMesgBuffers];
136  uavcan::uint8_t peak_tx_mailbox_index_;
137  const uavcan::uint8_t self_index_;
139 
140  int computeTimings(uavcan::uint32_t target_bitrate, Timings &out_timings);
141 
142  virtual uavcan::int16_t send(const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline,
143  uavcan::CanIOFlags flags);
144 
145  virtual uavcan::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic,
146  uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags);
147 
148  virtual uavcan::int16_t configureFilters(const uavcan::CanFilterConfig *filter_configs,
149  uavcan::uint16_t num_configs);
150 
151  virtual uavcan::uint16_t getNumFilters() const
152  {
153  return NumFilters;
154  }
155 
156  void handleTxMailboxInterrupt(uavcan::uint8_t mailbox_index, bool txok, uavcan::uint64_t utc_usec);
157 
158  bool waitMCRChange(uavcan::uint32_t mask, bool target_state);
159  void setMCR(uavcan::uint32_t mask, bool target_state);
160 
161  bool setEnable(bool enable_true);
162  uavcan::int16_t doReset(Timings timings);
163  bool waitFreezeAckChange(bool target_state);
164  void setFreeze(bool freeze_true);
165 
166 public:
167  enum { MaxRxQueueCapacity = 254 };
168 
171  SilentMode
172  };
173 
174  CanIface(flexcan::CanType *can, BusEvent &update_event, uavcan::uint8_t self_index,
175  CanRxItem *rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
176  : MaxMB(flexcan::HWMaxMB),
177  rx_queue_(rx_queue_buffer, rx_queue_capacity),
178  can_(can),
179  error_cnt_(0),
180  fifo_warn_cnt_(0),
181  pending_aborts_(0),
182  served_aborts_cnt_(0),
183  update_event_(update_event),
184  peak_tx_mailbox_index_(0),
185  self_index_(self_index),
186  had_activity_(false)
187  {
188  UAVCAN_ASSERT(self_index_ < UAVCAN_KINETIS_NUM_IFACES);
189  }
190 
191  /**
192  * Initializes the hardware CAN controller.
193  * Assumes:
194  * - Iface clock is enabled
195  * - Iface has been resetted via RCC
196  * - Caller will configure NVIC by itself
197  */
198  int init(const uavcan::uint32_t bitrate, const OperatingMode mode);
199 
200  void handleTxInterrupt(uavcan::uint32_t tx_iflags, uavcan::uint64_t utc_usec);
201  void handleRxInterrupt(uavcan::uint32_t rx_iflags, uavcan::uint64_t utc_usec);
202 
203  /**
204  * This method is used to count errors and abort transmission on error if necessary.
205  * This functionality used to be implemented in the SCE interrupt handler, but that approach was
206  * generating too much processing overhead, especially on disconnected interfaces.
207  *
208  * Should be called from RX ISR, TX ISR, and select(); interrupts must be enabled.
209  */
210  void pollErrorFlagsFromISR();
211 
212  void discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time);
213 
214  bool canAcceptNewTxFrame(const uavcan::CanFrame &frame) const;
215  bool isRxBufferEmpty() const;
216 
217  /**
218  * Number of RX frames lost due to queue overflow.
219  * This is an atomic read, it doesn't require a critical section.
220  */
221  uavcan::uint32_t getRxQueueOverflowCount() const
222  {
223  return rx_queue_.getOverflowCount();
224  }
225 
226  /**
227  * Total number of hardware failures and other kinds of errors (e.g. queue overruns).
228  * May increase continuously if the interface is not connected to the bus.
229  */
230  virtual uavcan::uint64_t getErrorCount() const;
231 
232  /**
233  * Number of times the driver exercised library's requirement to abort transmission on first error.
234  * This is an atomic read, it doesn't require a critical section.
235  * See @ref uavcan::CanIOFlagAbortOnError.
236  */
237  uavcan::uint32_t getVoluntaryTxAbortCount() const
238  {
239  return served_aborts_cnt_;
240  }
241 
242  /**
243  * Returns the number of frames pending in the RX queue.
244  * This is intended for debug use only.
245  */
246  unsigned getRxQueueLength() const;
247 
248  /**
249  * Whether this iface had at least one successful IO since the previous call of this method.
250  * This is designed for use with iface activity LEDs.
251  */
252  bool hadActivity();
253 
254  /**
255  * Peak number of TX mailboxes used concurrently since initialization.
256  * Range is [1, 3].
257  * Value of 3 suggests that priority inversion could be taking place.
258  */
259  uavcan::uint8_t getPeakNumTxMailboxesUsed() const
260  {
261  return uavcan::uint8_t(peak_tx_mailbox_index_ + 1);
262  }
263 };
264 
265 /**
266  * CAN driver, incorporates all available CAN ifaces.
267  * Please avoid direct use, prefer @ref CanInitHelper instead.
268  */
269 class CanDriver : public uavcan::ICanDriver
270  , uavcan::Noncopyable
271 {
274 #if UAVCAN_KINETIS_NUM_IFACES > 1
275  CanIface if1_;
276 #endif
277 
278  virtual uavcan::int16_t select(uavcan::CanSelectMasks &inout_masks,
279  const uavcan::CanFrame * (&pending_tx)[uavcan::MaxCanIfaces],
280  uavcan::MonotonicTime blocking_deadline);
281 
282  static void initOnce();
283 
284 public:
285  template <unsigned RxQueueCapacity>
286  CanDriver(CanRxItem(&rx_queue_storage)[UAVCAN_KINETIS_NUM_IFACES][RxQueueCapacity])
287  : update_event_(*this),
288  if0_(flexcan::Can[0], update_event_, 0, rx_queue_storage[0], RxQueueCapacity)
289 #if UAVCAN_KINETIS_NUM_IFACES > 1
290  , if1_(flexcan::Can[1], update_event_, 1, rx_queue_storage[1], RxQueueCapacity)
291 #endif
292  {
293  uavcan::StaticAssert < (RxQueueCapacity <= CanIface::MaxRxQueueCapacity) >::check();
294  }
295 
296  /**
297  * This function returns select masks indicating which interfaces are available for read/write.
298  */
299  uavcan::CanSelectMasks makeSelectMasks(const uavcan::CanFrame * (&pending_tx)[uavcan::MaxCanIfaces]) const;
300 
301  /**
302  * Whether there's at least one interface where receive() would return a frame.
303  */
304  bool hasReadableInterfaces() const;
305 
306  /**
307  * Returns zero if OK.
308  * Returns negative value if failed (e.g. invalid bitrate).
309  */
310  int init(const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode);
311 
312  virtual CanIface *getIface(uavcan::uint8_t iface_index);
313 
314  virtual uavcan::uint8_t getNumIfaces() const
315  {
316  return UAVCAN_KINETIS_NUM_IFACES;
317  }
318 
319  /**
320  * Whether at least one iface had at least one successful IO since previous call of this method.
321  * This is designed for use with iface activity LEDs.
322  */
323  bool hadActivity();
324 
325  BusEvent &updateEvent() { return update_event_; }
326 };
327 
328 /**
329  * Helper class.
330  * Normally only this class should be used by the application.
331  * 145 usec per Extended CAN frame @ 1 Mbps, e.g. 32 RX slots * 145 usec --> 4.6 msec before RX queue overruns.
332  */
333 template <unsigned RxQueueCapacity = 128>
335 {
336  CanRxItem queue_storage_[UAVCAN_KINETIS_NUM_IFACES][RxQueueCapacity];
337 
338 public:
339  enum { BitRateAutoDetect = 0 };
340 
342 
344  driver(queue_storage_)
345  {
346  }
347 
348  /**
349  * This overload simply configures the provided bitrate.
350  * Auto bit rate detection will not be performed.
351  * Bitrate value must be positive.
352  * @return Negative value on error; non-negative on success. Refer to constants Err*.
353  */
354  int init(uavcan::uint32_t bitrate)
355  {
356  return driver.init(bitrate, CanIface::NormalMode);
357  }
358 
359  /**
360  * This function can either initialize the driver at a fixed bit rate, or it can perform
361  * automatic bit rate detection. For theory please refer to the CiA application note #801.
362  *
363  * @param delay_callable A callable entity that suspends execution for strictly more than one second.
364  * The callable entity will be invoked without arguments.
365  * @ref getRecommendedListeningDelay().
366  *
367  * @param inout_bitrate Fixed bit rate or zero. Zero invokes the bit rate detection process.
368  * If auto detection was used, the function will update the argument
369  * with established bit rate. In case of an error the value will be undefined.
370  *
371  * @return Negative value on error; non-negative on success. Refer to constants Err*.
372  */
373  template <typename DelayCallable>
374  int init(DelayCallable delay_callable, uavcan::uint32_t &inout_bitrate = BitRateAutoDetect)
375  {
376  if (inout_bitrate > 0) {
377  return driver.init(inout_bitrate, CanIface::NormalMode);
378 
379  } else {
380  static const uavcan::uint32_t StandardBitRates[] = {
381  1000000,
382  500000,
383  250000,
384  125000
385  };
386 
387  for (uavcan::uint8_t br = 0; br < sizeof(StandardBitRates) / sizeof(StandardBitRates[0]); br++) {
388  inout_bitrate = StandardBitRates[br];
389 
390  const int res = driver.init(inout_bitrate, CanIface::SilentMode);
391 
392  delay_callable();
393 
394  if (res >= 0) {
395  for (uavcan::uint8_t iface = 0; iface < driver.getNumIfaces(); iface++) {
396  if (!driver.getIface(iface)->isRxBufferEmpty()) {
397  // Re-initializing in normal mode
398  return driver.init(inout_bitrate, CanIface::NormalMode);
399  }
400  }
401  }
402  }
403 
404  return -ErrBitRateNotDetected;
405  }
406  }
407 
408  /**
409  * Use this value for listening delay during automatic bit rate detection.
410  */
411  static uavcan::MonotonicDuration getRecommendedListeningDelay()
412  {
413  return uavcan::MonotonicDuration::fromMSec(1050);
414  }
415 };
416 
417 }
int init(const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode)
Returns zero if OK.
int init(DelayCallable delay_callable, uavcan::uint32_t &inout_bitrate=BitRateAutoDetect)
This function can either initialize the driver at a fixed bit rate, or it can perform automatic bit r...
Definition: can.hpp:374
virtual uavcan::uint8_t getNumIfaces() const
Definition: can.hpp:314
CanIface(flexcan::CanType *can, BusEvent &update_event, uavcan::uint8_t self_index, CanRxItem *rx_queue_buffer, uavcan::uint8_t rx_queue_capacity)
Definition: can.hpp:174
static const uavcan::int16_t ErrMcrFRZACKAckNotSet
MCR_FRZACK bit of the MCR register is not 1.
Definition: can.hpp:26
unsigned getLength() const
Definition: can.hpp:80
int init(uavcan::uint32_t bitrate)
This overload simply configures the provided bitrate.
Definition: can.hpp:354
void * send(void *data)
uavcan::uint8_t getPeakNumTxMailboxesUsed() const
Peak number of TX mailboxes used concurrently since initialization.
Definition: can.hpp:259
static const uavcan::int16_t ErrNotImplemented
Driver error codes.
Definition: can.hpp:20
uavcan::uint32_t served_aborts_cnt_
Definition: can.hpp:133
int reset(enum LPS22HB_BUS busid)
Reset the driver.
static uavcan::MonotonicDuration getRecommendedListeningDelay()
Use this value for listening delay during automatic bit rate detection.
Definition: can.hpp:411
constexpr unsigned long CAN_FIFO_NE
Definition: flexcan.hpp:519
uavcan::uint32_t overflow_cnt_
Definition: can.hpp:61
uavcan::MonotonicTime deadline
Definition: can.hpp:109
uavcan::uint8_t MaxMB
Definition: can.hpp:126
uavcan::uint8_t prescaler
Definition: can.hpp:92
RX queue item.
Definition: can.hpp:35
RxQueue(CanRxItem *buf, uavcan::uint8_t capacity)
Definition: can.hpp:66
flexcan::CanType *const can_
Definition: can.hpp:129
CAN driver, incorporates all available CAN ifaces.
Definition: can.hpp:269
void init()
Activates/configures the hardware registers.
CanRxItem *const buf_
Definition: can.hpp:56
uavcan::uint64_t fifo_warn_cnt_
Definition: can.hpp:131
uavcan::uint8_t peak_tx_mailbox_index_
Definition: can.hpp:136
CanDriver(CanRxItem(&rx_queue_storage)[UAVCAN_KINETIS_NUM_IFACES][RxQueueCapacity])
Definition: can.hpp:286
static const uavcan::int16_t ErrMcrSOFTRSTNotCleared
MCR_SOFTRST bit of the MCR register is not 0.
Definition: can.hpp:30
Single CAN iface.
Definition: can.hpp:50
virtual CanIface * getIface(uavcan::uint8_t iface_index)
uavcan::CanIOFlags flags
Definition: can.hpp:38
BusEvent & update_event_
Definition: can.hpp:134
const uavcan::uint8_t self_index_
Definition: can.hpp:137
uavcan::uint32_t pending_aborts_
Definition: can.hpp:132
static const uavcan::int16_t ErrBitRateNotDetected
Auto bit rate detection could not be finished.
Definition: can.hpp:28
CanType *const Can[UAVCAN_KINETIS_NUM_IFACES]
CANx register sets.
Definition: flexcan.hpp:198
const uavcan::uint8_t capacity_
Definition: can.hpp:57
static const uavcan::int16_t ErrMcrLPMAckNotSet
MCR_LPMACK bit of the MCR register is not 1.
Definition: can.hpp:24
uavcan::uint8_t propseg
Definition: can.hpp:96
static const uavcan::int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc)
Definition: can.hpp:23
static const uavcan::int16_t ErrMcrFRZACKAckNotCleared
MCR_FRZACK bit of the MCR register is not 0.
Definition: can.hpp:27
uavcan::CanFrame frame
Definition: can.hpp:37
uavcan::CanFrame frame
Definition: can.hpp:110
All bus events are reported as POLLIN.
Definition: thread.hpp:29
uavcan::uint32_t getRxQueueOverflowCount() const
Number of RX frames lost due to queue overflow.
Definition: can.hpp:221
BusEvent update_event_
Definition: can.hpp:272
static const uavcan::int16_t ErrInvalidBitRate
Bit rate not supported.
Definition: can.hpp:21
constexpr unsigned long CAN_FIFO_WARN
Definition: flexcan.hpp:521
static const uavcan::int16_t ErrFilterNumConfigs
Number of filters is more than supported.
Definition: can.hpp:29
uavcan::uint32_t getOverflowCount() const
Definition: can.hpp:85
uavcan::uint64_t utc_usec
Definition: can.hpp:36
static const uavcan::int16_t ErrMcrLPMAckNotCleared
MCR_LPMACK bit of the MCR register is not 0.
Definition: can.hpp:25
BusEvent & updateEvent()
Definition: can.hpp:325
constexpr unsigned long CAN_FIFO_OV
Definition: flexcan.hpp:523
mode
Definition: vtol_type.h:76
uavcan::uint32_t getVoluntaryTxAbortCount() const
Number of times the driver exercised library&#39;s requirement to abort transmission on first error...
Definition: can.hpp:237
virtual uavcan::uint16_t getNumFilters() const
Definition: can.hpp:151
uavcan::uint64_t error_cnt_
Definition: can.hpp:130
static const uavcan::int16_t ErrLogic
Internal logic error.
Definition: can.hpp:22