AP_UAVCAN_SLCAN.h 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #if AP_UAVCAN_SLCAN_ENABLED
  4. #include <AP_UAVCAN/AP_UAVCAN.h>
  5. #include "AP_HAL/utility/RingBuffer.h"
  6. #define SLCAN_BUFFER_SIZE 200
  7. #define SLCAN_RX_QUEUE_SIZE 64
  8. #define SLCAN_DRIVER_INDEX 2
  9. class SLCANRouter;
  10. namespace SLCAN {
  11. /**
  12. * Driver error codes.
  13. * These values can be returned from driver functions negated.
  14. */
  15. static const int16_t ErrUnknown = 1000; ///< Reserved for future use
  16. static const int16_t ErrNotImplemented = 1001; ///< Feature not implemented
  17. static const int16_t ErrInvalidBitRate = 1002; ///< Bit rate not supported
  18. static const int16_t ErrLogic = 1003; ///< Internal logic error
  19. static const int16_t ErrUnsupportedFrame = 1004; ///< Frame not supported (e.g. RTR, CAN FD, etc)
  20. static const int16_t ErrMsrInakNotSet = 1005; ///< INAK bit of the MSR register is not 1
  21. static const int16_t ErrMsrInakNotCleared = 1006; ///< INAK bit of the MSR register is not 0
  22. static const int16_t ErrBitRateNotDetected = 1007; ///< Auto bit rate detection could not be finished
  23. static const int16_t ErrFilterNumConfigs = 1008; ///< Auto bit rate detection could not be finished
  24. class CANManager;
  25. /**
  26. * RX queue item.
  27. * The application shall not use this directly.
  28. */
  29. struct CanRxItem {
  30. uint64_t utc_usec;
  31. uavcan::CanFrame frame;
  32. uavcan::CanIOFlags flags;
  33. CanRxItem() :
  34. utc_usec(0), flags(0)
  35. {
  36. }
  37. };
  38. class CAN: public AP_HAL::CAN {
  39. friend class CANManager;
  40. friend class ::SLCANRouter;
  41. struct TxItem {
  42. uavcan::MonotonicTime deadline;
  43. uavcan::CanFrame frame;
  44. bool pending;
  45. bool loopback;
  46. bool abort_on_error;
  47. TxItem() :
  48. pending(false), loopback(false), abort_on_error(false)
  49. {
  50. }
  51. };
  52. enum {
  53. NumTxMailboxes = 3
  54. };
  55. enum {
  56. NumFilters = 14
  57. };
  58. uint32_t bitrate_;
  59. virtual int16_t send(const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline,
  60. uavcan::CanIOFlags flags) override;
  61. virtual int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
  62. uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags) override;
  63. int16_t reportFrame(const uavcan::CanFrame& frame, bool loopback, uint64_t timestamp_usec);
  64. virtual int16_t configureFilters(const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs) override
  65. {
  66. //TODO: possibly check at the first serial read
  67. return 0;
  68. }
  69. virtual uint16_t getNumFilters() const override
  70. {
  71. return NumFilters;
  72. }
  73. /**
  74. * Total number of hardware failures and other kinds of errors (e.g. queue overruns).
  75. * May increase continuously if the interface is not connected to the bus.
  76. */
  77. virtual uint64_t getErrorCount() const override
  78. {
  79. return 0;
  80. }
  81. const char* processCommand(char* cmd);
  82. bool push_Frame(uavcan::CanFrame &frame);
  83. bool handle_FrameRTRStd(const char* cmd);
  84. bool handle_FrameRTRExt(const char* cmd);
  85. bool handle_FrameDataStd(const char* cmd);
  86. bool handle_FrameDataExt(const char* cmd);
  87. void reader();
  88. inline void addByte(const uint8_t byte);
  89. bool initialized_;
  90. bool _port_initialised;
  91. char buf_[SLCAN_BUFFER_SIZE + 1];
  92. int16_t pos_ = 0;
  93. AP_HAL::UARTDriver *_port = nullptr;
  94. ObjectBuffer<CanRxItem> rx_queue_;
  95. uint8_t self_index_;
  96. HAL_Semaphore rx_sem_;
  97. unsigned _pending_frame_size = 0;
  98. const uint32_t _serial_lock_key = 0x53494442;
  99. bool _close = true;
  100. public:
  101. CAN(uint8_t self_index, uint8_t rx_queue_capacity):
  102. self_index_(self_index), rx_queue_(rx_queue_capacity), _port_initialised(false)
  103. {
  104. UAVCAN_ASSERT(self_index_ < CAN_STM32_NUM_IFACES);
  105. }
  106. enum {
  107. MaxRxQueueCapacity = 254
  108. };
  109. enum OperatingMode {
  110. NormalMode, SilentMode
  111. };
  112. int init(const uint32_t bitrate, const OperatingMode mode, AP_HAL::UARTDriver* port);
  113. bool begin(uint32_t bitrate) override
  114. {
  115. if (init(bitrate, OperatingMode::NormalMode, nullptr) == 0) {
  116. bitrate_ = bitrate;
  117. initialized_ = true;
  118. }
  119. else {
  120. initialized_ = false;
  121. }
  122. return initialized_;
  123. }
  124. void end() override
  125. {
  126. }
  127. void reset() override;
  128. int32_t tx_pending() override
  129. {
  130. return _port->tx_pending() ? 0:-1;
  131. }
  132. int32_t available() override
  133. {
  134. return _port->available() ? 0:-1;
  135. }
  136. bool is_initialized() override
  137. {
  138. return initialized_;
  139. }
  140. bool closed()
  141. {
  142. return _close;
  143. }
  144. bool pending_frame_sent();
  145. bool isRxBufferEmpty(void);
  146. bool canAcceptNewTxFrame() const;
  147. };
  148. class CANManager: public AP_HAL::CANManager, public uavcan::ICanDriver {
  149. bool initialized_;
  150. CAN driver_;
  151. uint8_t _ifaces_num = 1;
  152. virtual int16_t select(uavcan::CanSelectMasks& inout_masks,
  153. const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override;
  154. uavcan::CanSelectMasks makeSelectMasks(const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces]);
  155. thread_t *_irq_handler_ctx = nullptr;
  156. public:
  157. CANManager()
  158. : AP_HAL::CANManager(this), initialized_(false), driver_(SLCAN_DRIVER_INDEX, SLCAN_RX_QUEUE_SIZE)
  159. { }
  160. /**
  161. * Whether at least one iface had at least one successful IO since previous call of this method.
  162. * This is designed for use with iface activity LEDs.
  163. */
  164. //bool hadActivity();
  165. static CANManager *from(AP_HAL::CANManager *can)
  166. {
  167. return static_cast<CANManager*>(can);
  168. }
  169. bool begin(uint32_t bitrate, uint8_t can_number) override;
  170. /*
  171. Test if CAN manager is ready and initialized
  172. return false - CAN manager not initialized
  173. true - CAN manager is initialized
  174. */
  175. bool is_initialized() override;
  176. void initialized(bool val) override;
  177. virtual CAN* getIface(uint8_t iface_index) override
  178. {
  179. return &driver_;
  180. }
  181. virtual uint8_t getNumIfaces() const override
  182. {
  183. return _ifaces_num;
  184. }
  185. void reader_trampoline(void);
  186. };
  187. }
  188. #include <AP_HAL_ChibiOS/CANSerialRouter.h>
  189. #endif // AP_UAVCAN_SLCAN_ENABLED