Skip to content

Commit

Permalink
a patch for ros-navigation#1773 BT navigator nodes with use_sim_time
Browse files Browse the repository at this point in the history
Signed-off-by: Daisuke Sato <daisukes@cmu.edu>
  • Loading branch information
daisukes committed May 27, 2020
1 parent ec7f550 commit a50a950
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
5 changes: 3 additions & 2 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
Expand Down Expand Up @@ -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<rclcpp::Node>("_", options);
Expand Down
5 changes: 3 additions & 2 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");

Expand All @@ -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<rclcpp::Node>(
std::string(get_name()) + std::string("_client_node"));
std::string(get_name()) + std::string("_rclcpp_node"));

nav_to_pose_client_ = rclcpp_action::create_client<ClientT>(
client_node_, "navigate_to_pose");
Expand Down

0 comments on commit a50a950

Please sign in to comment.