Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: add parameter for frame loopback and disable by default #57

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,9 @@ class SOCKETCAN_PUBLIC SocketCanReceiver
{
public:
/// Constructor
explicit SocketCanReceiver(const std::string & interface = "can0", const bool enable_fd = false);
explicit SocketCanReceiver(
const std::string & interface = "can0", const bool enable_fd = false,
const bool enable_loopback = false);
/// Destructor
~SocketCanReceiver() noexcept;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ class SOCKETCAN_PUBLIC SocketCanReceiverNode final
std::chrono::nanoseconds interval_ns_;
bool enable_fd_;
bool use_bus_time_;
bool enable_loopback_;
};
} // namespace socketcan
} // namespace drivers
Expand Down
2 changes: 2 additions & 0 deletions ros2_socketcan/launch/socket_can_bridge.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<arg name="receiver_interval_sec" default="0.01" />
<arg name="sender_timeout_sec" default="0.01" />
<arg name="enable_can_fd" default="false" />
<arg name="enable_frame_loopback" default="false" />
<arg name="from_can_bus_topic" default="from_can_bus" />
<arg name="to_can_bus_topic" default="to_can_bus" />
<arg name="use_bus_time" default="false" />
Expand All @@ -12,6 +13,7 @@
<arg name="interface" value="$(var interface)" />
<arg name="interval_sec" value="$(var receiver_interval_sec)" />
<arg name="enable_can_fd" value="$(var enable_can_fd)" />
<arg name="enable_frame_loopback" value="$(var enable_frame_loopback)" />
<arg name="from_can_bus_topic" value="$(var from_can_bus_topic)" />
<arg name="use_bus_time" value="$(var use_bus_time)" />
</include>
Expand Down
2 changes: 2 additions & 0 deletions ros2_socketcan/launch/socket_can_receiver.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ def generate_launch_description():
parameters=[{
'interface': LaunchConfiguration('interface'),
'enable_can_fd': LaunchConfiguration('enable_can_fd'),
'enable_frame_loopback': LaunchConfiguration('enable_frame_loopback'),
'interval_sec':
LaunchConfiguration('interval_sec'),
'filters': LaunchConfiguration('filters'),
Expand Down Expand Up @@ -80,6 +81,7 @@ def generate_launch_description():
return LaunchDescription([
DeclareLaunchArgument('interface', default_value='can0'),
DeclareLaunchArgument('enable_can_fd', default_value='false'),
DeclareLaunchArgument('enable_frame_loopback', default_value='false'),
DeclareLaunchArgument('interval_sec', default_value='0.01'),
DeclareLaunchArgument('use_bus_time', default_value='false'),
DeclareLaunchArgument('filters', default_value='0:0',
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
6 changes: 4 additions & 2 deletions ros2_socketcan/src/socket_can_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,10 @@ namespace socketcan
{

////////////////////////////////////////////////////////////////////////////////
SocketCanReceiver::SocketCanReceiver(const std::string & interface, const bool enable_fd)
: m_file_descriptor{bind_can_socket(interface, enable_fd)},
SocketCanReceiver::SocketCanReceiver(
const std::string & interface, const bool enable_fd,
const bool enable_loopback)
: m_file_descriptor{bind_can_socket(interface, enable_fd, enable_loopback)},
m_enable_fd(enable_fd)
{
}
Expand Down
6 changes: 5 additions & 1 deletion ros2_socketcan/src/socket_can_receiver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ SocketCanReceiverNode::SocketCanReceiverNode(rclcpp::NodeOptions options)
interface_ = this->declare_parameter("interface", "can0");
use_bus_time_ = this->declare_parameter<bool>("use_bus_time", false);
enable_fd_ = this->declare_parameter<bool>("enable_can_fd", false);
enable_loopback_ = this->declare_parameter<bool>("enable_frame_loopback", false);
double interval_sec = this->declare_parameter("interval_sec", 0.01);
this->declare_parameter("filters", "0:0");
interval_ns_ = std::chrono::duration_cast<std::chrono::nanoseconds>(
Expand All @@ -46,6 +47,9 @@ SocketCanReceiverNode::SocketCanReceiverNode(rclcpp::NodeOptions options)
RCLCPP_INFO(this->get_logger(), "interface: %s", interface_.c_str());
RCLCPP_INFO(this->get_logger(), "use bus time: %d", use_bus_time_);
RCLCPP_INFO(this->get_logger(), "can fd enabled: %s", enable_fd_ ? "true" : "false");
RCLCPP_INFO(
this->get_logger(), "frame loopback enabled: %s",
enable_loopback_ ? "true" : "false");
RCLCPP_INFO(this->get_logger(), "interval(s): %f", interval_sec);
}

Expand All @@ -54,7 +58,7 @@ LNI::CallbackReturn SocketCanReceiverNode::on_configure(const lc::State & state)
(void)state;

try {
receiver_ = std::make_unique<SocketCanReceiver>(interface_, enable_fd_);
receiver_ = std::make_unique<SocketCanReceiver>(interface_, enable_fd_, enable_loopback_);
// apply CAN filters
auto filters = get_parameter("filters").as_string();
receiver_->SetCanFilters(SocketCanReceiver::CanFilterList(filters));
Expand Down
Loading