15 #include "nav2_bt_navigator/bt_navigator.hpp"
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"
28 #include "nav2_behavior_tree/plugins_list.hpp"
30 using nav2_util::declare_parameter_if_not_declared;
32 namespace nav2_bt_navigator
36 : nav2_util::LifecycleNode(
"bt_navigator",
"",
37 options.automatically_declare_parameters_from_overrides(true)),
38 class_loader_(
"nav2_core",
"nav2_core::NavigatorBase")
40 RCLCPP_INFO(get_logger(),
"Creating");
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")));
58 nav2_util::CallbackReturn
61 RCLCPP_INFO(get_logger(),
"Configuring");
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);
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();
76 std::vector<std::string> plugin_lib_names;
77 plugin_lib_names = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS,
';');
79 auto user_defined_plugins = get_parameter(
"plugin_lib_names").as_string_array();
81 plugin_lib_names.insert(
82 plugin_lib_names.end(), user_defined_plugins.begin(),
83 user_defined_plugins.end());
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_;
93 odom_smoother_ = std::make_shared<nav2_util::OdomSmoother>(node, 0.3, odom_topic_);
96 const std::vector<std::string> default_navigator_ids = {
98 "navigate_through_poses"
100 const std::vector<std::string> default_navigator_types = {
101 "nav2_bt_navigator::NavigateToPoseNavigator",
102 "nav2_bt_navigator::NavigateThroughPosesNavigator"
105 std::vector<std::string> navigator_ids;
106 declare_parameter_if_not_declared(
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]));
119 for (
size_t i = 0; i != navigator_ids.size(); i++) {
121 std::string navigator_type = nav2_util::get_plugin_type_param(node, navigator_ids[i]);
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_))
130 return nav2_util::CallbackReturn::FAILURE;
132 }
catch (
const std::exception & ex) {
134 get_logger(),
"Failed to create navigator id %s."
135 " Exception: %s", navigator_ids[i].c_str(), ex.what());
137 return nav2_util::CallbackReturn::FAILURE;
141 return nav2_util::CallbackReturn::SUCCESS;
144 nav2_util::CallbackReturn
147 RCLCPP_INFO(get_logger(),
"Activating");
148 for (
size_t i = 0; i != navigators_.size(); i++) {
151 return nav2_util::CallbackReturn::FAILURE;
158 return nav2_util::CallbackReturn::SUCCESS;
161 nav2_util::CallbackReturn
164 RCLCPP_INFO(get_logger(),
"Deactivating");
165 for (
size_t i = 0; i != navigators_.size(); i++) {
167 return nav2_util::CallbackReturn::FAILURE;
174 return nav2_util::CallbackReturn::SUCCESS;
177 nav2_util::CallbackReturn
180 RCLCPP_INFO(get_logger(),
"Cleaning up");
183 tf_listener_.reset();
186 for (
size_t i = 0; i != navigators_.size(); i++) {
188 return nav2_util::CallbackReturn::FAILURE;
193 RCLCPP_INFO(get_logger(),
"Completed Cleaning up");
194 return nav2_util::CallbackReturn::SUCCESS;
197 nav2_util::CallbackReturn
200 RCLCPP_INFO(get_logger(),
"Shutting down");
201 return nav2_util::CallbackReturn::SUCCESS;
206 #include "rclcpp_components/register_node_macro.hpp"
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.