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