Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
behavior_tree_navigator.hpp
1 // Copyright (c) 2021-2023 Samsung Research America
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 #ifndef NAV2_CORE__BEHAVIOR_TREE_NAVIGATOR_HPP_
16 #define NAV2_CORE__BEHAVIOR_TREE_NAVIGATOR_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 #include <mutex>
22 
23 #include "nav2_util/odometry_utils.hpp"
24 #include "tf2_ros/buffer.h"
25 #include "rclcpp/rclcpp.hpp"
26 #include "rclcpp_lifecycle/lifecycle_node.hpp"
27 #include "pluginlib/class_loader.hpp"
28 #include "nav2_behavior_tree/bt_action_server.hpp"
29 
30 namespace nav2_core
31 {
32 
38 {
39  std::string robot_frame;
40  std::string global_frame;
41  double transform_tolerance;
42  std::shared_ptr<tf2_ros::Buffer> tf;
43 };
44 
51 {
52 public:
57  : current_navigator_(std::string("")) {}
58 
63  bool isNavigating()
64  {
65  std::scoped_lock l(mutex_);
66  return !current_navigator_.empty();
67  }
68 
73  void startNavigating(const std::string & navigator_name)
74  {
75  std::scoped_lock l(mutex_);
76  if (!current_navigator_.empty()) {
77  RCLCPP_ERROR(
78  rclcpp::get_logger("NavigatorMutex"),
79  "Major error! Navigation requested while another navigation"
80  " task is in progress! This likely occurred from an incorrect"
81  "implementation of a navigator plugin.");
82  }
83  current_navigator_ = navigator_name;
84  }
85 
90  void stopNavigating(const std::string & navigator_name)
91  {
92  std::scoped_lock l(mutex_);
93  if (current_navigator_ != navigator_name) {
94  RCLCPP_ERROR(
95  rclcpp::get_logger("NavigatorMutex"),
96  "Major error! Navigation stopped while another navigation"
97  " task is in progress! This likely occurred from an incorrect"
98  "implementation of a navigator plugin.");
99  } else {
100  current_navigator_ = std::string("");
101  }
102  }
103 
104 protected:
105  std::string current_navigator_;
106  std::mutex mutex_;
107 };
108 
117 {
118 public:
119  NavigatorBase() = default;
120  virtual ~NavigatorBase() = default;
121 
126  virtual bool on_configure(
127  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
128  const std::vector<std::string> & plugin_lib_names,
129  const FeedbackUtils & feedback_utils,
130  nav2_core::NavigatorMuxer * plugin_muxer,
131  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) = 0;
132 
137  virtual bool on_activate() = 0;
138 
143  virtual bool on_deactivate() = 0;
144 
149  virtual bool on_cleanup() = 0;
150 };
151 
158 template<class ActionT>
160 {
161 public:
162  using Ptr = std::shared_ptr<nav2_core::BehaviorTreeNavigator<ActionT>>;
163 
168  : NavigatorBase()
169  {
170  plugin_muxer_ = nullptr;
171  }
172 
176  virtual ~BehaviorTreeNavigator() = default;
177 
189  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
190  const std::vector<std::string> & plugin_lib_names,
191  const FeedbackUtils & feedback_utils,
192  nav2_core::NavigatorMuxer * plugin_muxer,
193  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) final
194  {
195  auto node = parent_node.lock();
196  logger_ = node->get_logger();
197  clock_ = node->get_clock();
198  feedback_utils_ = feedback_utils;
199  plugin_muxer_ = plugin_muxer;
200 
201  // get the default behavior tree for this navigator
202  std::string default_bt_xml_filename = getDefaultBTFilepath(parent_node);
203 
204  // Create the Behavior Tree Action Server for this navigator
205  bt_action_server_ = std::make_unique<nav2_behavior_tree::BtActionServer<ActionT>>(
206  node,
207  getName(),
208  plugin_lib_names,
209  default_bt_xml_filename,
210  std::bind(&BehaviorTreeNavigator::onGoalReceived, this, std::placeholders::_1),
211  std::bind(&BehaviorTreeNavigator::onLoop, this),
212  std::bind(&BehaviorTreeNavigator::onPreempt, this, std::placeholders::_1),
213  std::bind(
215  std::placeholders::_1, std::placeholders::_2));
216 
217  bool ok = true;
218  if (!bt_action_server_->on_configure()) {
219  ok = false;
220  }
221 
222  BT::Blackboard::Ptr blackboard = bt_action_server_->getBlackboard();
223  blackboard->set("tf_buffer", feedback_utils.tf); // NOLINT
224  blackboard->set("initial_pose_received", false); // NOLINT
225  blackboard->set("number_recoveries", 0); // NOLINT
226  blackboard->set("odom_smoother", odom_smoother); // NOLINT
227 
228  return configure(parent_node, odom_smoother) && ok;
229  }
230 
235  bool on_activate() final
236  {
237  bool ok = true;
238 
239  if (!bt_action_server_->on_activate()) {
240  ok = false;
241  }
242 
243  return activate() && ok;
244  }
245 
250  bool on_deactivate() final
251  {
252  bool ok = true;
253  if (!bt_action_server_->on_deactivate()) {
254  ok = false;
255  }
256 
257  return deactivate() && ok;
258  }
259 
264  bool on_cleanup() final
265  {
266  bool ok = true;
267  if (!bt_action_server_->on_cleanup()) {
268  ok = false;
269  }
270 
271  bt_action_server_.reset();
272 
273  return cleanup() && ok;
274  }
275 
276  virtual std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) = 0;
277 
282  virtual std::string getName() = 0;
283 
284 protected:
288  bool onGoalReceived(typename ActionT::Goal::ConstSharedPtr goal)
289  {
290  if (plugin_muxer_->isNavigating()) {
291  RCLCPP_ERROR(
292  logger_,
293  "Requested navigation from %s while another navigator is processing,"
294  " rejecting request.", getName().c_str());
295  return false;
296  }
297 
298  bool goal_accepted = goalReceived(goal);
299 
300  if (goal_accepted) {
301  plugin_muxer_->startNavigating(getName());
302  }
303 
304  return goal_accepted;
305  }
306 
311  typename ActionT::Result::SharedPtr result,
312  const nav2_behavior_tree::BtStatus final_bt_status)
313  {
314  plugin_muxer_->stopNavigating(getName());
315  goalCompleted(result, final_bt_status);
316  }
317 
323  virtual bool goalReceived(typename ActionT::Goal::ConstSharedPtr goal) = 0;
324 
329  virtual void onLoop() = 0;
330 
334  virtual void onPreempt(typename ActionT::Goal::ConstSharedPtr goal) = 0;
335 
340  virtual void goalCompleted(
341  typename ActionT::Result::SharedPtr result,
342  const nav2_behavior_tree::BtStatus final_bt_status) = 0;
343 
347  virtual bool configure(
348  rclcpp_lifecycle::LifecycleNode::WeakPtr /*node*/,
349  std::shared_ptr<nav2_util::OdomSmoother>/*odom_smoother*/)
350  {
351  return true;
352  }
353 
357  virtual bool cleanup() {return true;}
358 
362  virtual bool activate() {return true;}
363 
367  virtual bool deactivate() {return true;}
368 
369  std::unique_ptr<nav2_behavior_tree::BtActionServer<ActionT>> bt_action_server_;
370  rclcpp::Logger logger_{rclcpp::get_logger("Navigator")};
371  rclcpp::Clock::SharedPtr clock_;
372  FeedbackUtils feedback_utils_;
373  NavigatorMuxer * plugin_muxer_;
374 };
375 
376 } // namespace nav2_core
377 
378 #endif // NAV2_CORE__BEHAVIOR_TREE_NAVIGATOR_HPP_
Navigator interface that acts as a base class for all BT-based Navigator action's plugins All methods...
virtual void goalCompleted(typename ActionT::Result::SharedPtr result, const nav2_behavior_tree::BtStatus final_bt_status)=0
A callback that is called when a the action is completed; Can fill in action result message or indica...
virtual void onPreempt(typename ActionT::Goal::ConstSharedPtr goal)=0
A callback that is called when a preempt is requested.
BehaviorTreeNavigator()
A Navigator constructor.
virtual ~BehaviorTreeNavigator()=default
Virtual destructor.
virtual std::string getName()=0
Get the action name of this navigator to expose.
bool onGoalReceived(typename ActionT::Goal::ConstSharedPtr goal)
An intermediate goal reception function to mux navigators.
bool on_cleanup() final
Cleanup a navigator.
void onCompletion(typename ActionT::Result::SharedPtr result, const nav2_behavior_tree::BtStatus final_bt_status)
An intermediate completion function to mux navigators.
virtual bool deactivate()
Method to deactivate and any threads involved in execution.
virtual void onLoop()=0
A callback that defines execution that happens on one iteration through the BT Can be used to publish...
virtual bool activate()
Method to activate any threads involved in execution.
bool on_deactivate() final
Deactivation of the navigator's backend BT and actions.
virtual bool cleanup()
Method to cleanup resources.
bool on_configure(rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node, const std::vector< std::string > &plugin_lib_names, const FeedbackUtils &feedback_utils, nav2_core::NavigatorMuxer *plugin_muxer, std::shared_ptr< nav2_util::OdomSmoother > odom_smoother) final
Configuration to setup the navigator's backend BT and actions.
virtual bool goalReceived(typename ActionT::Goal::ConstSharedPtr goal)=0
A callback to be called when a new goal is received by the BT action server Can be used to check if g...
bool on_activate() final
Activation of the navigator's backend BT and actions.
virtual bool configure(rclcpp_lifecycle::LifecycleNode::WeakPtr, std::shared_ptr< nav2_util::OdomSmoother >)
Navigator interface to allow navigators to be stored in a vector and accessed via pluginlib due to te...
virtual bool on_cleanup()=0
Cleanup a navigator.
virtual bool on_configure(rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node, const std::vector< std::string > &plugin_lib_names, const FeedbackUtils &feedback_utils, nav2_core::NavigatorMuxer *plugin_muxer, std::shared_ptr< nav2_util::OdomSmoother > odom_smoother)=0
Configuration of the navigator's backend BT and actions.
virtual bool on_deactivate()=0
Deactivation of the navigator's backend BT and actions.
virtual bool on_activate()=0
Activation of the navigator's backend BT and actions.
A class to control the state of the BT navigator by allowing only a single plugin to be processed at ...
void startNavigating(const std::string &navigator_name)
Start navigating with a given navigator.
void stopNavigating(const std::string &navigator_name)
Stop navigating with a given navigator.
bool isNavigating()
Get the navigator muxer state.
NavigatorMuxer()
A Navigator Muxer constructor.
Navigator feedback utilities required to get transforms and reference frames.