13 #include <unordered_set> 18 #include <sys/socket.h> 19 #include <sys/ioctl.h> 21 #include <linux/can.h> 22 #include <linux/can/raw.h> 64 ::can_frame sockcan_frame = ::can_frame();
66 sockcan_frame.can_dlc = uavcan_frame.
dlc;
74 sockcan_frame.can_id |= CAN_ERR_FLAG;
78 sockcan_frame.can_id |= CAN_RTR_FLAG;
90 if (sockcan_frame.can_id & CAN_ERR_FLAG)
94 if (sockcan_frame.can_id & CAN_RTR_FLAG)
111 , deadline(arg_deadline)
126 return order > rhs.
order;
146 unsigned frames_in_socket_tx_queue_ = 0;
150 std::map<SocketCanError, std::uint64_t>
errors_;
162 assert(frames_in_socket_tx_queue_ < max_frames_in_socket_tx_queue_);
163 frames_in_socket_tx_queue_++;
168 if (frames_in_socket_tx_queue_ > 0)
170 frames_in_socket_tx_queue_--;
180 if (pending_loopback_ids_.count(frame.
id) > 0)
182 (void)pending_loopback_ids_.erase(frame.
id);
192 const ::can_frame sockcan_frame = makeSocketCanFrame(frame);
194 const int res = ::write(fd_, &sockcan_frame,
sizeof(sockcan_frame));
197 if (errno == ENOBUFS || errno == EAGAIN)
203 if (res !=
sizeof(sockcan_frame))
219 auto iov = ::iovec();
220 auto sockcan_frame = ::can_frame();
221 iov.iov_base = &sockcan_frame;
222 iov.iov_len =
sizeof(sockcan_frame);
224 static constexpr
size_t ControlSize =
sizeof(cmsghdr) +
sizeof(::timeval);
225 using ControlStorage =
typename std::aligned_storage<ControlSize>::type;
226 ControlStorage control_storage;
227 auto control =
reinterpret_cast<std::uint8_t *
>(&control_storage);
228 std::fill(control, control + ControlSize, 0x00);
230 auto msg = ::msghdr();
233 msg.msg_control = control;
234 msg.msg_controllen = ControlSize;
236 const int res = ::recvmsg(fd_, &msg, MSG_DONTWAIT);
239 return (res < 0 && errno == EWOULDBLOCK) ? 0 : res;
244 loopback = (msg.msg_flags &
static_cast<int>(MSG_CONFIRM)) != 0;
246 if (!loopback && !checkHWFilters(sockcan_frame))
251 frame = makeUavcanFrame(sockcan_frame);
255 const ::cmsghdr*
const cmsg = CMSG_FIRSTHDR(&msg);
256 assert(cmsg !=
nullptr);
257 if (cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type ==
SO_TIMESTAMP)
259 auto tv = ::timeval();
260 (void)std::memcpy(&tv, CMSG_DATA(cmsg),
sizeof(tv));
261 assert(tv.tv_sec >= 0 && tv.tv_usec >= 0);
276 const TxItem tx = tx_queue_.top();
280 const int res = write(tx.
frame);
283 incrementNumFramesInSocketTxQueue();
286 (void)pending_loopback_ids_.insert(tx.
frame.
id);
314 bool loopback =
false;
315 const int res = read(rx.
frame, rx.
ts_utc, loopback);
324 accept = wasInPendingLoopbackSet(rx.
frame);
349 if (!hw_filters_container_.empty())
351 for (
auto&
f : hw_filters_container_)
353 if (((frame.can_id &
f.can_mask) ^
f.can_id) == 0)
375 , max_frames_in_socket_tx_queue_(max_frames_in_socket_tx_queue)
385 UAVCAN_TRACE(
"SocketCAN",
"SocketCanIface: Closing fd %d", fd_);
395 tx_queue_.emplace(frame, tx_deadline, flags, tx_frame_counter_);
409 if (rx_queue_.empty())
412 if (rx_queue_.empty())
418 const RxItem& rx = rx_queue_.front();
419 out_frame = rx.
frame;
422 out_flags = rx.
flags;
433 void poll(
bool read,
bool write)
448 return !tx_queue_.empty() && (frames_in_socket_tx_queue_ < max_frames_in_socket_tx_queue_);
454 if (filter_configs ==
nullptr)
459 hw_filters_container_.clear();
460 hw_filters_container_.resize(num_configs);
462 for (
unsigned i = 0; i < num_configs; i++)
473 hw_filters_container_[i].can_id |= CAN_RTR_FLAG;
481 hw_filters_container_[i].can_mask |= CAN_RTR_FLAG;
492 static constexpr
unsigned NumFilters = 8;
502 for (
auto& kv : errors_) { ec += kv.second; }
509 const decltype(errors_) &
getErrors()
const {
return errors_; }
522 const int s = ::socket(PF_CAN, SOCK_RAW,
CAN_RAW);
532 RaiiCloser(
int filedesc) : fd_(filedesc)
540 UAVCAN_TRACE(
"SocketCAN",
"RaiiCloser: Closing fd %d", fd_);
544 void disarm() { fd_ = -1; }
548 auto ifr = ::ifreq();
549 if (iface_name.length() >= IFNAMSIZ)
551 errno = ENAMETOOLONG;
554 (void)std::strncpy(ifr.ifr_name, iface_name.c_str(), iface_name.length());
555 if (::ioctl(s, SIOCGIFINDEX, &ifr) < 0 || ifr.ifr_ifindex < 0)
562 auto addr = ::sockaddr_can();
564 addr.can_ifindex = ifr.ifr_ifindex;
565 if (::bind(s, reinterpret_cast<sockaddr*>(&addr),
sizeof(addr)) < 0)
575 if (::setsockopt(s, SOL_SOCKET,
SO_TIMESTAMP, &on,
sizeof(on)) < 0)
585 if (::fcntl(s, F_SETFL, O_NONBLOCK) < 0)
593 int socket_error = 0;
594 ::socklen_t errlen =
sizeof(socket_error);
595 (void)::getsockopt(s, SOL_SOCKET, SO_ERROR, reinterpret_cast<void*>(&socket_error), &errlen);
596 if (socket_error != 0)
598 errno = socket_error;
603 raii_closer.disarm();
629 assert(pfd.fd == this->getFileDescriptor());
630 if (!down_ && (pfd.revents & POLLERR))
633 ::socklen_t errlen =
sizeof(
error);
634 (void)::getsockopt(pfd.fd, SOL_SOCKET, SO_ERROR, reinterpret_cast<void*>(&error), &errlen);
636 down_ = error == ENETDOWN || error == ENODEV;
638 UAVCAN_TRACE(
"SocketCAN",
"Iface %d is dead; error %d", this->getFileDescriptor(), error);
646 std::vector<std::unique_ptr<IfaceWrapper>>
ifaces_;
669 bool need_block = (inout_masks.
write == 0);
670 for (
unsigned i = 0; need_block && (i < ifaces_.size()); i++)
672 const bool need_read = inout_masks.
read & (1 << i);
673 if (need_read && ifaces_[i]->hasReadyRx())
683 unsigned num_pollfds = 0;
686 for (
unsigned i = 0; i < ifaces_.size(); i++)
688 if (!ifaces_[i]->isDown())
691 pollfds[num_pollfds].events = POLLIN;
692 if (ifaces_[i]->hasReadyTx() || (inout_masks.
write & (1U << i)))
694 pollfds[num_pollfds].events |= POLLOUT;
696 pollfd_index_to_iface[num_pollfds] = ifaces_[i].get();
702 if (num_pollfds == 0)
709 auto ts = ::timespec();
710 if (timeout_usec > 0)
712 ts.tv_sec = timeout_usec / 1000000LL;
713 ts.tv_nsec = (timeout_usec % 1000000LL) * 1000;
717 const int res = ::ppoll(pollfds, num_pollfds, &ts,
nullptr);
724 for (
unsigned i = 0; i < num_pollfds; i++)
728 const bool poll_read = pollfds[i].revents & POLLIN;
729 const bool poll_write = pollfds[i].revents & POLLOUT;
730 pollfd_index_to_iface[i]->
poll(poll_read, poll_write);
736 for (
unsigned i = 0; i < ifaces_.size(); i++)
738 if (!ifaces_[i]->isDown())
742 if (ifaces_[i]->hasReadyRx())
749 return ifaces_.size();
754 return (iface_index >= ifaces_.size()) ?
nullptr : ifaces_[iface_index].
get();
790 UAVCAN_TRACE(
"SocketCAN",
"New iface '%s' fd %d", iface_name.c_str(), fd);
792 return ifaces_.size() - 1;
800 return ifaces_.at(iface_index)->isDown();
bool checkHWFilters(const ::can_frame &frame) const
uint32_t id
CAN ID with flags (above)
bool isRemoteTransmissionRequest() const
std::queue< RxItem > rx_queue_
SocketCanIface(const SystemClock &clock, int socket_fd, int max_frames_in_socket_tx_queue=2)
uavcan::MonotonicTime getMonotonic() const override
std::uint8_t getNumIfaces() const override
int write(const uavcan::CanFrame &frame) const
static UtcTime fromUSec(uint64_t us)
static const uint32_t MaskExtID
static const uint32_t FlagEFF
Extended frame format.
uavcan::MonotonicTime deadline
int addIface(const std::string &iface_name)
bool isIfaceDown(std::uint8_t iface_index) const
uint8_t dlc
Data Length Code.
std::unordered_multiset< std::uint32_t > pending_loopback_ids_
static inline ::can_frame makeSocketCanFrame(const uavcan::CanFrame &uavcan_frame)
#define UAVCAN_TRACE(...)
uavcan::MonotonicTime ts_mono
IfaceWrapper(const SystemClock &clock, int fd)
std::map< SocketCanError, std::uint64_t > errors_
Implicitly convertible to/from uavcan.Timestamp.
int read(uavcan::CanFrame &frame, uavcan::UtcTime &ts_utc, bool &loopback) const
const SystemClock & clock_
UAVCAN_EXPORT OutputIt copy(InputIt first, InputIt last, OutputIt result)
virtual ~SocketCanIface()
std::priority_queue< TxItem > tx_queue_
static const uint32_t FlagRTR
Remote transmission request.
SocketCanIface * getIface(std::uint8_t iface_index) override
void registerError(SocketCanError e)
std::uint16_t getNumFilters() const override
bool operator<(const TxItem &rhs) const
static int openSocket(const std::string &iface_name)
void incrementNumFramesInSocketTxQueue()
uavcan::UtcDuration getPrivateAdjustment() const
const unsigned max_frames_in_socket_tx_queue_
std::vector< std::unique_ptr< IfaceWrapper > > ifaces_
void poll(bool read, bool write)
bool priorityHigherThan(const CanFrame &rhs) const
bool priorityLowerThan(const CanFrame &rhs) const
static uavcan::CanFrame makeUavcanFrame(const ::can_frame &sockcan_frame)
static void fill(T(&a)[Size], R value)
std::int16_t send(const uavcan::CanFrame &frame, const uavcan::MonotonicTime tx_deadline, const uavcan::CanIOFlags flags) override
static const uint32_t FlagERR
Error frame.
std::int16_t configureFilters(const uavcan::CanFilterConfig *const filter_configs, const std::uint16_t num_configs) override
bool isErrorFrame() const
bool wasInPendingLoopbackSet(const uavcan::CanFrame &frame)
int CAN_RAW_RECV_OWN_MSGS
std::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
std::vector<::can_filter > hw_filters_container_
static const CanIOFlags CanIOFlagLoopback
std::int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
std::uint64_t getErrorCount() const override
SocketCanDriver(const SystemClock &clock)
TxItem(const uavcan::CanFrame &arg_frame, uavcan::MonotonicTime arg_deadline, uavcan::CanIOFlags arg_flags, std::uint64_t arg_order)
const SystemClock & clock_
decltype(errors_) const & getErrors() const
int getFileDescriptor() const
void updateDownStatusFromPollResult(const ::pollfd &pfd)