can.hpp 13 KB

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