APM:Libraries
CAN.cpp
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/libuavcan_drivers/linux/include/uavcan_linux/socketcan.hpp
23  */
24 
25 #include <AP_HAL/AP_HAL.h>
26 #include <AP_HAL/system.h>
27 
29 
30 #if HAL_WITH_UAVCAN
31 
32 #include "CAN.h"
33 
34 #include <AP_UAVCAN/AP_UAVCAN.h>
35 
36 #include <unistd.h>
37 #include <fcntl.h>
38 
39 #include <sys/socket.h>
40 #include <sys/ioctl.h>
41 #include <net/if.h>
42 #include <linux/can/raw.h>
43 
44 extern const AP_HAL::HAL& hal;
45 
46 using namespace Linux;
47 
48 uavcan::MonotonicTime getMonotonic()
49 {
50  return uavcan::MonotonicTime::fromUSec(AP_HAL::micros64());
51 }
52 
53 static can_frame makeSocketCanFrame(const uavcan::CanFrame& uavcan_frame)
54 {
55  can_frame sockcan_frame { uavcan_frame.id& uavcan::CanFrame::MaskExtID, uavcan_frame.dlc, { } };
56  std::copy(uavcan_frame.data, uavcan_frame.data + uavcan_frame.dlc, sockcan_frame.data);
57  if (uavcan_frame.isExtended()) {
58  sockcan_frame.can_id |= CAN_EFF_FLAG;
59  }
60  if (uavcan_frame.isErrorFrame()) {
61  sockcan_frame.can_id |= CAN_ERR_FLAG;
62  }
63  if (uavcan_frame.isRemoteTransmissionRequest()) {
64  sockcan_frame.can_id |= CAN_RTR_FLAG;
65  }
66  return sockcan_frame;
67 }
68 
69 static uavcan::CanFrame makeUavcanFrame(const can_frame& sockcan_frame)
70 {
71  uavcan::CanFrame uavcan_frame(sockcan_frame.can_id & CAN_EFF_MASK, sockcan_frame.data, sockcan_frame.can_dlc);
72  if (sockcan_frame.can_id & CAN_EFF_FLAG) {
73  uavcan_frame.id |= uavcan::CanFrame::FlagEFF;
74  }
75  if (sockcan_frame.can_id & CAN_ERR_FLAG) {
76  uavcan_frame.id |= uavcan::CanFrame::FlagERR;
77  }
78  if (sockcan_frame.can_id & CAN_RTR_FLAG) {
79  uavcan_frame.id |= uavcan::CanFrame::FlagRTR;
80  }
81  return uavcan_frame;
82 }
83 
84 bool CAN::begin(uint32_t bitrate)
85 {
86  if (_initialized) return _initialized;
87  // TODO: Add possibility change bitrate
89  if (_fd > 0) {
90  _bitrate = bitrate;
91  _initialized = true;
92  } else {
93  _initialized = false;
94  }
95  return _initialized;
96 }
97 
98 void CAN::reset()
99 {
100  if (_initialized && _bitrate != 0) {
101  close(_fd);
102  begin(_bitrate);
103  }
104 }
105 
106 void CAN::end()
107 {
108  _initialized = false;
109  close(_fd);
110 }
111 
112 bool CAN::is_initialized()
113 {
114  return _initialized;
115 }
116 
117 int32_t CAN::tx_pending()
118 {
119  if (_initialized) {
120  return _tx_queue.size();
121  } else {
122  return -1;
123  }
124 }
125 
126 int32_t CAN::available()
127 {
128  if (_initialized) {
129  return _rx_queue.size();
130  } else {
131  return -1;
132  }
133 }
134 
135 int CAN::openSocket(const std::string& iface_name)
136 {
137  errno = 0;
138 
139  int s = socket(PF_CAN, SOCK_RAW, CAN_RAW);
140  if (s < 0) {
141  return s;
142  }
143 
144  std::shared_ptr<void> defer(&s, [](int* fd) { if (*fd >= 0) close(*fd); });
145  const int ret = s;
146 
147  // Detect the iface index
148  auto ifr = ifreq();
149  if (iface_name.length() >= IFNAMSIZ) {
150  errno = ENAMETOOLONG;
151  return -1;
152  }
153  std::strncpy(ifr.ifr_name, iface_name.c_str(), iface_name.length());
154  if (ioctl(s, SIOCGIFINDEX, &ifr) < 0 || ifr.ifr_ifindex < 0) {
155  return -1;
156  }
157 
158  // Bind to the specified CAN iface
159  {
160  auto addr = sockaddr_can();
161  addr.can_family = AF_CAN;
162  addr.can_ifindex = ifr.ifr_ifindex;
163  if (bind(s, reinterpret_cast<sockaddr*>(&addr), sizeof(addr)) < 0) {
164  return -1;
165  }
166  }
167 
168  // Configure
169  {
170  const int on = 1;
171  // Timestamping
172  if (setsockopt(s, SOL_SOCKET, SO_TIMESTAMP, &on, sizeof(on)) < 0) {
173  return -1;
174  }
175  // Socket loopback
176  if (setsockopt(s, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &on, sizeof(on)) < 0) {
177  return -1;
178  }
179  // Non-blocking
180  if (fcntl(s, F_SETFL, O_NONBLOCK) < 0) {
181  return -1;
182  }
183  }
184 
185  // Validate the resulting socket
186  {
187  int socket_error = 0;
188  socklen_t errlen = sizeof(socket_error);
189  getsockopt(s, SOL_SOCKET, SO_ERROR, reinterpret_cast<void*>(&socket_error), &errlen);
190  if (socket_error != 0) {
191  errno = socket_error;
192  return -1;
193  }
194  }
195  s = -1;
196  return ret;
197 }
198 
199 int16_t CAN::send(const uavcan::CanFrame& frame, const uavcan::MonotonicTime tx_deadline,
200  const uavcan::CanIOFlags flags)
201 {
202  _tx_queue.emplace(frame, tx_deadline, flags, _tx_frame_counter);
204  _pollRead(); // Read poll is necessary because it can release the pending TX flag
205  _pollWrite();
206  return 1;
207 }
208 
209 int16_t CAN::receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
210  uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags)
211 {
212  if (_rx_queue.empty()) {
213  _pollRead(); // This allows to use the socket not calling poll() explicitly.
214  if (_rx_queue.empty()) {
215  return 0;
216  }
217  }
218  {
219  const RxItem& rx = _rx_queue.front();
220  out_frame = rx.frame;
221  out_ts_monotonic = rx.ts_mono;
222  out_ts_utc = rx.ts_utc;
223  out_flags = rx.flags;
224  }
225  _rx_queue.pop();
226  return 1;
227 }
228 
229 bool CAN::hasReadyTx() const
230 {
232 }
233 
234 bool CAN::hasReadyRx() const
235 {
236  return !_rx_queue.empty();
237 }
238 
239 void CAN::poll(bool read, bool write)
240 {
241  if (read) {
242  _pollRead(); // Read poll must be executed first because it may decrement _frames_in_socket_tx_queue
243  }
244  if (write) {
245  _pollWrite();
246  }
247 }
248 
249 int16_t CAN::configureFilters(const uavcan::CanFilterConfig* const filter_configs,
250  const std::uint16_t num_configs)
251 {
252  if (filter_configs == nullptr) {
253  return -1;
254  }
255  _hw_filters_container.clear();
256  _hw_filters_container.resize(num_configs);
257 
258  for (unsigned i = 0; i < num_configs; i++) {
259  const uavcan::CanFilterConfig& fc = filter_configs[i];
260  _hw_filters_container[i].can_id = fc.id & uavcan::CanFrame::MaskExtID;
261  _hw_filters_container[i].can_mask = fc.mask & uavcan::CanFrame::MaskExtID;
262  if (fc.id & uavcan::CanFrame::FlagEFF) {
263  _hw_filters_container[i].can_id |= CAN_EFF_FLAG;
264  }
265  if (fc.id & uavcan::CanFrame::FlagRTR) {
266  _hw_filters_container[i].can_id |= CAN_RTR_FLAG;
267  }
268  if (fc.mask & uavcan::CanFrame::FlagEFF) {
269  _hw_filters_container[i].can_mask |= CAN_EFF_FLAG;
270  }
271  if (fc.mask & uavcan::CanFrame::FlagRTR) {
272  _hw_filters_container[i].can_mask |= CAN_RTR_FLAG;
273  }
274  }
275 
276  return 0;
277 }
278 
283 static constexpr unsigned NumFilters = CAN_FILTER_NUMBER;
284 uint16_t CAN::getNumFilters() const { return NumFilters; }
285 
286 uint64_t CAN::getErrorCount() const
287 {
288  uint64_t ec = 0;
289  for (auto& kv : _errors) { ec += kv.second; }
290  return ec;
291 }
292 
293 void CAN::_pollWrite()
294 {
295  while (hasReadyTx()) {
296  const TxItem tx = _tx_queue.top();
297 
298  if (tx.deadline >= getMonotonic()) {
299  const int res = _write(tx.frame);
300  if (res == 1) { // Transmitted successfully
302  if (tx.flags & uavcan::CanIOFlagLoopback) {
303  _pending_loopback_ids.insert(tx.frame.id);
304  }
305  } else if (res == 0) { // Not transmitted, nor is it an error
306  break; // Leaving the loop, the frame remains enqueued for the next retry
307  } else { // Transmission error
309  }
310  } else {
312  }
313 
314  // Removing the frame from the queue even if transmission failed
315  _tx_queue.pop();
316  }
317 }
318 
319 void CAN::_pollRead()
320 {
321  uint8_t iterations_count = 0;
322  while (iterations_count < CAN_MAX_POLL_ITERATIONS_COUNT)
323  {
324  iterations_count++;
325  RxItem rx;
326  rx.ts_mono = getMonotonic(); // Monotonic timestamp is not required to be precise (unlike UTC)
327  bool loopback = false;
328  const int res = _read(rx.frame, rx.ts_utc, loopback);
329  if (res == 1) {
330  bool accept = true;
331  if (loopback) { // We receive loopback for all CAN frames
333  rx.flags |= uavcan::CanIOFlagLoopback;
334  accept = _wasInPendingLoopbackSet(rx.frame);
335  }
336  if (accept) {
337  _rx_queue.push(rx);
338  }
339  } else if (res == 0) {
340  break;
341  } else {
343  break;
344  }
345  }
346 }
347 
348 int CAN::_write(const uavcan::CanFrame& frame) const
349 {
350  errno = 0;
351 
352  const can_frame sockcan_frame = makeSocketCanFrame(frame);
353 
354  const int res = write(_fd, &sockcan_frame, sizeof(sockcan_frame));
355  if (res <= 0) {
356  if (errno == ENOBUFS || errno == EAGAIN) { // Writing is not possible atm, not an error
357  return 0;
358  }
359  return res;
360  }
361  if (res != sizeof(sockcan_frame)) {
362  return -1;
363  }
364  return 1;
365 }
366 
367 
368 int CAN::_read(uavcan::CanFrame& frame, uavcan::UtcTime& ts_utc, bool& loopback) const
369 {
370  auto iov = iovec();
371  auto sockcan_frame = can_frame();
372  iov.iov_base = &sockcan_frame;
373  iov.iov_len = sizeof(sockcan_frame);
374  union {
375  uint8_t data[CMSG_SPACE(sizeof(::timeval))];
376  struct cmsghdr align;
377  } control;
378 
379  auto msg = msghdr();
380  msg.msg_iov = &iov;
381  msg.msg_iovlen = 1;
382  msg.msg_control = control.data;
383  msg.msg_controllen = sizeof(control.data);
384 
385  const int res = recvmsg(_fd, &msg, MSG_DONTWAIT);
386  if (res <= 0) {
387  return (res < 0 && errno == EWOULDBLOCK) ? 0 : res;
388  }
389  /*
390  * Flags
391  */
392  loopback = (msg.msg_flags & static_cast<int>(MSG_CONFIRM)) != 0;
393 
394  if (!loopback && !_checkHWFilters(sockcan_frame)) {
395  return 0;
396  }
397 
398  frame = makeUavcanFrame(sockcan_frame);
399  /*
400  * Timestamp
401  */
402  const cmsghdr* const cmsg = CMSG_FIRSTHDR(&msg);
403  if (cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SO_TIMESTAMP) {
404  auto tv = timeval();
405  std::memcpy(&tv, CMSG_DATA(cmsg), sizeof(tv)); // Copy to avoid alignment problems
406  ts_utc = uavcan::UtcTime::fromUSec(std::uint64_t(tv.tv_sec) * 1000000ULL + tv.tv_usec);
407  } else {
408  return -1;
409  }
410  return 1;
411 }
412 
414 {
416 }
417 
419 {
420  if (_frames_in_socket_tx_queue > 0) {
422  }
423 }
424 
425 bool CAN::_wasInPendingLoopbackSet(const uavcan::CanFrame& frame)
426 {
427  if (_pending_loopback_ids.count(frame.id) > 0) {
428  _pending_loopback_ids.erase(frame.id);
429  return true;
430  }
431  return false;
432 }
433 
434 bool CAN::_checkHWFilters(const can_frame& frame) const
435 {
436  if (!_hw_filters_container.empty()) {
437  for (auto& f : _hw_filters_container) {
438  if (((frame.can_id & f.can_mask) ^ f.can_id) == 0) {
439  return true;
440  }
441  }
442  return false;
443  } else {
444  return true;
445  }
446 }
447 
449 {
450  if (!_down&& (pfd.revents & POLLERR)) {
451  int error = 0;
452  socklen_t errlen = sizeof(error);
453  getsockopt(pfd.fd, SOL_SOCKET, SO_ERROR, reinterpret_cast<void*>(&error), &errlen);
454 
455  _down= error == ENETDOWN || error == ENODEV;
456 
457  hal.console->printf("Iface %d is dead; error %d", this->getFileDescriptor(), error);
458  }
459 }
460 
462 {
463  if (!_initialized) return;
464 
465  if (p_uavcan != nullptr) {
466  p_uavcan->do_cyclic();
467  } else {
468  hal.console->printf("p_uavcan is nullptr");
469  }
470 }
471 
472 bool CANManager::begin(uint32_t bitrate, uint8_t can_number)
473 {
474  if (init(can_number) >= 0) {
475  _initialized = true;
476  }
477  return _initialized;
478 }
479 
481 {
482  return _initialized;
483 }
484 
485 void CANManager::initialized(bool val)
486 {
487  _initialized = val;
488 }
489 
491 {
492  return p_uavcan;
493 }
494 
495 void CANManager::set_UAVCAN(AP_UAVCAN *uavcan)
496 {
497  p_uavcan = uavcan;
498 }
499 
500 CAN* CANManager::getIface(uint8_t iface_index)
501 {
502  return (iface_index >= _ifaces.size()) ? nullptr : _ifaces[iface_index].get();
503 }
504 
505 int CANManager::init(uint8_t can_number)
506 {
507  int res = -1;
508  char iface_name[16];
509  sprintf(iface_name, "can%u", can_number);
510 
511  res = addIface(iface_name);
512  if (res < 0) {
513  hal.console->printf("CANManager: init %s failed\n", iface_name);
514  }
515 
516  return res;
517 }
518 
519 int16_t CANManager::select(uavcan::CanSelectMasks& inout_masks,
520  const uavcan::CanFrame* (&)[uavcan::MaxCanIfaces],
521  uavcan::MonotonicTime blocking_deadline)
522 {
523  // Detecting whether we need to block at all
524  bool need_block = (inout_masks.write == 0); // Write queue is infinite
525 
526  for (unsigned i = 0; need_block && (i < _ifaces.size()); i++) {
527  const bool need_read = inout_masks.read & (1 << i);
528  if (need_read && _ifaces[i]->hasReadyRx()) {
529  need_block = false;
530  }
531  }
532 
533  if (need_block) {
534  // Poll FD set setup
535  pollfd pollfds[uavcan::MaxCanIfaces] = {};
536  unsigned num_pollfds = 0;
537  IfaceWrapper* pollfd_index_to_iface[uavcan::MaxCanIfaces] = {};
538 
539  for (unsigned i = 0; i < _ifaces.size(); i++) {
540  if (!_ifaces[i]->isDown()) {
541  pollfds[num_pollfds].fd = _ifaces[i]->getFileDescriptor();
542  pollfds[num_pollfds].events = POLLIN;
543  if (_ifaces[i]->hasReadyTx() || (inout_masks.write & (1U << i))) {
544  pollfds[num_pollfds].events |= POLLOUT;
545  }
546  pollfd_index_to_iface[num_pollfds] = _ifaces[i].get();
547  num_pollfds++;
548  }
549  }
550 
551  if (num_pollfds == 0) {
552  return 0;
553  }
554 
555  // Timeout conversion
556  const std::int64_t timeout_usec = (blocking_deadline - getMonotonic()).toUSec();
557  auto ts = timespec();
558  if (timeout_usec > 0) {
559  ts.tv_sec = timeout_usec / 1000000LL;
560  ts.tv_nsec = (timeout_usec % 1000000LL) * 1000;
561  }
562 
563  // Blocking here
564  const int res = ppoll(pollfds, num_pollfds, &ts, nullptr);
565  if (res < 0) {
566  return res;
567  }
568 
569  // Handling poll output
570  for (unsigned i = 0; i < num_pollfds; i++) {
571  pollfd_index_to_iface[i]->updateDownStatusFromPollResult(pollfds[i]);
572 
573  const bool poll_read = pollfds[i].revents & POLLIN;
574  const bool poll_write = pollfds[i].revents & POLLOUT;
575  pollfd_index_to_iface[i]->poll(poll_read, poll_write);
576  }
577  }
578 
579  // Writing the output masks
580  inout_masks = uavcan::CanSelectMasks();
581  for (unsigned i = 0; i < _ifaces.size(); i++) {
582  if (!_ifaces[i]->isDown()) {
583  inout_masks.write |= std::uint8_t(1U << i); // Always ready to write if not down
584  }
585  if (_ifaces[i]->hasReadyRx()) {
586  inout_masks.read |= std::uint8_t(1U << i); // Readability depends only on RX buf, even if down
587  }
588  }
589 
590  // Return value is irrelevant as long as it's non-negative
591  return _ifaces.size();
592 }
593 
594 int CANManager::addIface(const std::string& iface_name)
595 {
596  if (_ifaces.size() >= uavcan::MaxCanIfaces) {
597  return -1;
598  }
599 
600  // Open the socket
601  const int fd = CAN::openSocket(iface_name);
602  if (fd < 0) {
603  return fd;
604  }
605 
606  // Construct the iface - upon successful construction the iface will take ownership of the fd.
607  _ifaces.emplace_back(new IfaceWrapper(fd));
608 
609  hal.console->printf("New iface '%s' fd %d\n", iface_name.c_str(), fd);
610 
611  return _ifaces.size() - 1;
612 }
613 
614 #endif
bool is_initialized() override
virtual CAN * getIface(uint8_t iface_index) override
std::vector< can_filter > _hw_filters_container
Definition: CAN.h:170
int _fd
Definition: CAN.h:160
static int openSocket(const std::string &iface_name)
std::map< SocketCanError, uint64_t > _errors
Definition: CAN.h:166
void _incrementNumFramesInSocketTxQueue()
bool _initialized
Definition: CAN.h:158
void _registerError(SocketCanError e)
Definition: CAN.h:154
#define on
Definition: Config.h:51
bool hasReadyRx() const
AP_HAL::UARTDriver * console
Definition: HAL.h:110
std::unordered_multiset< uint32_t > _pending_loopback_ids
Definition: CAN.h:169
uint32_t _bitrate
Definition: CAN.h:156
void _confirmSentFrame()
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
void _pollWrite()
virtual int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
int _write(const uavcan::CanFrame &frame) const
void _pollRead()
uavcan::MonotonicTime getMonotonic()
virtual void set_UAVCAN(AP_UAVCAN *uavcan) override
void reset() override
int addIface(const std::string &iface_name)
void end() override
virtual bool begin(uint32_t bitrate, uint8_t can_number) override
int init(uint8_t can_number)
uint16_t getNumFilters() const override
virtual void initialized(bool val)
virtual AP_UAVCAN * get_UAVCAN(void) override
bool _checkHWFilters(const can_frame &frame) const
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual bool is_initialized()
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
#define constexpr
Definition: AP_HAL_Macros.h:16
int32_t available() override
int16_t send(const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags) override
void poll(bool read, bool write)
#define f(i)
bool begin(uint32_t bitrate) override
unsigned _frames_in_socket_tx_queue
Definition: CAN.h:163
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
Definition: CAN.h:54
uint64_t _tx_frame_counter
Definition: CAN.h:164
uint64_t micros64()
Definition: system.cpp:162
#define HAL_BOARD_CAN_IFACE_NAME
Definition: linux.h:405
int16_t configureFilters(const uavcan::CanFilterConfig *filter_configs, uint16_t num_configs) override
std::priority_queue< TxItem > _tx_queue
Definition: CAN.h:167
bool _wasInPendingLoopbackSet(const uavcan::CanFrame &frame)
void updateDownStatusFromPollResult(const pollfd &pfd)
void init()
Generic board initialization function.
Definition: system.cpp:136
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int getFileDescriptor() const
Definition: CAN.h:77
#define error(fmt, args ...)
const unsigned _max_frames_in_socket_tx_queue
Definition: CAN.h:162
int _read(uavcan::CanFrame &frame, uavcan::UtcTime &ts_utc, bool &loopback) const
int32_t tx_pending() override
std::queue< RxItem > _rx_queue
Definition: CAN.h:168
#define CAN_MAX_POLL_ITERATIONS_COUNT
Definition: CAN.h:50
uint64_t getErrorCount() const override
bool hasReadyTx() const
#define CAN_FILTER_NUMBER
Definition: CAN.h:52