diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 1334e1a9fe..943bf83151 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -45,7 +45,10 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/) RCLCPP_INFO(get_logger(), "Configuring"); auto node = shared_from_this(); - auto options = rclcpp::NodeOptions().arguments( { "--ros-args", 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("_", options); diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 042423dd03..421e1da927 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -58,7 +58,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name) { RCLCPP_INFO(get_logger(), "Creating"); auto options = rclcpp::NodeOptions().arguments( - {"--ros-args", std::string("__node:=") + get_name() + "_client","--"}); + {"--ros-args", std::string("__node:=") + get_name() + "_client", "--"}); client_node_ = std::make_shared("_", options); std::vector 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 26623cc7cf..dac209923d 100644 --- a/nav2_lifecycle_manager/src/lifecycle_manager.cpp +++ b/nav2_lifecycle_manager/src/lifecycle_manager.cpp @@ -55,7 +55,7 @@ LifecycleManager::LifecycleManager() std::bind(&LifecycleManager::shutdownCallback, this, _1, _2, _3)); auto options = rclcpp::NodeOptions().arguments( - {"--ros-args", std::string("__node:=") + get_name() + "service_client", "--"}); + {"--ros-args", std::string("__node:=") + get_name() + "service_client", "--"}); service_client_node_ = std::make_shared("_", options); transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE; diff --git a/nav2_rviz_plugins/src/navigation_dialog.cpp b/nav2_rviz_plugins/src/navigation_dialog.cpp index ef9138f977..1c1f409a8c 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( - {"--ros-args", "__node:=navigation_dialog_action_client","--"}); + {"--ros-args", "__node:=navigation_dialog_action_client", "--"}); client_node_ = std::make_shared("_", options); action_client_ = rclcpp_action::create_client(client_node_, "NavigateToPose");