Skip to content

Commit ea61bc4

Browse files
committed
fix: explicitly add the same namespace as the parent node
1 parent 83d05ae commit ea61bc4

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -165,7 +165,7 @@ void TrajectoryExecutionManager::initialize()
165165
rclcpp::NodeOptions opt;
166166
opt.allow_undeclared_parameters(true);
167167
opt.automatically_declare_parameters_from_overrides(true);
168-
controller_mgr_node_ = std::make_shared<rclcpp::Node>("moveit_simple_controller_manager", opt);
168+
controller_mgr_node_ = std::make_shared<rclcpp::Node>("moveit_simple_controller_manager", node_->get_namespace(), opt);
169169

170170
auto all_params = node_->get_node_parameters_interface()->get_parameter_overrides();
171171
for (const auto& param : all_params)

0 commit comments

Comments
 (0)