diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp
index 39926a8e9b64d4323b5a1aec68aa82aa4acf83bc..f2fc2eaba15a8cd34edd0dd6a3696f999b775ba7 100644
--- a/nav2_bt_navigator/src/bt_navigator.cpp
+++ b/nav2_bt_navigator/src/bt_navigator.cpp
@@ -46,7 +46,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
auto node = shared_from_this();
auto options = rclcpp::NodeOptions().arguments(
- {std::string("__node:=") + get_name() + "_client_node"});
+ {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);
diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp
index 2767ac7c50427077ca78350ec178bea97458145d..b907ff1f52369d8dcfc95b7adb9ba7fc6eac78fd 100644
--- a/nav2_costmap_2d/src/costmap_2d_ros.cpp
+++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp
@@ -57,7 +57,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name)
{
RCLCPP_INFO(get_logger(), "Creating");
auto options = rclcpp::NodeOptions().arguments(
- {std::string("__node:=") + get_name() + "_client"});
+ {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"};
diff --git a/nav2_lifecycle_manager/src/lifecycle_manager.cpp b/nav2_lifecycle_manager/src/lifecycle_manager.cpp
index 9da5d5e2551d7e1d69b48bb4ad3f563a208bce05..0b07c7f660896443a0542965b9cb2a5466675094 100644
--- a/nav2_lifecycle_manager/src/lifecycle_manager.cpp
+++ b/nav2_lifecycle_manager/src/lifecycle_manager.cpp
@@ -54,7 +54,7 @@ LifecycleManager::LifecycleManager()
std::bind(&LifecycleManager::shutdownCallback, this, _1, _2, _3));
auto options = rclcpp::NodeOptions().arguments(
- {std::string("__node:=") + get_name() + "service_client"});
+ {std::string("__node:=") + get_name() + "service_client"});
service_client_node_ = std::make_shared<rclcpp::Node>("_", options);
if (autostart_) {
startup();
diff --git a/nav2_rviz_plugins/src/navigation_dialog.cpp b/nav2_rviz_plugins/src/navigation_dialog.cpp
index ea6d836775e8e465cfcab2be86353c70c08ffd4c..d842ff3637dbb800322e70d670c7ec9f1cccaee4 100644
--- a/nav2_rviz_plugins/src/navigation_dialog.cpp
+++ b/nav2_rviz_plugins/src/navigation_dialog.cpp
@@ -43,7 +43,7 @@ NavigationDialog::NavigationDialog(QWidget * parent)
: QDialog(parent)
{
auto options = rclcpp::NodeOptions().arguments(
- {"__node:=navigation_dialog_action_client"});
+ {"__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");
diff --git a/nav2_tasks/include/nav2_tasks/bt_action_node.hpp b/nav2_tasks/include/nav2_tasks/bt_action_node.hpp
index 5bfbe2e1e552d5bed463df2e4a9222cc36cdc105..9065a07f2b4dc1f93dad253ec8a979bbe121b40a 100644
--- a/nav2_tasks/include/nav2_tasks/bt_action_node.hpp
+++ b/nav2_tasks/include/nav2_tasks/bt_action_node.hpp
@@ -168,7 +168,8 @@ new_goal_received:
action_client_->async_cancel_goal(goal_handle_);
auto future_cancel = action_client_->async_cancel_goal(goal_handle_);
if (rclcpp::spin_until_future_complete(node_, future_cancel) !=
- rclcpp::executor::FutureReturnCode::SUCCESS) {
+ rclcpp::executor::FutureReturnCode::SUCCESS)
+ {
RCLCPP_ERROR(node_->get_logger(),
"Failed to cancel action server for %s", action_name_.c_str());
}
diff --git a/nav2_util/include/nav2_util/node_utils.hpp b/nav2_util/include/nav2_util/node_utils.hpp
index 4a60cf6424162ac3a9adfdd8ced382010bbac641..06947de1e05168564f075731d92fa3685276f2ed 100644
--- a/nav2_util/include/nav2_util/node_utils.hpp
+++ b/nav2_util/include/nav2_util/node_utils.hpp
@@ -48,7 +48,10 @@ std::string generate_internal_node_name(const std::string & prefix = "");
/// Creates a node with a name as generated by generate_internal_node_name
/**
- * Creates a node with a name as generated by generate_internal_node_name.
+ * Creates a node with the following settings:
+ * - name generated by generate_internal_node_name
+ * - no parameter services
+ * - no parameter event publisher
*
* \param[in] prefix A string to help understand the purpose of the node.
* \return A shared_ptr to the node.
diff --git a/nav2_util/include/nav2_util/service_client.hpp b/nav2_util/include/nav2_util/service_client.hpp
index a3f144fabdd634b04a9c3ec0b09d3927cf26bd5b..7a395a46122cde881684eb5ba2f3a6a9b088d809 100644
--- a/nav2_util/include/nav2_util/service_client.hpp
+++ b/nav2_util/include/nav2_util/service_client.hpp
@@ -44,8 +44,8 @@ public:
: service_name_(service_name)
{
auto options = rclcpp::NodeOptions().arguments(
- {"__node:=" + parent_name + std::string("_") + service_name +
- "_client"});
+ {"__node:=" + parent_name + std::string("_") + service_name +
+ "_client"});
node_ = rclcpp::Node::make_shared("_", options);
client_ = node_->create_client<ServiceT>(service_name);
}
diff --git a/nav2_util/src/lifecycle_node.cpp b/nav2_util/src/lifecycle_node.cpp
index 3a62fd70be20004085e972bfbde606fb109c02ac..480fdf154324b907877961a7079f28052e8d7bf5 100644
--- a/nav2_util/src/lifecycle_node.cpp
+++ b/nav2_util/src/lifecycle_node.cpp
@@ -19,7 +19,8 @@
#include "lifecycle_msgs/msg/state.hpp"
-namespace nav2_util {
+namespace nav2_util
+{
// The nav2_util::LifecycleNode class is temporary until we get the
// required support for lifecycle nodes in MessageFilter, TransformListener,
@@ -38,32 +39,36 @@ namespace nav2_util {
// MessageFilter.
//
-LifecycleNode::LifecycleNode(const std::string& node_name,
- const std::string& namespace_, bool use_rclcpp_node,
- const rclcpp::NodeOptions& options)
- : rclcpp_lifecycle::LifecycleNode(node_name, namespace_, options),
- use_rclcpp_node_(use_rclcpp_node) {
+LifecycleNode::LifecycleNode(
+ const std::string & node_name,
+ const std::string & namespace_, bool use_rclcpp_node,
+ const rclcpp::NodeOptions & options)
+: rclcpp_lifecycle::LifecycleNode(node_name, namespace_, options),
+ use_rclcpp_node_(use_rclcpp_node)
+{
if (use_rclcpp_node_) {
stop_rclcpp_thread_ = false;
std::vector<std::string> new_args = options.arguments();
new_args.push_back(
- std::string("__node:=") + this->get_name() + "_rclcpp_node");
+ std::string("__node:=") + this->get_name() + "_rclcpp_node");
rclcpp_node_ = std::make_shared<rclcpp::Node>(
- "_", namespace_, rclcpp::NodeOptions(options).arguments(new_args));
+ "_", namespace_, rclcpp::NodeOptions(options).arguments(new_args));
rclcpp_thread_ = std::make_unique<std::thread>(
- [&](rclcpp::Node::SharedPtr node) {
- while (!stop_rclcpp_thread_ && rclcpp::ok()) {
- rclcpp::spin_some(node);
- }
- },
- rclcpp_node_);
+ [&](rclcpp::Node::SharedPtr node) {
+ while (!stop_rclcpp_thread_ && rclcpp::ok()) {
+ rclcpp::spin_some(node);
+ }
+ },
+ rclcpp_node_);
}
}
-LifecycleNode::~LifecycleNode() {
+LifecycleNode::~LifecycleNode()
+{
// In case this lifecycle node wasn't properly shut down, do it here
if (get_current_state().id() ==
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
+ {
on_deactivate(get_current_state());
on_cleanup(get_current_state());
}
diff --git a/nav2_util/src/node_utils.cpp b/nav2_util/src/node_utils.cpp
index bb61c908a1c9d64abf238f5bf8f63963f5e22569..de4fe36ca7db2bd3fa591fa1a4f942638a50d1ab 100644
--- a/nav2_util/src/node_utils.cpp
+++ b/nav2_util/src/node_utils.cpp
@@ -63,9 +63,13 @@ std::string generate_internal_node_name(const std::string & prefix)
return sanitize_node_name(prefix) + "_" + time_to_string(8);
}
-rclcpp::Node::SharedPtr generate_internal_node(const std::string& prefix) {
- auto options = rclcpp::NodeOptions().arguments(
- {"__node:=" + generate_internal_node_name(prefix)});
+rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix)
+{
+ auto options =
+ rclcpp::NodeOptions()
+ .start_parameter_services(false)
+ .start_parameter_event_publisher(false)
+ .arguments({"__node:=" + generate_internal_node_name(prefix)});
return rclcpp::Node::make_shared("_", options);
}