Simple RAII wrapper around a raw CAN receiver.
More...
#include <socket_can_receiver.hpp>
|
| | SocketCanReceiver (const std::string &interface="can0") |
| | Constructor. More...
|
| |
| | ~SocketCanReceiver () noexcept |
| | Destructor. More...
|
| |
| CanId | receive (void *const data, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::zero()) const |
| |
| template<typename T , typename = std::enable_if_t<!std::is_pointer<T>::value>> |
| CanId | receive (T &data, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::zero()) const |
| |
Simple RAII wrapper around a raw CAN receiver.
◆ SocketCanReceiver()
| autoware::drivers::socketcan::SocketCanReceiver::SocketCanReceiver |
( |
const std::string & |
interface = "can0" | ) |
|
|
explicit |
◆ ~SocketCanReceiver()
| autoware::drivers::socketcan::SocketCanReceiver::~SocketCanReceiver |
( |
| ) |
|
|
noexcept |
◆ receive() [1/2]
template<typename T , typename = std::enable_if_t<!std::is_pointer<T>::value>>
| CanId autoware::drivers::socketcan::SocketCanReceiver::receive |
( |
T & |
data, |
|
|
const std::chrono::nanoseconds |
timeout = std::chrono::nanoseconds::zero() |
|
) |
| const |
|
inline |
Receive typed CAN data. Slightly less efficient than untyped interface; has extra copy and branches
- Template Parameters
-
| Type | of data to receive, must be 8 bytes or smaller |
- Parameters
-
| [out] | data | A buffer to be written with data bytes. Must be at least 8 bytes in size |
| [in] | timeout | Maximum duration to wait for data on the file descriptor. Negative durations are treated the same as zero timeout |
- Returns
- The CanId for the received can_frame, with length appropriately populated
- Exceptions
-
| SocketCanTimeout | On timeout |
| std::runtime_error | If received data would not fit into provided type |
| std::runtime_error | on other errors |
◆ receive() [2/2]
| CanId autoware::drivers::socketcan::SocketCanReceiver::receive |
( |
void *const |
data, |
|
|
const std::chrono::nanoseconds |
timeout = std::chrono::nanoseconds::zero() |
|
) |
| const |
Receive CAN data
- Parameters
-
| [out] | data | A buffer to be written with data bytes. Must be at least 8 bytes in size |
| [in] | timeout | Maximum duration to wait for data on the file descriptor. Negative durations are treated the same as zero timeout |
- Returns
- The CanId for the received can_frame, with length appropriately populated
- Exceptions
-
The documentation for this class was generated from the following files: