Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
bt_navigator.cpp
1 // Copyright (c) 2018 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_bt_navigator/bt_navigator.hpp"
16 
17 #include <memory>
18 #include <string>
19 #include <utility>
20 #include <vector>
21 
22 #include "nav2_util/geometry_utils.hpp"
23 #include "nav2_util/node_utils.hpp"
24 #include "nav2_util/string_utils.hpp"
25 #include "nav2_util/robot_utils.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 
28 #include "nav2_behavior_tree/plugins_list.hpp"
29 
30 using nav2_util::declare_parameter_if_not_declared;
31 
32 namespace nav2_bt_navigator
33 {
34 
35 BtNavigator::BtNavigator(rclcpp::NodeOptions options)
36 : nav2_util::LifecycleNode("bt_navigator", "",
37  options.automatically_declare_parameters_from_overrides(true)),
38  class_loader_("nav2_core", "nav2_core::NavigatorBase")
39 {
40  RCLCPP_INFO(get_logger(), "Creating");
41 
42  declare_parameter_if_not_declared(
43  this, "plugin_lib_names", rclcpp::ParameterValue(std::vector<std::string>{}));
44  declare_parameter_if_not_declared(
45  this, "transform_tolerance", rclcpp::ParameterValue(0.1));
46  declare_parameter_if_not_declared(
47  this, "global_frame", rclcpp::ParameterValue(std::string("map")));
48  declare_parameter_if_not_declared(
49  this, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
50  declare_parameter_if_not_declared(
51  this, "odom_topic", rclcpp::ParameterValue(std::string("odom")));
52 }
53 
55 {
56 }
57 
58 nav2_util::CallbackReturn
59 BtNavigator::on_configure(const rclcpp_lifecycle::State & state)
60 {
61  RCLCPP_INFO(get_logger(), "Configuring");
62 
63  tf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
64  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
65  get_node_base_interface(), get_node_timers_interface());
66  tf_->setCreateTimerInterface(timer_interface);
67  tf_->setUsingDedicatedThread(true);
68  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, false);
69 
70  global_frame_ = get_parameter("global_frame").as_string();
71  robot_frame_ = get_parameter("robot_base_frame").as_string();
72  transform_tolerance_ = get_parameter("transform_tolerance").as_double();
73  odom_topic_ = get_parameter("odom_topic").as_string();
74 
75  // Libraries to pull plugins (BT Nodes) from
76  std::vector<std::string> plugin_lib_names;
77  plugin_lib_names = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS, ';');
78 
79  auto user_defined_plugins = get_parameter("plugin_lib_names").as_string_array();
80  // append user_defined_plugins to plugin_lib_names
81  plugin_lib_names.insert(
82  plugin_lib_names.end(), user_defined_plugins.begin(),
83  user_defined_plugins.end());
84 
85  nav2_core::FeedbackUtils feedback_utils;
86  feedback_utils.tf = tf_;
87  feedback_utils.global_frame = global_frame_;
88  feedback_utils.robot_frame = robot_frame_;
89  feedback_utils.transform_tolerance = transform_tolerance_;
90 
91  // Odometry smoother object for getting current speed
92  auto node = shared_from_this();
93  odom_smoother_ = std::make_shared<nav2_util::OdomSmoother>(node, 0.3, odom_topic_);
94 
95  // Navigator defaults
96  const std::vector<std::string> default_navigator_ids = {
97  "navigate_to_pose",
98  "navigate_through_poses"
99  };
100  const std::vector<std::string> default_navigator_types = {
101  "nav2_bt_navigator::NavigateToPoseNavigator",
102  "nav2_bt_navigator::NavigateThroughPosesNavigator"
103  };
104 
105  std::vector<std::string> navigator_ids;
106  declare_parameter_if_not_declared(
107  node, "navigators",
108  rclcpp::ParameterValue(default_navigator_ids));
109  get_parameter("navigators", navigator_ids);
110  if (navigator_ids == default_navigator_ids) {
111  for (size_t i = 0; i < default_navigator_ids.size(); ++i) {
112  declare_parameter_if_not_declared(
113  node, default_navigator_ids[i] + ".plugin",
114  rclcpp::ParameterValue(default_navigator_types[i]));
115  }
116  }
117 
118  // Load navigator plugins
119  for (size_t i = 0; i != navigator_ids.size(); i++) {
120  try {
121  std::string navigator_type = nav2_util::get_plugin_type_param(node, navigator_ids[i]);
122  RCLCPP_INFO(
123  get_logger(), "Creating navigator id %s of type %s",
124  navigator_ids[i].c_str(), navigator_type.c_str());
125  navigators_.push_back(class_loader_.createUniqueInstance(navigator_type));
126  if (!navigators_.back()->on_configure(
127  node, plugin_lib_names, feedback_utils,
128  &plugin_muxer_, odom_smoother_))
129  {
130  return nav2_util::CallbackReturn::FAILURE;
131  }
132  } catch (const std::exception & ex) {
133  RCLCPP_FATAL(
134  get_logger(), "Failed to create navigator id %s."
135  " Exception: %s", navigator_ids[i].c_str(), ex.what());
136  on_cleanup(state);
137  return nav2_util::CallbackReturn::FAILURE;
138  }
139  }
140 
141  return nav2_util::CallbackReturn::SUCCESS;
142 }
143 
144 nav2_util::CallbackReturn
145 BtNavigator::on_activate(const rclcpp_lifecycle::State & state)
146 {
147  RCLCPP_INFO(get_logger(), "Activating");
148  for (size_t i = 0; i != navigators_.size(); i++) {
149  if (!navigators_[i]->on_activate()) {
150  on_deactivate(state);
151  return nav2_util::CallbackReturn::FAILURE;
152  }
153  }
154 
155  // create bond connection
156  createBond();
157 
158  return nav2_util::CallbackReturn::SUCCESS;
159 }
160 
161 nav2_util::CallbackReturn
162 BtNavigator::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
163 {
164  RCLCPP_INFO(get_logger(), "Deactivating");
165  for (size_t i = 0; i != navigators_.size(); i++) {
166  if (!navigators_[i]->on_deactivate()) {
167  return nav2_util::CallbackReturn::FAILURE;
168  }
169  }
170 
171  // destroy bond connection
172  destroyBond();
173 
174  return nav2_util::CallbackReturn::SUCCESS;
175 }
176 
177 nav2_util::CallbackReturn
178 BtNavigator::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
179 {
180  RCLCPP_INFO(get_logger(), "Cleaning up");
181 
182  // Reset the listener before the buffer
183  tf_listener_.reset();
184  tf_.reset();
185 
186  for (size_t i = 0; i != navigators_.size(); i++) {
187  if (!navigators_[i]->on_cleanup()) {
188  return nav2_util::CallbackReturn::FAILURE;
189  }
190  }
191 
192  navigators_.clear();
193  RCLCPP_INFO(get_logger(), "Completed Cleaning up");
194  return nav2_util::CallbackReturn::SUCCESS;
195 }
196 
197 nav2_util::CallbackReturn
198 BtNavigator::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
199 {
200  RCLCPP_INFO(get_logger(), "Shutting down");
201  return nav2_util::CallbackReturn::SUCCESS;
202 }
203 
204 } // namespace nav2_bt_navigator
205 
206 #include "rclcpp_components/register_node_macro.hpp"
207 
208 // Register the component with class_loader.
209 // This acts as a sort of entry point, allowing the component to be discoverable when its library
210 // is being loaded into a running process.
211 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_bt_navigator::BtNavigator)
An action server that uses behavior tree for navigating a robot to its goal position.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures member variables.
BtNavigator(rclcpp::NodeOptions options=rclcpp::NodeOptions())
A constructor for nav2_bt_navigator::BtNavigator class.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates action server.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets member variables.
~BtNavigator()
A destructor for nav2_bt_navigator::BtNavigator class.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates action server.
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.
Navigator feedback utilities required to get transforms and reference frames.