CAN.h 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * Many thanks to members of the UAVCAN project:
  15. * Pavel Kirienko <pavel.kirienko@gmail.com>
  16. * Ilia Sheremet <illia.sheremet@gmail.com>
  17. *
  18. * license info can be found in the uavcan submodule located:
  19. * modules/uavcan/LICENSE
  20. * modules/uavcan/libuavcan_drivers/linux/include/uavcan_linux/socketcan.hpp
  21. */
  22. #pragma once
  23. #include "AP_HAL_Linux.h"
  24. #include <AP_HAL/CAN.h>
  25. #include <linux/can.h>
  26. #include <string>
  27. #include <queue>
  28. #include <memory>
  29. #include <map>
  30. #include <unordered_set>
  31. #include <poll.h>
  32. namespace Linux {
  33. enum class SocketCanError
  34. {
  35. SocketReadFailure,
  36. SocketWriteFailure,
  37. TxTimeout
  38. };
  39. #define CAN_MAX_POLL_ITERATIONS_COUNT 100
  40. #define CAN_MAX_INIT_TRIES_COUNT 100
  41. #define CAN_FILTER_NUMBER 8
  42. class CAN: public AP_HAL::CAN {
  43. public:
  44. CAN(int socket_fd=0)
  45. : _fd(socket_fd)
  46. , _frames_in_socket_tx_queue(0)
  47. , _max_frames_in_socket_tx_queue(2)
  48. { }
  49. ~CAN() { }
  50. bool begin(uint32_t bitrate) override;
  51. void end() override;
  52. void reset() override;
  53. bool is_initialized() override;
  54. int32_t tx_pending() override;
  55. int32_t available() override;
  56. static int openSocket(const std::string& iface_name);
  57. int getFileDescriptor() const { return _fd; }
  58. int16_t send(const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline,
  59. uavcan::CanIOFlags flags) override;
  60. int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
  61. uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags) override;
  62. bool hasReadyTx() const;
  63. bool hasReadyRx() const;
  64. void poll(bool read, bool write);
  65. int16_t configureFilters(const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs) override;
  66. uint16_t getNumFilters() const override;
  67. uint64_t getErrorCount() const override;
  68. private:
  69. struct TxItem
  70. {
  71. uavcan::CanFrame frame;
  72. uavcan::MonotonicTime deadline;
  73. uavcan::CanIOFlags flags = 0;
  74. std::uint64_t order = 0;
  75. TxItem(const uavcan::CanFrame& arg_frame, uavcan::MonotonicTime arg_deadline,
  76. uavcan::CanIOFlags arg_flags, std::uint64_t arg_order)
  77. : frame(arg_frame)
  78. , deadline(arg_deadline)
  79. , flags(arg_flags)
  80. , order(arg_order)
  81. { }
  82. bool operator<(const TxItem& rhs) const
  83. {
  84. if (frame.priorityLowerThan(rhs.frame)) {
  85. return true;
  86. }
  87. if (frame.priorityHigherThan(rhs.frame)) {
  88. return false;
  89. }
  90. return order > rhs.order;
  91. }
  92. };
  93. struct RxItem
  94. {
  95. uavcan::CanFrame frame;
  96. uavcan::MonotonicTime ts_mono;
  97. uavcan::UtcTime ts_utc;
  98. uavcan::CanIOFlags flags;
  99. RxItem()
  100. : flags(0)
  101. { }
  102. };
  103. void _pollWrite();
  104. void _pollRead();
  105. int _write(const uavcan::CanFrame& frame) const;
  106. int _read(uavcan::CanFrame& frame, uavcan::UtcTime& ts_utc, bool& loopback) const;
  107. void _incrementNumFramesInSocketTxQueue();
  108. void _confirmSentFrame();
  109. bool _wasInPendingLoopbackSet(const uavcan::CanFrame& frame);
  110. bool _checkHWFilters(const can_frame& frame) const;
  111. void _registerError(SocketCanError e) { _errors[e]++; }
  112. uint32_t _bitrate;
  113. bool _initialized;
  114. int _fd;
  115. const unsigned _max_frames_in_socket_tx_queue;
  116. unsigned _frames_in_socket_tx_queue;
  117. uint64_t _tx_frame_counter;
  118. std::map<SocketCanError, uint64_t> _errors;
  119. std::priority_queue<TxItem> _tx_queue;
  120. std::queue<RxItem> _rx_queue;
  121. std::unordered_multiset<uint32_t> _pending_loopback_ids;
  122. std::vector<can_filter> _hw_filters_container;
  123. };
  124. class CANManager: public AP_HAL::CANManager, public uavcan::ICanDriver {
  125. public:
  126. static CANManager *from(AP_HAL::CANManager *can)
  127. {
  128. return static_cast<CANManager*>(can);
  129. }
  130. CANManager() : AP_HAL::CANManager(this) { _ifaces.reserve(uavcan::MaxCanIfaces); }
  131. ~CANManager() { }
  132. //These methods belong to AP_HAL::CANManager
  133. virtual bool begin(uint32_t bitrate, uint8_t can_number) override;
  134. virtual void initialized(bool val) override;
  135. virtual bool is_initialized() override;
  136. //These methods belong to ICanDriver
  137. virtual CAN* getIface(uint8_t iface_index) override;
  138. virtual uint8_t getNumIfaces() const override { return _ifaces.size(); }
  139. virtual int16_t select(uavcan::CanSelectMasks& inout_masks,
  140. const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override;
  141. int init(uint8_t can_number);
  142. int addIface(const std::string& iface_name);
  143. private:
  144. class IfaceWrapper : public CAN
  145. {
  146. bool _down = false;
  147. public:
  148. IfaceWrapper(int fd) : CAN(fd) { }
  149. void updateDownStatusFromPollResult(const pollfd& pfd);
  150. bool isDown() const { return _down; }
  151. };
  152. bool _initialized;
  153. std::vector<std::unique_ptr<IfaceWrapper>> _ifaces;
  154. };
  155. }