Skip to content

Commit

Permalink
Add enable_loopback option to SocketCAN interface
Browse files Browse the repository at this point in the history
  • Loading branch information
JWhitleyWork committed Dec 4, 2024
1 parent 85da8c3 commit 659a866
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 3 deletions.
6 changes: 5 additions & 1 deletion ros2_socketcan/include/ros2_socketcan/socket_can_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,14 @@ namespace socketcan
/// Bind a non-blocking CAN_RAW socket to the given interface
/// \param[in] interface The name of the interface to bind, must be smaller than IFNAMSIZ
/// \param[in] enable_fd Whether this socket uses CAN FD or not
/// \param[in] enable_loopback Whether this socket will receive sent messages from other processes
/// connected to the same socket on the same system
/// \return The file descriptor bound to the given interface
/// \throw std::runtime_error If one of socket(), fnctl(), ioctl(), bind() failed
/// \throw std::domain_error If the provided interface name is too long
int32_t bind_can_socket(const std::string & interface, bool enable_fd);
int32_t bind_can_socket(
const std::string & interface, bool enable_fd,
bool enable_loopback = false);

/// Set SocketCAN filters
/// \param[in] fd File descriptor of the socket
Expand Down
12 changes: 10 additions & 2 deletions ros2_socketcan/src/socket_can_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace socketcan
{

////////////////////////////////////////////////////////////////////////////////
int32_t bind_can_socket(const std::string & interface, bool enable_fd)
int32_t bind_can_socket(const std::string & interface, bool enable_fd, bool enable_loopback)
{
if (interface.length() >= static_cast<std::string::size_type>(IFNAMSIZ)) {
throw std::domain_error{"CAN interface name too long"};
Expand Down Expand Up @@ -73,14 +73,22 @@ int32_t bind_can_socket(const std::string & interface, bool enable_fd)
}
//lint -restore NOLINT

// Enable local message loopback
const int32_t loopback = enable_loopback ? 1 : 0;
if (0 !=
setsockopt(file_descriptor, SOL_CAN_RAW, CAN_RAW_LOOPBACK, &loopback, sizeof(loopback)))
{
throw std::runtime_error{"Failed to set local loopback option"};
}

// Enable CAN FD support
const int32_t enable_canfd = enable_fd ? 1 : 0;
if (0 !=
setsockopt(
file_descriptor, SOL_CAN_RAW, CAN_RAW_FD_FRAMES, &enable_canfd,
sizeof(enable_canfd)))
{
throw std::runtime_error{"Failed to enable CAN FD support"};
throw std::runtime_error{"Failed to set CAN FD support option"};
}

return file_descriptor;
Expand Down

0 comments on commit 659a866

Please sign in to comment.