Skip to content

Static ROS 2 subscription causes segmentation fault #1766

@alsora

Description

@alsora

Bug report

Required Info:

  • Operating System:
    • Ubuntu 20.04
  • Installation type:
    • binaries
  • Version or commit hash:
    • Galactic
  • DDS implementation:
    • Fast-DDS and CycloneDDS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

The following program terminates abruptly with a segmentation fault

#include <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

static rclcpp::Subscription<std_msgs::msg::String>::SharedPtr s_test_sub;

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);

    auto node = std::make_shared<rclcpp::Node>("my_node");

    s_test_sub = node->create_subscription<std_msgs::msg::String>(
        "my_topic",
        rclcpp::SensorDataQoS(),
        [](std_msgs::msg::String::ConstSharedPtr msg) { (void)msg; });

    rclcpp::shutdown();
    return 0;
}

With Fast-DDS

[rcl|context.c:157] failed to finalize rmw context while cleaning up context, memory may be leaked: Finalizing a context with active nodes, at /tmp/binarydeb/ros-galactic-rmw-fastrtps-cpp-5.0.0/src/rmw_init.cpp:159
[ERROR] [1630667049.700022883] [rclcpp]: failed to finalize context: error not set
cannot publish data, at /tmp/binarydeb/ros-galactic-rmw-fastrtps-shared-cpp-5.0.0/src/rmw_publish.cpp:59 during '__function__'
[ERROR] [1630667049.700135214] [my_node.rclcpp]: Error in destruction of rcl subscription handle: Failed to delete datareader, at /tmp/binarydeb/ros-galactic-rmw-fastrtps-shared-cpp-5.0.0/src/subscription.cpp:54, at /tmp/binarydeb/ros-galactic-rcl-3.1.2/src/rcl/subscription.c:174

>>> [rcutils|error_handling.c:108] rcutils_set_error_state()
This error state is being overwritten:

  'cannot publish data, at /tmp/binarydeb/ros-galactic-rmw-fastrtps-shared-cpp-5.0.0/src/rmw_publish.cpp:59'

with this new error message:

  'Failed to delete datareader, at /tmp/binarydeb/ros-galactic-rmw-fastrtps-shared-cpp-5.0.0/src/subscription.cpp:54'

rcutils_reset_error() should be called after error handling to avoid this.
<<<
__function__:79: 'destroy_subscription' failed
Segmentation fault (core dumped)

With CycloneDDS

Not all nodes were finished before finishing the context
.Ensure `rcl_node_fini` is called for all nodes before `rcl_context_fini`,to avoid leaking.
terminate called without an active exception
Aborted (core dumped)

Additional information

NOTE: the problem can be "fixed" by adding the line s_test_sub.reset() before returning from the program.

The rclcpp::Node public APIs allow to create ROS 2 subscriptions outside of a node class.
However, it looks like the lifespan of this subscription is still tied to the one of the node, thus making the aforementioned API not very useful.

The fix above is not really a solution, as it can only work in an example program and not in a more complex scenario where there be a variety of components creating entities from a node.

My expected behavior would be that calling rclcpp::shutdown() would "disable" ROS 2 entities, so I don't expect that static instance to still be usable, but at the same time I would like the program to be able to terminate gracefully.

The same problem applies also to other entities, e.g. publishers.

Metadata

Metadata

Assignees

No one assigned

    Labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions