APM:Libraries
CAN.h
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14 */
15 
16 /*
17  * Many thanks to members of the UAVCAN project:
18  * Pavel Kirienko <pavel.kirienko@gmail.com>
19  * Ilia Sheremet <illia.sheremet@gmail.com>
20  *
21  * license info can be found in the uavcan submodule located:
22  * modules/uavcan/LICENSE
23  * modules/uavcan/libuavcan_drivers/linux/include/uavcan_linux/socketcan.hpp
24  */
25 
26 
27 #pragma once
28 
29 #include "AP_HAL_Linux.h"
30 #include <AP_HAL/CAN.h>
31 
32 #include <linux/can.h>
33 
34 #include <string>
35 #include <queue>
36 #include <memory>
37 #include <map>
38 #include <unordered_set>
39 #include <poll.h>
40 
41 namespace Linux {
42 
43 enum class SocketCanError
44 {
47  TxTimeout
48 };
49 
50 #define CAN_MAX_POLL_ITERATIONS_COUNT 100
51 #define CAN_MAX_INIT_TRIES_COUNT 100
52 #define CAN_FILTER_NUMBER 8
53 
54 class CAN: public AP_HAL::CAN {
55 public:
56  CAN(int socket_fd=0)
57  : _fd(socket_fd)
58  , _frames_in_socket_tx_queue(0)
59  , _max_frames_in_socket_tx_queue(2)
60  { }
61  ~CAN() { }
62 
63  bool begin(uint32_t bitrate) override;
64 
65  void end() override;
66 
67  void reset() override;
68 
69  bool is_initialized() override;
70 
71  int32_t tx_pending() override;
72 
73  int32_t available() override;
74 
75  static int openSocket(const std::string& iface_name);
76 
77  int getFileDescriptor() const { return _fd; }
78 
79  int16_t send(const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline,
80  uavcan::CanIOFlags flags) override;
81 
82  int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
83  uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags) override;
84 
85  bool hasReadyTx() const;
86 
87  bool hasReadyRx() const;
88 
89  void poll(bool read, bool write);
90 
91  int16_t configureFilters(const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs) override;
92 
93  uint16_t getNumFilters() const override;
94 
95  uint64_t getErrorCount() const override;
96 
97 
98 private:
99  struct TxItem
100  {
101  uavcan::CanFrame frame;
102  uavcan::MonotonicTime deadline;
103  uavcan::CanIOFlags flags = 0;
104  std::uint64_t order = 0;
105 
106  TxItem(const uavcan::CanFrame& arg_frame, uavcan::MonotonicTime arg_deadline,
107  uavcan::CanIOFlags arg_flags, std::uint64_t arg_order)
108  : frame(arg_frame)
109  , deadline(arg_deadline)
110  , flags(arg_flags)
111  , order(arg_order)
112  { }
113 
114  bool operator<(const TxItem& rhs) const
115  {
116  if (frame.priorityLowerThan(rhs.frame)) {
117  return true;
118  }
119  if (frame.priorityHigherThan(rhs.frame)) {
120  return false;
121  }
122  return order > rhs.order;
123  }
124  };
125 
126  struct RxItem
127  {
128  uavcan::CanFrame frame;
129  uavcan::MonotonicTime ts_mono;
130  uavcan::UtcTime ts_utc;
131  uavcan::CanIOFlags flags;
132 
134  : flags(0)
135  { }
136  };
137 
138  void _pollWrite();
139 
140  void _pollRead();
141 
142  int _write(const uavcan::CanFrame& frame) const;
143 
144  int _read(uavcan::CanFrame& frame, uavcan::UtcTime& ts_utc, bool& loopback) const;
145 
146  void _incrementNumFramesInSocketTxQueue();
147 
148  void _confirmSentFrame();
149 
150  bool _wasInPendingLoopbackSet(const uavcan::CanFrame& frame);
151 
152  bool _checkHWFilters(const can_frame& frame) const;
153 
154  void _registerError(SocketCanError e) { _errors[e]++; }
155 
156  uint32_t _bitrate;
157 
159 
160  int _fd;
161 
165 
166  std::map<SocketCanError, uint64_t> _errors;
167  std::priority_queue<TxItem> _tx_queue;
168  std::queue<RxItem> _rx_queue;
169  std::unordered_multiset<uint32_t> _pending_loopback_ids;
170  std::vector<can_filter> _hw_filters_container;
171 };
172 
173 class CANManager: public AP_HAL::CANManager, public uavcan::ICanDriver {
174 public:
175  static CANManager *from(AP_HAL::CANManager *can)
176  {
177  return static_cast<CANManager*>(can);
178  }
179 
180  CANManager() : AP_HAL::CANManager(this) { _ifaces.reserve(uavcan::MaxCanIfaces); }
182 
183  void _timer_tick();
184 
185  //These methods belong to AP_HAL::CANManager
186 
187  virtual bool begin(uint32_t bitrate, uint8_t can_number) override;
188 
189  virtual void initialized(bool val);
190  virtual bool is_initialized();
191 
193 
194  virtual AP_UAVCAN *get_UAVCAN(void) override;
195  virtual void set_UAVCAN(AP_UAVCAN *uavcan) override;
196 
197  //These methods belong to ICanDriver (which is an ancestor of AP_HAL::CANManager)
198 
199  virtual CAN* getIface(uint8_t iface_index) override;
200 
201  virtual uint8_t getNumIfaces() const override { return _ifaces.size(); }
202 
203  virtual int16_t select(uavcan::CanSelectMasks& inout_masks,
204  const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override;
205 
206  int init(uint8_t can_number);
207 
208  int addIface(const std::string& iface_name);
209 
210 private:
211  class IfaceWrapper : public CAN
212  {
213  bool _down = false;
214 
215  public:
216  IfaceWrapper(int fd) : CAN(fd) { }
217 
218  void updateDownStatusFromPollResult(const pollfd& pfd);
219 
220  bool isDown() const { return _down; }
221  };
222 
224 
225  std::vector<std::unique_ptr<IfaceWrapper>> _ifaces;
226 };
227 
228 }
std::vector< can_filter > _hw_filters_container
Definition: CAN.h:170
int _fd
Definition: CAN.h:160
CAN(int socket_fd=0)
Definition: CAN.h:56
std::map< SocketCanError, uint64_t > _errors
Definition: CAN.h:166
bool _initialized
Definition: CAN.h:158
void _registerError(SocketCanError e)
Definition: CAN.h:154
std::unordered_multiset< uint32_t > _pending_loopback_ids
Definition: CAN.h:169
uint32_t _bitrate
Definition: CAN.h:156
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
uavcan::CanFrame frame
Definition: CAN.h:101
void reset()
std::uint64_t order
Definition: CAN.h:104
uavcan::MonotonicTime ts_mono
Definition: CAN.h:129
std::vector< std::unique_ptr< IfaceWrapper > > _ifaces
Definition: CAN.h:225
int _write(int fd, const char *buf, size_t cnt)
Definition: syscalls.c:191
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
bool _initialized
Definition: CAN.h:223
uavcan::MonotonicTime deadline
Definition: CAN.h:102
unsigned _frames_in_socket_tx_queue
Definition: CAN.h:163
static CANManager * from(AP_HAL::CANManager *can)
Definition: CAN.h:175
Definition: CAN.h:54
uint64_t _tx_frame_counter
Definition: CAN.h:164
~CAN()
Definition: CAN.h:61
bool operator<(const TxItem &rhs) const
Definition: CAN.h:114
AP_UAVCAN * p_uavcan
Definition: CAN.h:192
TxItem(const uavcan::CanFrame &arg_frame, uavcan::MonotonicTime arg_deadline, uavcan::CanIOFlags arg_flags, std::uint64_t arg_order)
Definition: CAN.h:106
uavcan::CanIOFlags flags
Definition: CAN.h:131
SocketCanError
Definition: CAN.h:43
std::priority_queue< TxItem > _tx_queue
Definition: CAN.h:167
uavcan::CanFrame frame
Definition: CAN.h:128
uavcan::UtcTime ts_utc
Definition: CAN.h:130
void init()
Generic board initialization function.
Definition: system.cpp:136
int getFileDescriptor() const
Definition: CAN.h:77
virtual uint8_t getNumIfaces() const override
Definition: CAN.h:201
const unsigned _max_frames_in_socket_tx_queue
Definition: CAN.h:162
int _read(int fd, char *buf, size_t cnt)
Definition: system.cpp:126
std::queue< RxItem > _rx_queue
Definition: CAN.h:168