Skip to content

nlamprian/fix_duplicate_node #411

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 1 commit into
base: ros2-master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 7 additions & 3 deletions teb_local_planner/src/teb_local_planner_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,10 +85,14 @@ void TebLocalPlannerROS::initialize(nav2_util::LifecycleNode::SharedPtr node)
// check if the plugin is already initialized
if(!initialized_)
{
auto options = rclcpp::NodeOptions().arguments(
{"--ros-args", "-r",
std::string("__node:=") + node->get_name() + "_" + name_ +
"_costmap_converter_rclcpp_node",
"--"});
intra_proc_node_ = std::make_shared<rclcpp::Node>("_", options);

// declare parameters (ros2-dashing)
intra_proc_node_.reset(
new rclcpp::Node("costmap_converter", node->get_namespace(),
rclcpp::NodeOptions()));
cfg_->declareParameters(node, name_);

// get parameters of TebConfig via the nodehandle and override the default config
Expand Down