Skip to content

Commit

Permalink
Fix node name collisions
Browse files Browse the repository at this point in the history
Make sure service clients have a unique node name (this was a problem in recoveries nodes)
Delimit ros arguments with new `--ros-args`,`--`
  • Loading branch information
rotu committed Aug 8, 2019
1 parent 8c4960e commit a111076
Show file tree
Hide file tree
Showing 7 changed files with 9 additions and 12 deletions.
3 changes: 1 addition & 2 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
RCLCPP_INFO(get_logger(), "Configuring");
auto node = shared_from_this();

auto options = rclcpp::NodeOptions().arguments(
{std::string("__node:=") + get_name() + "_client_node"});
auto options = rclcpp::NodeOptions().arguments( { "--ros-args", std::string("__node:=") + get_name() + "_client_node", "--"});
// Support for handling the topic-based goal pose from rviz
client_node_ = std::make_shared<rclcpp::Node>("_", options);

Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name)
{
RCLCPP_INFO(get_logger(), "Creating");
auto options = rclcpp::NodeOptions().arguments(
{std::string("__node:=") + get_name() + "_client"});
{"--ros-args", std::string("__node:=") + get_name() + "_client","--"});
client_node_ = std::make_shared<rclcpp::Node>("_", options);

std::vector<std::string> plugin_names{"static_layer", "obstacle_layer", "inflation_layer"};
Expand Down
2 changes: 1 addition & 1 deletion nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ LifecycleManager::LifecycleManager()
std::bind(&LifecycleManager::shutdownCallback, this, _1, _2, _3));

auto options = rclcpp::NodeOptions().arguments(
{std::string("__node:=") + get_name() + "service_client"});
{"--ros-args", std::string("__node:=") + get_name() + "service_client", "--"});
service_client_node_ = std::make_shared<rclcpp::Node>("_", options);

transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE;
Expand Down
2 changes: 1 addition & 1 deletion nav2_rviz_plugins/src/navigation_dialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ NavigationDialog::NavigationDialog(QWidget * parent)
: QDialog(parent)
{
auto options = rclcpp::NodeOptions().arguments(
{"__node:=navigation_dialog_action_client"});
{"--ros-args", "__node:=navigation_dialog_action_client","--"});
client_node_ = std::make_shared<rclcpp::Node>("_", options);
action_client_ = rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(client_node_,
"NavigateToPose");
Expand Down
5 changes: 1 addition & 4 deletions nav2_util/include/nav2_util/service_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,7 @@ class ServiceClient
ServiceClient(const std::string & service_name, const std::string & parent_name)
: service_name_(service_name)
{
auto options = rclcpp::NodeOptions().arguments(
{"__node:=" + parent_name + std::string("_") + service_name +
"_client"});
node_ = rclcpp::Node::make_shared("_", options);
node_ = generate_internal_node(parent_name + std::string("_") + service_name + "_client");
client_ = node_->create_client<ServiceT>(service_name);
}

Expand Down
5 changes: 3 additions & 2 deletions nav2_util/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,9 @@ LifecycleNode::LifecycleNode(
{
if (use_rclcpp_node_) {
std::vector<std::string> new_args = options.arguments();
new_args.push_back(
std::string("__node:=") + this->get_name() + "_rclcpp_node");
new_args.push_back("--ros-args");
new_args.push_back(std::string("__node:=") + this->get_name() + "_rclcpp_node");
new_args.push_back("--");
rclcpp_node_ = std::make_shared<rclcpp::Node>(
"_", namespace_, rclcpp::NodeOptions(options).arguments(new_args));
rclcpp_exec_ = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
Expand Down
2 changes: 1 addition & 1 deletion nav2_util/src/node_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix)
rclcpp::NodeOptions()
.start_parameter_services(false)
.start_parameter_event_publisher(false)
.arguments({"__node:=" + generate_internal_node_name(prefix)});
.arguments({"--ros-args", "__node:=" + generate_internal_node_name(prefix), "--"});
return rclcpp::Node::make_shared("_", options);
}

Expand Down

0 comments on commit a111076

Please sign in to comment.