Skip to content

Commit

Permalink
PlanningSceneMonitor: Fix warning about having two publisher with the…
Browse files Browse the repository at this point in the history
… same node (moveit#662)

Co-authored-by: Dave Coleman <dave@picknik.ai>
  • Loading branch information
JafarAbdi and davetcoleman committed Sep 2, 2021
1 parent 3398193 commit 4eeacb7
Showing 1 changed file with 3 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,9 @@ PlanningSceneMonitor::PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node,
std::vector<std::string> new_args = rclcpp::NodeOptions().arguments();
new_args.push_back("--ros-args");
new_args.push_back("-r");
new_args.push_back(std::string("__node:=") + node_->get_name() + "_private");
// Add random ID to prevent warnings about multiple publishers within the same node
new_args.push_back(std::string("__node:=") + node_->get_name() + "_private_" +
std::to_string(reinterpret_cast<std::size_t>(this)));
new_args.push_back("--");
pnode_ = std::make_shared<rclcpp::Node>("_", node_->get_namespace(), rclcpp::NodeOptions().arguments(new_args));
// use same callback queue as root_nh_
Expand Down

0 comments on commit 4eeacb7

Please sign in to comment.