Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
navigator.hpp
1 // Copyright (c) 2021 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_BT_NAVIGATOR__NAVIGATOR_HPP_
16 #define NAV2_BT_NAVIGATOR__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_bt_navigator
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 
113 template<class ActionT>
115 {
116 public:
117  using Ptr = std::shared_ptr<nav2_bt_navigator::Navigator<ActionT>>;
118 
123  {
124  plugin_muxer_ = nullptr;
125  }
126 
130  virtual ~Navigator() = default;
131 
143  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
144  const std::vector<std::string> & plugin_lib_names,
145  const FeedbackUtils & feedback_utils,
146  nav2_bt_navigator::NavigatorMuxer * plugin_muxer,
147  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
148  {
149  auto node = parent_node.lock();
150  logger_ = node->get_logger();
151  clock_ = node->get_clock();
152  feedback_utils_ = feedback_utils;
153  plugin_muxer_ = plugin_muxer;
154 
155  // get the default behavior tree for this navigator
156  std::string default_bt_xml_filename = getDefaultBTFilepath(parent_node);
157 
158  // Create the Behavior Tree Action Server for this navigator
159  bt_action_server_ = std::make_unique<nav2_behavior_tree::BtActionServer<ActionT>>(
160  node,
161  getName(),
162  plugin_lib_names,
163  default_bt_xml_filename,
164  std::bind(&Navigator::onGoalReceived, this, std::placeholders::_1),
165  std::bind(&Navigator::onLoop, this),
166  std::bind(&Navigator::onPreempt, this, std::placeholders::_1),
167  std::bind(&Navigator::onCompletion, this, std::placeholders::_1, std::placeholders::_2));
168 
169  bool ok = true;
170  if (!bt_action_server_->on_configure()) {
171  ok = false;
172  }
173 
174  BT::Blackboard::Ptr blackboard = bt_action_server_->getBlackboard();
175  blackboard->set<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer", feedback_utils.tf); // NOLINT
176  blackboard->set<bool>("initial_pose_received", false); // NOLINT
177  blackboard->set<int>("number_recoveries", 0); // NOLINT
178  blackboard->set<std::shared_ptr<nav2_util::OdomSmoother>>("odom_smoother", odom_smoother); // NOLINT
179 
180  return configure(parent_node, odom_smoother) && ok;
181  }
182 
187  bool on_activate()
188  {
189  bool ok = true;
190 
191  if (!bt_action_server_->on_activate()) {
192  ok = false;
193  }
194 
195  return activate() && ok;
196  }
197 
203  {
204  bool ok = true;
205  if (!bt_action_server_->on_deactivate()) {
206  ok = false;
207  }
208 
209  return deactivate() && ok;
210  }
211 
216  bool on_cleanup()
217  {
218  bool ok = true;
219  if (!bt_action_server_->on_cleanup()) {
220  ok = false;
221  }
222 
223  bt_action_server_.reset();
224 
225  return cleanup() && ok;
226  }
227 
232  virtual std::string getName() = 0;
233 
234  virtual std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) = 0;
235 
240  std::unique_ptr<nav2_behavior_tree::BtActionServer<ActionT>> & getActionServer()
241  {
242  return bt_action_server_;
243  }
244 
245 protected:
249  bool onGoalReceived(typename ActionT::Goal::ConstSharedPtr goal)
250  {
251  if (plugin_muxer_->isNavigating()) {
252  RCLCPP_ERROR(
253  logger_,
254  "Requested navigation from %s while another navigator is processing,"
255  " rejecting request.", getName().c_str());
256  return false;
257  }
258 
259  bool goal_accepted = goalReceived(goal);
260 
261  if (goal_accepted) {
262  plugin_muxer_->startNavigating(getName());
263  }
264 
265  return goal_accepted;
266  }
267 
272  typename ActionT::Result::SharedPtr result,
273  const nav2_behavior_tree::BtStatus final_bt_status)
274  {
275  plugin_muxer_->stopNavigating(getName());
276  goalCompleted(result, final_bt_status);
277  }
278 
284  virtual bool goalReceived(typename ActionT::Goal::ConstSharedPtr goal) = 0;
285 
290  virtual void onLoop() = 0;
291 
295  virtual void onPreempt(typename ActionT::Goal::ConstSharedPtr goal) = 0;
296 
301  virtual void goalCompleted(
302  typename ActionT::Result::SharedPtr result,
303  const nav2_behavior_tree::BtStatus final_bt_status) = 0;
304 
308  virtual bool configure(
309  rclcpp_lifecycle::LifecycleNode::WeakPtr /*node*/,
310  std::shared_ptr<nav2_util::OdomSmoother>/*odom_smoother*/)
311  {
312  return true;
313  }
314 
318  virtual bool cleanup() {return true;}
319 
323  virtual bool activate() {return true;}
324 
328  virtual bool deactivate() {return true;}
329 
330  std::unique_ptr<nav2_behavior_tree::BtActionServer<ActionT>> bt_action_server_;
331  rclcpp::Logger logger_{rclcpp::get_logger("Navigator")};
332  rclcpp::Clock::SharedPtr clock_;
333  FeedbackUtils feedback_utils_;
334  NavigatorMuxer * plugin_muxer_;
335 };
336 
337 } // namespace nav2_bt_navigator
338 
339 #endif // NAV2_BT_NAVIGATOR__NAVIGATOR_HPP_
A class to control the state of the BT navigator by allowing only a single plugin to be processed at ...
Definition: navigator.hpp:51
NavigatorMuxer()
A Navigator Muxer constructor.
Definition: navigator.hpp:56
bool isNavigating()
Get the navigator muxer state.
Definition: navigator.hpp:63
void startNavigating(const std::string &navigator_name)
Start navigating with a given navigator.
Definition: navigator.hpp:73
void stopNavigating(const std::string &navigator_name)
Stop navigating with a given navigator.
Definition: navigator.hpp:90
Navigator interface that acts as a base class for all BT-based Navigator action's plugins.
Definition: navigator.hpp:115
bool on_deactivate()
Deactivation of the navigator's backend BT and actions.
Definition: navigator.hpp:202
bool onGoalReceived(typename ActionT::Goal::ConstSharedPtr goal)
An intermediate goal reception function to mux navigators.
Definition: navigator.hpp:249
virtual bool deactivate()
Method to deactivate and any threads involved in execution.
Definition: navigator.hpp:328
virtual std::string getName()=0
Get the action name of this navigator to expose.
virtual void onPreempt(typename ActionT::Goal::ConstSharedPtr goal)=0
A callback that is called when a preempt is requested.
virtual ~Navigator()=default
Virtual destructor.
void onCompletion(typename ActionT::Result::SharedPtr result, const nav2_behavior_tree::BtStatus final_bt_status)
An intermediate completion function to mux navigators.
Definition: navigator.hpp:271
virtual bool cleanup()
Method to cleanup resources.
Definition: navigator.hpp:318
bool on_activate()
Activation of the navigator's backend BT and actions.
Definition: navigator.hpp:187
virtual void onLoop()=0
A callback that defines execution that happens on one iteration through the BT Can be used to publish...
bool on_cleanup()
Cleanup a navigator.
Definition: navigator.hpp:216
virtual bool activate()
Method to activate any threads involved in execution.
Definition: navigator.hpp:323
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...
bool on_configure(rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node, const std::vector< std::string > &plugin_lib_names, const FeedbackUtils &feedback_utils, nav2_bt_navigator::NavigatorMuxer *plugin_muxer, std::shared_ptr< nav2_util::OdomSmoother > odom_smoother)
Configuration to setup the navigator's backend BT and actions.
Definition: navigator.hpp:142
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...
Navigator()
A Navigator constructor.
Definition: navigator.hpp:122
virtual bool configure(rclcpp_lifecycle::LifecycleNode::WeakPtr, std::shared_ptr< nav2_util::OdomSmoother >)
Definition: navigator.hpp:308
std::unique_ptr< nav2_behavior_tree::BtActionServer< ActionT > > & getActionServer()
Get the action server.
Definition: navigator.hpp:240
Navigator feedback utilities required to get transforms and reference frames.
Definition: navigator.hpp:38