-
Notifications
You must be signed in to change notification settings - Fork 131
Description
I'm configuring my system to use Zero-copy and shared memory, also it publishes a custom msg that has old plain type, that means all fields with fixed size.
My test consist of one publisher and four subscribers. The fourth subscriber I keep stopping it, that means shutdown() is called and after few seconds it starts again. After few times, the publisher started to return a error when calling borrow_loaned_message(). One observation I had is the publisher "Crashes" when the subscriber is starting and not when it stopped.
Could be the subscriber somehow isn't releasing some loan? What could be causing the borrow_loaned_message() running out of resource if the callback is doing nothing, neither doing any copy or holding the data.
Running ROS2 humble.
Publisher
rclcpp::init(argc, argv);
rclcpp::executors::MultiThreadedExecutor exec{};
rclcpp::NodeOptions options = rclcpp::NodeOptions{};
[...]
const auto qos = rclcpp::QoS(10).history(rclcpp::HistoryPolicy::KeepLast).keep_last(10).reliable();
[...]
try {
auto loanedMsg = publisher_->borrow_loaned_message();
publisher_->publish(std::move(loanedMsg));
}
catch(const std::exception &e)
{
std::cerr << "---------->" << e.what() << '\n';
}
[...]
exec.spin();
rclcpp::shutdown();
Subscriber
[...]
auto qosSub = rclcpp::QoS(10).history(rclcpp::HistoryPolicy::KeepLast).keep_last(10).reliable();
[...]
rclcpp::init(argc, argv);
rclcpp::executors::MultiThreadedExecutor exec{};
rclcpp::NodeOptions options = rclcpp::NodeOptions{};
[...]
void cb(const typename ros2_interface::msg::Image8m::UniquePtr msg)
{
//Doing nothing here;
}
[...]
exec.spin();
rclcpp::shutdown();
The environment variables are:
FASTRTPS_DEFAULT_PROFILES_FILE=/etc/ros_shm_profile.xml
RMW_IMPLEMENTATION=rmw_fastrtps_cpp
RMW_FASTRTPS_USE_QOS_FROM_XML=1
ROS_DISABLE_LOANED_MESSAGES=0
ROS_LOCALHOST_ONLY=1
XML profile:
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
<transport_descriptors>
<!-- Create a descriptor for the new transport -->
<transport_descriptor>
<transport_id>shm_transport_only</transport_id>
<type>SHM</type>
<segment_size>6912512</segment_size>
</transport_descriptor>
</transport_descriptors>
<participant profile_name="SHMParticipant" is_default_profile="true">
<rtps>
<!-- Link the Transport Layer to the Participant -->
<userTransports>
<transport_id>shm_transport_only</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
</rtps>
</participant>
</profiles>
Actually free_payloads_ is getting empty, but why if the subscriber is doing nothing with the data and why it isn't being released?