15 #ifndef NAV2_CORE__BEHAVIOR_TREE_NAVIGATOR_HPP_
16 #define NAV2_CORE__BEHAVIOR_TREE_NAVIGATOR_HPP_
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"
39 std::string robot_frame;
40 std::string global_frame;
41 double transform_tolerance;
42 std::shared_ptr<tf2_ros::Buffer> tf;
57 : current_navigator_(std::string(
"")) {}
65 std::scoped_lock l(mutex_);
66 return !current_navigator_.empty();
75 std::scoped_lock l(mutex_);
76 if (!current_navigator_.empty()) {
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.");
83 current_navigator_ = navigator_name;
92 std::scoped_lock l(mutex_);
93 if (current_navigator_ != navigator_name) {
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.");
100 current_navigator_ = std::string(
"");
105 std::string current_navigator_;
127 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
128 const std::vector<std::string> & plugin_lib_names,
131 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) = 0;
158 template<
class ActionT>
162 using Ptr = std::shared_ptr<nav2_core::BehaviorTreeNavigator<ActionT>>;
170 plugin_muxer_ =
nullptr;
189 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
190 const std::vector<std::string> & plugin_lib_names,
193 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
final
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;
202 std::string default_bt_xml_filename = getDefaultBTFilepath(parent_node);
205 bt_action_server_ = std::make_unique<nav2_behavior_tree::BtActionServer<ActionT>>(
209 default_bt_xml_filename,
215 std::placeholders::_1, std::placeholders::_2));
218 if (!bt_action_server_->on_configure()) {
222 BT::Blackboard::Ptr blackboard = bt_action_server_->getBlackboard();
223 blackboard->set(
"tf_buffer", feedback_utils.tf);
224 blackboard->set(
"initial_pose_received",
false);
225 blackboard->set(
"number_recoveries", 0);
226 blackboard->set(
"odom_smoother", odom_smoother);
228 return configure(parent_node, odom_smoother) && ok;
239 if (!bt_action_server_->on_activate()) {
253 if (!bt_action_server_->on_deactivate()) {
267 if (!bt_action_server_->on_cleanup()) {
271 bt_action_server_.reset();
276 virtual std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) = 0;
293 "Requested navigation from %s while another navigator is processing,"
294 " rejecting request.",
getName().c_str());
304 return goal_accepted;
311 typename ActionT::Result::SharedPtr result,
312 const nav2_behavior_tree::BtStatus final_bt_status)
323 virtual bool goalReceived(
typename ActionT::Goal::ConstSharedPtr goal) = 0;
334 virtual void onPreempt(
typename ActionT::Goal::ConstSharedPtr goal) = 0;
341 typename ActionT::Result::SharedPtr result,
342 const nav2_behavior_tree::BtStatus final_bt_status) = 0;
348 rclcpp_lifecycle::LifecycleNode::WeakPtr ,
349 std::shared_ptr<nav2_util::OdomSmoother>)
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_;
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.