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")));
52 declare_parameter_if_not_declared(
53 this,
"filter_duration", rclcpp::ParameterValue(0.3));
60 nav2_util::CallbackReturn
63 RCLCPP_INFO(get_logger(),
"Configuring");
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);
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();
79 std::vector<std::string> plugin_lib_names;
80 plugin_lib_names = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS,
';');
82 auto user_defined_plugins = get_parameter(
"plugin_lib_names").as_string_array();
84 plugin_lib_names.insert(
85 plugin_lib_names.end(), user_defined_plugins.begin(),
86 user_defined_plugins.end());
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_;
96 odom_smoother_ = std::make_shared<nav2_util::OdomSmoother>(node, filter_duration_, odom_topic_);
99 const std::vector<std::string> default_navigator_ids = {
101 "navigate_through_poses"
103 const std::vector<std::string> default_navigator_types = {
104 "nav2_bt_navigator::NavigateToPoseNavigator",
105 "nav2_bt_navigator::NavigateThroughPosesNavigator"
108 std::vector<std::string> navigator_ids;
109 declare_parameter_if_not_declared(
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]));
122 for (
size_t i = 0; i != navigator_ids.size(); i++) {
124 std::string navigator_type = nav2_util::get_plugin_type_param(node, navigator_ids[i]);
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_))
133 return nav2_util::CallbackReturn::FAILURE;
135 }
catch (
const std::exception & ex) {
137 get_logger(),
"Failed to create navigator id %s."
138 " Exception: %s", navigator_ids[i].c_str(), ex.what());
140 return nav2_util::CallbackReturn::FAILURE;
144 return nav2_util::CallbackReturn::SUCCESS;
147 nav2_util::CallbackReturn
150 RCLCPP_INFO(get_logger(),
"Activating");
151 for (
size_t i = 0; i != navigators_.size(); i++) {
154 return nav2_util::CallbackReturn::FAILURE;
161 return nav2_util::CallbackReturn::SUCCESS;
164 nav2_util::CallbackReturn
167 RCLCPP_INFO(get_logger(),
"Deactivating");
168 for (
size_t i = 0; i != navigators_.size(); i++) {
170 return nav2_util::CallbackReturn::FAILURE;
177 return nav2_util::CallbackReturn::SUCCESS;
180 nav2_util::CallbackReturn
183 RCLCPP_INFO(get_logger(),
"Cleaning up");
186 tf_listener_.reset();
189 for (
size_t i = 0; i != navigators_.size(); i++) {
191 return nav2_util::CallbackReturn::FAILURE;
196 RCLCPP_INFO(get_logger(),
"Completed Cleaning up");
197 return nav2_util::CallbackReturn::SUCCESS;
200 nav2_util::CallbackReturn
203 RCLCPP_INFO(get_logger(),
"Shutting down");
204 return nav2_util::CallbackReturn::SUCCESS;
209 #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.