Skip to content
Snippets Groups Projects
Commit 45652529 authored by Carl Delsey's avatar Carl Delsey Committed by Matt Hansen
Browse files

Adding -r and --ros-args where needed.

parent cf530044
No related branches found
No related tags found
No related merge requests found
......@@ -47,7 +47,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
auto options = rclcpp::NodeOptions().arguments(
{"--ros-args",
std::string("__node:=") + get_name() + "_client_node",
"-r", 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);
......
......@@ -64,7 +64,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name, const std::string & absolut
{
RCLCPP_INFO(get_logger(), "Creating Costmap");
auto options = rclcpp::NodeOptions().arguments(
{"--ros-args", std::string("__node:=") + get_name() + "_client", "--"});
{"--ros-args", "-r", 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"};
......
......@@ -52,7 +52,7 @@ LifecycleManager::LifecycleManager()
std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3));
auto options = rclcpp::NodeOptions().arguments(
{"--ros-args", std::string("__node:=") + get_name() + "service_client", "--"});
{"--ros-args", "-r", 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;
......
......@@ -50,6 +50,7 @@ LifecycleNode::LifecycleNode(
if (use_rclcpp_node_) {
std::vector<std::string> new_args = options.arguments();
new_args.push_back("--ros-args");
new_args.push_back("-r");
new_args.push_back(std::string("__node:=") + this->get_name() + "_rclcpp_node");
new_args.push_back("--");
rclcpp_node_ = std::make_shared<rclcpp::Node>(
......
......@@ -82,7 +82,7 @@ rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix)
rclcpp::NodeOptions()
.start_parameter_services(false)
.start_parameter_event_publisher(false)
.arguments({"--ros-args", "__node:=" + generate_internal_node_name(prefix), "--"});
.arguments({"--ros-args", "-r", "__node:=" + generate_internal_node_name(prefix), "--"});
return rclcpp::Node::make_shared("_", options);
}
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment