Skip to content

Segfault in hardware interface when reading robot_description from topic #1442

@firesurfer

Description

@firesurfer

Describe the bug

I have a hardware interface for some piece of internal hardware. When I have the controller_manager obtain the robot_description from the robot_state_publisher instead of passing it as a parameter I get a segfault in the read method of the hardware interface. This behavior does not occur when starting it with gdb attached!

To Reproduce

Start the ros2_control_node configured to read the robot_description from the corresponding topic.

Expected behavior

Should not crash ;)

Environment (please complete the following information):

  • OS: Ubuntu 22.04
  • Version: Iron binary install - hardware_interface version: 3.24.0

Additional context

I already call the read method once in the activate method in order to obtain the current positions of the hardware. This call succeeds. But in the read method there is quite a bit of logic as I need to workaround some quirks of our hardware.

Stacktrace (I replaced the names):

[ros2_control_node-12] #7    Source "../sysdeps/unix/sysv/linux/x86_64/clone3.S", line 81, in __clone3 [0x75c70952684f]
[ros2_control_node-12] #6    Source "./nptl/pthread_create.c", line 442, in start_thread [0x75c709494ac2]
[ros2_control_node-12] #5    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x75c7098dc252, in 
[ros2_control_node-12] #4    Object "/opt/ros/iron/lib/controller_manager/ros2_control_node", at 0x58f626c40a08, in 
[ros2_control_node-12] #3    Object "/opt/ros/iron/lib/libcontroller_manager.so", at 0x75c70a0869c2, in controller_manager::ControllerManager::read(rclcpp::Time const&, rclcpp::Duration const&)
[ros2_control_node-12] #2    Object "/opt/ros/iron/lib/libhardware_interface.so", at 0x75c709eb3942, in hardware_interface::ResourceManager::read(rclcpp::Time const&, rclcpp::Duration const&)
[ros2_control_node-12] #1    Object "/opt/ros/iron/lib/libhardware_interface.so", at 0x75c709ed524f, in hardware_interface::System::read(rclcpp::Time const&, rclcpp::Duration const&)
[ros2_control_node-12] #0    Object "Path to our hw interface plugin lib", at 0x75c6fc4a5da1, in NameOftheComponent...::read(rclcpp::Time const&, rclcpp::Duration const&)

Starting the node with GDB attached delays startup a tiny bit. So it might be somehow timing related.
In the hardware interface I access the URDF via system_info.original_xml and read some parameters such as joint limits from it.

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