#include <socketcan.hpp>
Classes | |
struct | RxItem |
struct | TxItem |
Public Member Functions | |
std::int16_t | configureFilters (const uavcan::CanFilterConfig *const filter_configs, const std::uint16_t num_configs) override |
std::uint64_t | getErrorCount () const override |
const decltype(errors_) & | getErrors () const |
int | getFileDescriptor () const |
std::uint16_t | getNumFilters () const override |
bool | hasReadyRx () const |
bool | hasReadyTx () const |
void | poll (bool read, bool write) |
std::int16_t | receive (uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override |
std::int16_t | send (const uavcan::CanFrame &frame, const uavcan::MonotonicTime tx_deadline, const uavcan::CanIOFlags flags) override |
SocketCanIface (const SystemClock &clock, int socket_fd, int max_frames_in_socket_tx_queue=2) | |
virtual | ~SocketCanIface () |
![]() | |
virtual int16_t | receive (CanFrame &out_frame, MonotonicTime &out_ts_monotonic, UtcTime &out_ts_utc, CanIOFlags &out_flags)=0 |
virtual int16_t | send (const CanFrame &frame, MonotonicTime tx_deadline, CanIOFlags flags)=0 |
virtual | ~ICanIface () |
Static Public Member Functions | |
static int | openSocket (const std::string &iface_name) |
Static Public Attributes | |
static constexpr unsigned | NumFilters = 8 |
Private Member Functions | |
bool | checkHWFilters (const ::can_frame &frame) const |
void | confirmSentFrame () |
void | incrementNumFramesInSocketTxQueue () |
void | pollRead () |
void | pollWrite () |
int | read (uavcan::CanFrame &frame, uavcan::UtcTime &ts_utc, bool &loopback) const |
void | registerError (SocketCanError e) |
bool | wasInPendingLoopbackSet (const uavcan::CanFrame &frame) |
int | write (const uavcan::CanFrame &frame) const |
Static Private Member Functions | |
static inline ::can_frame | makeSocketCanFrame (const uavcan::CanFrame &uavcan_frame) |
static uavcan::CanFrame | makeUavcanFrame (const ::can_frame &sockcan_frame) |
Private Attributes | |
const SystemClock & | clock_ |
std::map< SocketCanError, std::uint64_t > | errors_ |
const int | fd_ |
unsigned | frames_in_socket_tx_queue_ = 0 |
std::vector<::can_filter > | hw_filters_container_ |
const unsigned | max_frames_in_socket_tx_queue_ |
std::unordered_multiset< std::uint32_t > | pending_loopback_ids_ |
std::queue< RxItem > | rx_queue_ |
std::uint64_t | tx_frame_counter_ = 0 |
Increments with every frame pushed into the TX queue. More... | |
std::priority_queue< TxItem > | tx_queue_ |
Single SocketCAN socket interface.
SocketCAN socket adapter maintains TX and RX queues in user space. At any moment socket's buffer contains no more than 'max_frames_in_socket_tx_queue_' TX frames, rest is waiting in the user space TX queue; when the socket produces loopback for the previously sent TX frame the next frame from the user space TX queue will be sent into the socket.
This approach allows to properly maintain TX timeouts (http://stackoverflow.com/questions/19633015/). TX timestamping is implemented by means of reading RX timestamps of loopback frames (see "TX timestamping" on linux-can mailing list, http://permalink.gmane.org/gmane.linux.can/5322).
Note that if max_frames_in_socket_tx_queue_ is greater than one, frame reordering may occur (depending on the unrderlying logic).
This class is too complex and needs to be refactored later. At least, basic socket IO and configuration should be extracted into a different class.
Definition at line 60 of file socketcan.hpp.
|
inline |
Takes ownership of socket's file descriptor.
max_frames_in_socket_tx_queue See a note in the class comment.
Definition at line 372 of file socketcan.hpp.
|
inlinevirtual |
Socket file descriptor will be closed.
Definition at line 383 of file socketcan.hpp.
|
inlineprivate |
Returns true if a frame accepted by HW filters
Definition at line 347 of file socketcan.hpp.
|
inlineoverridevirtual |
Configure the hardware CAN filters. CanFilterConfig.
Implements uavcan::ICanIface.
Definition at line 451 of file socketcan.hpp.
|
inlineprivate |
Definition at line 166 of file socketcan.hpp.
|
inlineoverridevirtual |
Returns total number of errors of each kind detected since the object was created.
Implements uavcan::ICanIface.
Definition at line 499 of file socketcan.hpp.
|
inline |
Returns number of errors of each kind in a map.
Definition at line 509 of file socketcan.hpp.
|
inline |
Definition at line 511 of file socketcan.hpp.
|
inlineoverridevirtual |
Number of available hardware filters.
Implements uavcan::ICanIface.
Definition at line 493 of file socketcan.hpp.
|
inline |
Definition at line 445 of file socketcan.hpp.
|
inline |
Definition at line 446 of file socketcan.hpp.
|
inlineprivate |
Definition at line 160 of file socketcan.hpp.
|
inlinestaticprivate |
Definition at line 62 of file socketcan.hpp.
|
inlinestaticprivate |
Definition at line 83 of file socketcan.hpp.
|
inlinestatic |
Open and configure a CAN socket on iface specified by name.
iface_name | String containing iface name, e.g. "can0", "vcan1", "slcan0" |
Definition at line 518 of file socketcan.hpp.
|
inline |
Performs socket read/write.
read | Socket is readable |
write | Socket is writeable |
Definition at line 433 of file socketcan.hpp.
|
inlineprivate |
Definition at line 308 of file socketcan.hpp.
|
inlineprivate |
Definition at line 272 of file socketcan.hpp.
|
inlineprivate |
SocketCAN git show 1e55659ce6ddb5247cee0b1f720d77a799902b85 MSG_DONTROUTE is set for any packet from localhost, MSG_CONFIRM is set for any pakcet of your socket. Diff: https://git.ucsd.edu/abuss/linux/commit/1e55659ce6ddb5247cee0b1f720d77a799902b85 Man: https://www.kernel.org/doc/Documentation/networking/can.txt (chapter 4.1.6).
Definition at line 217 of file socketcan.hpp.
|
inlineoverride |
Will read the socket only if RX queue is empty. Normally, poll() needs to be executed first.
Definition at line 406 of file socketcan.hpp.
|
inlineprivate |
Definition at line 158 of file socketcan.hpp.
|
inlineoverride |
Assumes that the socket is writeable
Definition at line 392 of file socketcan.hpp.
|
inlineprivate |
Definition at line 178 of file socketcan.hpp.
|
inlineprivate |
Definition at line 188 of file socketcan.hpp.
|
private |
Definition at line 142 of file socketcan.hpp.
|
private |
Definition at line 150 of file socketcan.hpp.
|
private |
Definition at line 143 of file socketcan.hpp.
|
private |
Definition at line 146 of file socketcan.hpp.
|
private |
Definition at line 156 of file socketcan.hpp.
|
private |
Definition at line 145 of file socketcan.hpp.
|
staticconstexpr |
SocketCAN emulates the CAN filters in software, so the number of filters is virtually unlimited. This method returns a constant value.
Definition at line 492 of file socketcan.hpp.
|
private |
Definition at line 154 of file socketcan.hpp.
|
private |
Definition at line 153 of file socketcan.hpp.
|
private |
Increments with every frame pushed into the TX queue.
Definition at line 148 of file socketcan.hpp.
|
private |
Definition at line 152 of file socketcan.hpp.