15 #ifndef NAV2_BT_NAVIGATOR__NAVIGATOR_HPP_
16 #define NAV2_BT_NAVIGATOR__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"
30 namespace nav2_bt_navigator
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_;
113 template<
class ActionT>
117 using Ptr = std::shared_ptr<nav2_bt_navigator::Navigator<ActionT>>;
124 plugin_muxer_ =
nullptr;
143 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
144 const std::vector<std::string> & plugin_lib_names,
147 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
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;
156 std::string default_bt_xml_filename = getDefaultBTFilepath(parent_node);
159 bt_action_server_ = std::make_unique<nav2_behavior_tree::BtActionServer<ActionT>>(
163 default_bt_xml_filename,
170 if (!bt_action_server_->on_configure()) {
174 BT::Blackboard::Ptr blackboard = bt_action_server_->getBlackboard();
175 blackboard->set<std::shared_ptr<tf2_ros::Buffer>>(
"tf_buffer", feedback_utils.tf);
176 blackboard->set<
bool>(
"initial_pose_received",
false);
177 blackboard->set<
int>(
"number_recoveries", 0);
178 blackboard->set<std::shared_ptr<nav2_util::OdomSmoother>>(
"odom_smoother", odom_smoother);
180 return configure(parent_node, odom_smoother) && ok;
191 if (!bt_action_server_->on_activate()) {
205 if (!bt_action_server_->on_deactivate()) {
219 if (!bt_action_server_->on_cleanup()) {
223 bt_action_server_.reset();
234 virtual std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) = 0;
242 return bt_action_server_;
254 "Requested navigation from %s while another navigator is processing,"
255 " rejecting request.",
getName().c_str());
265 return goal_accepted;
272 typename ActionT::Result::SharedPtr result,
273 const nav2_behavior_tree::BtStatus final_bt_status)
284 virtual bool goalReceived(
typename ActionT::Goal::ConstSharedPtr goal) = 0;
295 virtual void onPreempt(
typename ActionT::Goal::ConstSharedPtr goal) = 0;
302 typename ActionT::Result::SharedPtr result,
303 const nav2_behavior_tree::BtStatus final_bt_status) = 0;
309 rclcpp_lifecycle::LifecycleNode::WeakPtr ,
310 std::shared_ptr<nav2_util::OdomSmoother>)
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_;
A class to control the state of the BT navigator by allowing only a single plugin to be processed at ...
NavigatorMuxer()
A Navigator Muxer constructor.
bool isNavigating()
Get the navigator muxer state.
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.
Navigator interface that acts as a base class for all BT-based Navigator action's plugins.
bool on_deactivate()
Deactivation of the navigator's backend BT and actions.
bool onGoalReceived(typename ActionT::Goal::ConstSharedPtr goal)
An intermediate goal reception function to mux navigators.
virtual bool deactivate()
Method to deactivate and any threads involved in execution.
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.
virtual bool cleanup()
Method to cleanup resources.
bool on_activate()
Activation of the navigator's backend BT and actions.
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.
virtual bool activate()
Method to activate any threads involved in execution.
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.
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.
virtual bool configure(rclcpp_lifecycle::LifecycleNode::WeakPtr, std::shared_ptr< nav2_util::OdomSmoother >)
std::unique_ptr< nav2_behavior_tree::BtActionServer< ActionT > > & getActionServer()
Get the action server.
Navigator feedback utilities required to get transforms and reference frames.