Skip to content

Commit 1e95407

Browse files
authored
set thread names by node in component container isolated (#2871)
Signed-off-by: Adam Aposhian <adam.aposhian@fireflyautomatix.com>
1 parent db8d917 commit 1e95407

File tree

1 file changed

+11
-2
lines changed

1 file changed

+11
-2
lines changed

rclcpp_components/include/rclcpp_components/component_manager_isolated.hpp

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,10 @@
2222
#include <utility>
2323
#include <vector>
2424
#include <unordered_map>
25+
#include <system_error>
2526

2627
#include "rclcpp_components/component_manager.hpp"
27-
28+
#include "rcpputils/thread_name.hpp"
2829

2930
namespace rclcpp_components
3031
{
@@ -77,8 +78,16 @@ class ComponentManagerIsolated : public rclcpp_components::ComponentManager
7778
DedicatedExecutorWrapper & wrapper = result.first->second;
7879
wrapper.executor = exec;
7980
auto & thread_initialized = wrapper.thread_initialized;
81+
auto name = node_wrappers_[node_id].get_node_base_interface()->get_name();
82+
// Copy name so that it doesn't deallocate before the thread is started
8083
wrapper.thread = std::thread(
81-
[exec, &thread_initialized]() {
84+
[exec, &thread_initialized, name]() {
85+
try {
86+
rcpputils::set_thread_name(name);
87+
} catch (const std::system_error & e) {
88+
RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Failed to set thread name: %s (%s)", e.what(),
89+
e.code().message().c_str());
90+
}
8291
thread_initialized = true;
8392
exec->spin();
8493
});

0 commit comments

Comments
 (0)