Nav2 Navigation Stack - kilted  kilted
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  declare_parameter_if_not_declared(
53  this, "filter_duration", rclcpp::ParameterValue(0.3));
54 }
55 
57 {
58 }
59 
60 nav2_util::CallbackReturn
61 BtNavigator::on_configure(const rclcpp_lifecycle::State & state)
62 {
63  RCLCPP_INFO(get_logger(), "Configuring");
64 
65  tf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
66  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
67  get_node_base_interface(), get_node_timers_interface());
68  tf_->setCreateTimerInterface(timer_interface);
69  tf_->setUsingDedicatedThread(true);
70  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, false);
71 
72  global_frame_ = get_parameter("global_frame").as_string();
73  robot_frame_ = get_parameter("robot_base_frame").as_string();
74  transform_tolerance_ = get_parameter("transform_tolerance").as_double();
75  odom_topic_ = get_parameter("odom_topic").as_string();
76  filter_duration_ = get_parameter("filter_duration").as_double();
77 
78  // Libraries to pull plugins (BT Nodes) from
79  std::vector<std::string> plugin_lib_names;
80  plugin_lib_names = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS, ';');
81 
82  auto user_defined_plugins = get_parameter("plugin_lib_names").as_string_array();
83  // append user_defined_plugins to plugin_lib_names
84  plugin_lib_names.insert(
85  plugin_lib_names.end(), user_defined_plugins.begin(),
86  user_defined_plugins.end());
87 
88  nav2_core::FeedbackUtils feedback_utils;
89  feedback_utils.tf = tf_;
90  feedback_utils.global_frame = global_frame_;
91  feedback_utils.robot_frame = robot_frame_;
92  feedback_utils.transform_tolerance = transform_tolerance_;
93 
94  // Odometry smoother object for getting current speed
95  auto node = shared_from_this();
96  odom_smoother_ = std::make_shared<nav2_util::OdomSmoother>(node, filter_duration_, odom_topic_);
97 
98  // Navigator defaults
99  const std::vector<std::string> default_navigator_ids = {
100  "navigate_to_pose",
101  "navigate_through_poses"
102  };
103  const std::vector<std::string> default_navigator_types = {
104  "nav2_bt_navigator::NavigateToPoseNavigator",
105  "nav2_bt_navigator::NavigateThroughPosesNavigator"
106  };
107 
108  std::vector<std::string> navigator_ids;
109  declare_parameter_if_not_declared(
110  node, "navigators",
111  rclcpp::ParameterValue(default_navigator_ids));
112  get_parameter("navigators", navigator_ids);
113  if (navigator_ids == default_navigator_ids) {
114  for (size_t i = 0; i < default_navigator_ids.size(); ++i) {
115  declare_parameter_if_not_declared(
116  node, default_navigator_ids[i] + ".plugin",
117  rclcpp::ParameterValue(default_navigator_types[i]));
118  }
119  }
120 
121  // Load navigator plugins
122  for (size_t i = 0; i != navigator_ids.size(); i++) {
123  try {
124  std::string navigator_type = nav2_util::get_plugin_type_param(node, navigator_ids[i]);
125  RCLCPP_INFO(
126  get_logger(), "Creating navigator id %s of type %s",
127  navigator_ids[i].c_str(), navigator_type.c_str());
128  navigators_.push_back(class_loader_.createUniqueInstance(navigator_type));
129  if (!navigators_.back()->on_configure(
130  node, plugin_lib_names, feedback_utils,
131  &plugin_muxer_, odom_smoother_))
132  {
133  return nav2_util::CallbackReturn::FAILURE;
134  }
135  } catch (const std::exception & ex) {
136  RCLCPP_FATAL(
137  get_logger(), "Failed to create navigator id %s."
138  " Exception: %s", navigator_ids[i].c_str(), ex.what());
139  on_cleanup(state);
140  return nav2_util::CallbackReturn::FAILURE;
141  }
142  }
143 
144  return nav2_util::CallbackReturn::SUCCESS;
145 }
146 
147 nav2_util::CallbackReturn
148 BtNavigator::on_activate(const rclcpp_lifecycle::State & state)
149 {
150  RCLCPP_INFO(get_logger(), "Activating");
151  for (size_t i = 0; i != navigators_.size(); i++) {
152  if (!navigators_[i]->on_activate()) {
153  on_deactivate(state);
154  return nav2_util::CallbackReturn::FAILURE;
155  }
156  }
157 
158  // create bond connection
159  createBond();
160 
161  return nav2_util::CallbackReturn::SUCCESS;
162 }
163 
164 nav2_util::CallbackReturn
165 BtNavigator::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
166 {
167  RCLCPP_INFO(get_logger(), "Deactivating");
168  for (size_t i = 0; i != navigators_.size(); i++) {
169  if (!navigators_[i]->on_deactivate()) {
170  return nav2_util::CallbackReturn::FAILURE;
171  }
172  }
173 
174  // destroy bond connection
175  destroyBond();
176 
177  return nav2_util::CallbackReturn::SUCCESS;
178 }
179 
180 nav2_util::CallbackReturn
181 BtNavigator::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
182 {
183  RCLCPP_INFO(get_logger(), "Cleaning up");
184 
185  // Reset the listener before the buffer
186  tf_listener_.reset();
187  tf_.reset();
188 
189  for (size_t i = 0; i != navigators_.size(); i++) {
190  if (!navigators_[i]->on_cleanup()) {
191  return nav2_util::CallbackReturn::FAILURE;
192  }
193  }
194 
195  navigators_.clear();
196  RCLCPP_INFO(get_logger(), "Completed Cleaning up");
197  return nav2_util::CallbackReturn::SUCCESS;
198 }
199 
200 nav2_util::CallbackReturn
201 BtNavigator::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
202 {
203  RCLCPP_INFO(get_logger(), "Shutting down");
204  return nav2_util::CallbackReturn::SUCCESS;
205 }
206 
207 } // namespace nav2_bt_navigator
208 
209 #include "rclcpp_components/register_node_macro.hpp"
210 
211 // Register the component with class_loader.
212 // This acts as a sort of entry point, allowing the component to be discoverable when its library
213 // is being loaded into a running process.
214 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.