Skip to content
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

Ignore global parameters when spawning sub-nodes #851

Closed
Show file tree
Hide file tree
Changes from 4 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
3 changes: 2 additions & 1 deletion nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,8 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
auto node = shared_from_this();

// Support for handling the topic-based goal pose from rviz
client_node_ = std::make_shared<rclcpp::Node>("bt_navigator_client_node");
client_node_ =
std::make_shared<rclcpp::Node>("bt_navigator_client_node", rclcpp::NodeOptions().use_global_arguments(false));

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks like the code is exceeding 100 columns here and will fail the cpplint tool. Please run ament_cpplint and ament_uncrustify. We're trying to get all code to pass cleanly.


self_client_ = rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
client_node_, "NavigateToPose");
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 @@ -56,7 +56,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name)
: nav2_util::LifecycleNode(name, name, true), name_(name)
{
RCLCPP_INFO(get_logger(), "Creating");
client_node_ = std::make_shared<rclcpp::Node>(name + "_client");
client_node_ = std::make_shared<rclcpp::Node>(name + "_client", rclcpp::NodeOptions().use_global_arguments(false));

std::vector<std::string> plugin_names{"static_layer", "obstacle_layer", "inflation_layer"};
std::vector<std::string> plugin_types{"nav2_costmap_2d::StaticLayer",
Expand Down
3 changes: 2 additions & 1 deletion nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,8 @@ LifecycleManager::LifecycleManager()
shutdown_srv_ = create_service<std_srvs::srv::Empty>("lifecycle_manager/shutdown",
std::bind(&LifecycleManager::shutdownCallback, this, _1, _2, _3));

service_client_node_ = std::make_shared<rclcpp::Node>("lifecycle_manager_service_client");
service_client_node_ = std::make_shared<rclcpp::Node>("lifecycle_manager_service_client",
rclcpp::NodeOptions().use_global_arguments(false));

if (autostart_) {
startup();
Expand Down
3 changes: 2 additions & 1 deletion nav2_rviz_plugins/src/navigation_dialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@ NavigationDialog::onCancelButtonPressed()
NavigationDialog::NavigationDialog(QWidget * parent)
: QDialog(parent)
{
client_node_ = std::make_shared<rclcpp::Node>("navigation_dialog_action_client");
client_node_ = std::make_shared<rclcpp::Node>("navigation_dialog_action_client",
rclcpp::NodeOptions().use_global_arguments(false));
action_client_ = rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(client_node_,
"NavigateToPose");
goal_ = nav2_msgs::action::NavigateToPose::Goal();
Expand Down
2 changes: 1 addition & 1 deletion nav2_util/include/nav2_util/service_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class ServiceClient
ServiceClient(const std::string & service_name, const std::string & parent_name)
: service_name_(service_name)
{
node_ = rclcpp::Node::make_shared(parent_name + std::string("_") + service_name + "_client");
node_ = rclcpp::Node::make_shared(parent_name + std::string("_") + service_name + "_client", rclcpp::NodeOptions().use_global_arguments(false));
client_ = node_->create_client<ServiceT>(service_name);
}

Expand Down
3 changes: 2 additions & 1 deletion nav2_util/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,8 @@ LifecycleNode::LifecycleNode(
{
if (use_rclcpp_node_) {
stop_rclcpp_thread_ = false;
rclcpp_node_ = std::make_shared<rclcpp::Node>(node_name + "_rclcpp_node", namespace_);
rclcpp_node_ = std::make_shared<rclcpp::Node>(node_name + "_rclcpp_node", namespace_,
rclcpp::NodeOptions().use_global_arguments(false));
rclcpp_thread_ = std::make_unique<std::thread>(
[&](rclcpp::Node::SharedPtr node) {
while (!stop_rclcpp_thread_ && rclcpp::ok()) {rclcpp::spin_some(node);}}, rclcpp_node_
Expand Down
6 changes: 3 additions & 3 deletions nav2_util/src/node_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,9 +67,9 @@ rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix)
{
rclcpp::NodeOptions options;
options.use_global_arguments(false);
options.start_parameter_services(false);
options.start_parameter_event_publisher(false);
return rclcpp::Node::make_shared(generate_internal_node_name(prefix));
// options.start_parameter_services(false);

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Prefer removing commented-out code. I'm generally not a fan of leaving commented-out code around for documentation purposes, but would instead rather have it in the revision history and keep the current code as clean as possible.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

// options.start_parameter_event_publisher(false);
return rclcpp::Node::make_shared(generate_internal_node_name(prefix), options);
}

rclcpp::NodeOptions
Expand Down