From a50a9500cce8b0e362ea3c9ba8967be89d9f840b Mon Sep 17 00:00:00 2001 From: Daisuke Sato Date: Wed, 27 May 2020 18:39:31 -0400 Subject: [PATCH] a patch for #1773 BT navigator nodes with use_sim_time Signed-off-by: Daisuke Sato --- nav2_bt_navigator/src/bt_navigator.cpp | 5 +++-- nav2_waypoint_follower/src/waypoint_follower.cpp | 5 +++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 7e28205aa1..1e88ed2d2e 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -31,7 +31,7 @@ namespace nav2_bt_navigator { BtNavigator::BtNavigator() -: nav2_util::LifecycleNode("bt_navigator", "", true), +: nav2_util::LifecycleNode("bt_navigator", "", false), start_time_(0) { RCLCPP_INFO(get_logger(), "Creating"); @@ -76,9 +76,10 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Configuring"); + // use suffix '_rclcpp_node' to keep parameter file consistency #1773 auto options = rclcpp::NodeOptions().arguments( {"--ros-args", - "-r", std::string("__node:=") + get_name() + "_client_node", + "-r", std::string("__node:=") + get_name() + "_rclcpp_node", "--"}); // Support for handling the topic-based goal pose from rviz client_node_ = std::make_shared("_", options); diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index dd08a89d59..3a0edabce6 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -26,7 +26,7 @@ namespace nav2_waypoint_follower { WaypointFollower::WaypointFollower() -: nav2_util::LifecycleNode("WaypointFollower", "", true) +: nav2_util::LifecycleNode("WaypointFollower", "", false) { RCLCPP_INFO(get_logger(), "Creating"); @@ -47,8 +47,9 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/) stop_on_failure_ = get_parameter("stop_on_failure").as_bool(); loop_rate_ = get_parameter("loop_rate").as_int(); + // use suffix '_rclcpp_node' to keep parameter file consistency #1773 client_node_ = std::make_shared( - std::string(get_name()) + std::string("_client_node")); + std::string(get_name()) + std::string("_rclcpp_node")); nav_to_pose_client_ = rclcpp_action::create_client( client_node_, "navigate_to_pose");