39 #include <sys/socket.h> 42 #include <linux/can/raw.h> 46 using namespace Linux;
53 static can_frame makeSocketCanFrame(
const uavcan::CanFrame& uavcan_frame)
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;
60 if (uavcan_frame.isErrorFrame()) {
61 sockcan_frame.can_id |= CAN_ERR_FLAG;
63 if (uavcan_frame.isRemoteTransmissionRequest()) {
64 sockcan_frame.can_id |= CAN_RTR_FLAG;
69 static uavcan::CanFrame makeUavcanFrame(
const can_frame& sockcan_frame)
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;
75 if (sockcan_frame.can_id & CAN_ERR_FLAG) {
76 uavcan_frame.id |= uavcan::CanFrame::FlagERR;
78 if (sockcan_frame.can_id & CAN_RTR_FLAG) {
79 uavcan_frame.id |= uavcan::CanFrame::FlagRTR;
139 int s = socket(PF_CAN, SOCK_RAW, CAN_RAW);
144 std::shared_ptr<void> defer(&s, [](
int* fd) {
if (*fd >= 0)
close(*fd); });
149 if (iface_name.length() >= IFNAMSIZ) {
150 errno = ENAMETOOLONG;
153 std::strncpy(ifr.ifr_name, iface_name.c_str(), iface_name.length());
154 if (ioctl(s, SIOCGIFINDEX, &ifr) < 0 || ifr.ifr_ifindex < 0) {
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) {
172 if (setsockopt(s, SOL_SOCKET, SO_TIMESTAMP, &on,
sizeof(on)) < 0) {
176 if (setsockopt(s, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &on,
sizeof(on)) < 0) {
180 if (fcntl(s, F_SETFL, O_NONBLOCK) < 0) {
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;
199 int16_t
CAN::send(
const uavcan::CanFrame& frame,
const uavcan::MonotonicTime tx_deadline,
200 const uavcan::CanIOFlags flags)
209 int16_t
CAN::receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
210 uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags)
220 out_frame = rx.frame;
221 out_ts_monotonic = rx.ts_mono;
222 out_ts_utc = rx.ts_utc;
223 out_flags = rx.flags;
250 const std::uint16_t num_configs)
252 if (filter_configs ==
nullptr) {
258 for (
unsigned i = 0; i < num_configs; i++) {
259 const uavcan::CanFilterConfig& fc = filter_configs[i];
262 if (fc.id & uavcan::CanFrame::FlagEFF) {
265 if (fc.id & uavcan::CanFrame::FlagRTR) {
268 if (fc.mask & uavcan::CanFrame::FlagEFF) {
271 if (fc.mask & uavcan::CanFrame::FlagRTR) {
289 for (
auto& kv :
_errors) { ec += kv.second; }
299 const int res =
_write(tx.frame);
302 if (tx.flags & uavcan::CanIOFlagLoopback) {
305 }
else if (res == 0) {
321 uint8_t iterations_count = 0;
327 bool loopback =
false;
328 const int res =
_read(rx.frame, rx.ts_utc, loopback);
333 rx.flags |= uavcan::CanIOFlagLoopback;
339 }
else if (res == 0) {
348 int CAN::_write(
const uavcan::CanFrame& frame)
const 352 const can_frame sockcan_frame = makeSocketCanFrame(frame);
354 const int res =
write(
_fd, &sockcan_frame,
sizeof(sockcan_frame));
361 if (res !=
sizeof(sockcan_frame)) {
368 int CAN::_read(uavcan::CanFrame& frame, uavcan::UtcTime& ts_utc,
bool& loopback)
const 371 auto sockcan_frame = can_frame();
372 iov.iov_base = &sockcan_frame;
373 iov.iov_len =
sizeof(sockcan_frame);
375 uint8_t data[CMSG_SPACE(
sizeof(::timeval))];
376 struct cmsghdr align;
382 msg.msg_control = control.data;
383 msg.msg_controllen =
sizeof(control.data);
385 const int res = recvmsg(
_fd, &msg, MSG_DONTWAIT);
387 return (res < 0 &&
errno == EWOULDBLOCK) ? 0 : res;
392 loopback = (msg.msg_flags &
static_cast<int>(MSG_CONFIRM)) != 0;
398 frame = makeUavcanFrame(sockcan_frame);
402 const cmsghdr*
const cmsg = CMSG_FIRSTHDR(&msg);
403 if (cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SO_TIMESTAMP) {
405 std::memcpy(&tv, CMSG_DATA(cmsg),
sizeof(tv));
406 ts_utc = uavcan::UtcTime::fromUSec(std::uint64_t(tv.tv_sec) * 1000000ULL + tv.tv_usec);
438 if (((frame.can_id &
f.can_mask) ^
f.can_id) == 0) {
450 if (!_down&& (pfd.revents & POLLERR)) {
452 socklen_t errlen =
sizeof(
error);
453 getsockopt(pfd.fd, SOL_SOCKET, SO_ERROR, reinterpret_cast<void*>(&error), &errlen);
455 _down= error == ENETDOWN || error == ENODEV;
465 if (p_uavcan !=
nullptr) {
466 p_uavcan->do_cyclic();
474 if (
init(can_number) >= 0) {
502 return (iface_index >= _ifaces.size()) ?
nullptr : _ifaces[iface_index].
get();
509 sprintf(iface_name,
"can%u", can_number);
511 res = addIface(iface_name);
513 hal.
console->
printf(
"CANManager: init %s failed\n", iface_name);
520 const uavcan::CanFrame* (&)[uavcan::MaxCanIfaces],
521 uavcan::MonotonicTime blocking_deadline)
524 bool need_block = (inout_masks.write == 0);
526 for (
unsigned i = 0; need_block && (i < _ifaces.size()); i++) {
527 const bool need_read = inout_masks.read & (1 << i);
535 pollfd pollfds[uavcan::MaxCanIfaces] = {};
536 unsigned num_pollfds = 0;
537 IfaceWrapper* pollfd_index_to_iface[uavcan::MaxCanIfaces] = {};
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;
546 pollfd_index_to_iface[num_pollfds] = _ifaces[i].get();
551 if (num_pollfds == 0) {
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;
564 const int res = ppoll(pollfds, num_pollfds, &ts,
nullptr);
570 for (
unsigned i = 0; i < num_pollfds; i++) {
571 pollfd_index_to_iface[i]->updateDownStatusFromPollResult(pollfds[i]);
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);
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);
586 inout_masks.read |= std::uint8_t(1U << i);
591 return _ifaces.size();
596 if (_ifaces.size() >= uavcan::MaxCanIfaces) {
607 _ifaces.emplace_back(
new IfaceWrapper(fd));
609 hal.
console->
printf(
"New iface '%s' fd %d\n", iface_name.c_str(), fd);
611 return _ifaces.size() - 1;
bool is_initialized() override
virtual CAN * getIface(uint8_t iface_index) override
std::vector< can_filter > _hw_filters_container
static int openSocket(const std::string &iface_name)
std::map< SocketCanError, uint64_t > _errors
void _incrementNumFramesInSocketTxQueue()
void _registerError(SocketCanError e)
AP_HAL::UARTDriver * console
std::unordered_multiset< uint32_t > _pending_loopback_ids
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
virtual int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&pending_tx)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
int _write(const uavcan::CanFrame &frame) const
uavcan::MonotonicTime getMonotonic()
virtual void set_UAVCAN(AP_UAVCAN *uavcan) override
int addIface(const std::string &iface_name)
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
virtual bool is_initialized()
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
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)
bool begin(uint32_t bitrate) override
unsigned _frames_in_socket_tx_queue
int close(int fileno)
POSIX Close a file with fileno handel.
uint64_t _tx_frame_counter
#define HAL_BOARD_CAN_IFACE_NAME
int16_t configureFilters(const uavcan::CanFilterConfig *filter_configs, uint16_t num_configs) override
std::priority_queue< TxItem > _tx_queue
bool _wasInPendingLoopbackSet(const uavcan::CanFrame &frame)
void updateDownStatusFromPollResult(const pollfd &pfd)
void init()
Generic board initialization function.
int errno
Note: fdevopen assigns stdin,stdout,stderr.
int getFileDescriptor() const
#define error(fmt, args ...)
const unsigned _max_frames_in_socket_tx_queue
int _read(uavcan::CanFrame &frame, uavcan::UtcTime &ts_utc, bool &loopback) const
int32_t tx_pending() override
std::queue< RxItem > _rx_queue
#define CAN_MAX_POLL_ITERATIONS_COUNT
uint64_t getErrorCount() const override
#define CAN_FILTER_NUMBER