15 #ifndef NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_HPP_
24 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav2_behavior_tree/behavior_tree_engine.hpp"
26 #include "nav2_behavior_tree/ros_topic_logger.hpp"
27 #include "nav2_ros_common/lifecycle_node.hpp"
28 #include "nav2_ros_common/simple_action_server.hpp"
30 namespace nav2_behavior_tree
36 template<
class ActionT,
class NodeT>
42 typedef std::function<bool (
typename ActionT::Goal::ConstSharedPtr)> OnGoalReceivedCallback;
43 typedef std::function<void ()> OnLoopCallback;
44 typedef std::function<void (
typename ActionT::Goal::ConstSharedPtr)> OnPreemptCallback;
45 typedef std::function<void (
typename ActionT::Result::SharedPtr,
46 nav2_behavior_tree::BtStatus)> OnCompletionCallback;
52 const typename NodeT::WeakPtr & parent,
53 const std::string & action_name,
54 const std::vector<std::string> & plugin_lib_names,
55 const std::string & default_bt_xml_filename,
56 OnGoalReceivedCallback on_goal_received_callback,
57 OnLoopCallback on_loop_callback,
58 OnPreemptCallback on_preempt_callback,
59 OnCompletionCallback on_completion_callback,
60 const std::vector<std::string> & search_directories = std::vector<std::string>{});
107 const std::string & bt_xml_filename_or_id =
"");
130 return current_bt_file_or_id_;
139 return default_bt_xml_filename_or_id_;
148 return action_server_->accept_pending_goal();
156 action_server_->terminate_pending_goal();
165 return action_server_->get_current_goal();
174 return action_server_->get_pending_goal();
182 action_server_->publish_feedback(feedback);
234 void populateErrorCode(
typename std::shared_ptr<typename ActionT::Result> result);
242 std::string action_name_;
245 typename ActionServer::SharedPtr action_server_;
251 BT::Blackboard::Ptr blackboard_;
254 std::string current_bt_file_or_id_;
255 std::string default_bt_xml_filename_or_id_;
256 std::vector<std::string> search_directories_;
259 std::unique_ptr<nav2_behavior_tree::BehaviorTreeEngine> bt_;
262 std::vector<std::string> plugin_lib_names_;
265 std::vector<std::string> error_code_name_prefixes_;
268 nav2::LifecycleNode::SharedPtr client_node_;
271 typename NodeT::WeakPtr node_;
274 rclcpp::Clock::SharedPtr clock_;
277 rclcpp::Logger logger_{rclcpp::get_logger(
"BtActionServer")};
280 std::unique_ptr<RosTopicLogger> topic_logger_;
283 std::chrono::milliseconds bt_loop_duration_;
286 std::chrono::milliseconds default_server_timeout_;
289 std::chrono::milliseconds wait_for_service_timeout_;
292 bool always_reload_bt_ =
false;
295 bool enable_groot_monitoring_ =
false;
296 int groot_server_port_ = 1667;
299 OnGoalReceivedCallback on_goal_received_callback_;
300 OnLoopCallback on_loop_callback_;
301 OnPreemptCallback on_preempt_callback_;
302 OnCompletionCallback on_completion_callback_;
305 uint16_t internal_error_code_;
306 std::string internal_error_msg_;
311 #include <nav2_behavior_tree/bt_action_server_impl.hpp>
An action server wrapper to make applications simpler using Actions.
An action server that uses behavior tree to execute an action.
std::string extractBehaviorTreeID(const std::string &file_or_id)
Extract BehaviorTree ID from XML file.
BtActionServer(const typename NodeT::WeakPtr &parent, const std::string &action_name, const std::vector< std::string > &plugin_lib_names, const std::string &default_bt_xml_filename, OnGoalReceivedCallback on_goal_received_callback, OnLoopCallback on_loop_callback, OnPreemptCallback on_preempt_callback, OnCompletionCallback on_completion_callback, const std::vector< std::string > &search_directories=std::vector< std::string >{})
A constructor for nav2_behavior_tree::BtActionServer class.
bool on_cleanup()
Resets member variables.
void setGrootMonitoring(const bool enable, const unsigned server_port)
Enable (or disable) Groot2 monitoring of BT.
const std::shared_ptr< const typename ActionT::Goal > acceptPendingGoal()
Wrapper function to accept pending goal if a preempt has been requested.
bool loadBehaviorTree(const std::string &bt_xml_filename_or_id="")
Replace current BT with another one.
void haltTree()
Function to halt the current tree. It will interrupt the execution of RUNNING nodes by calling their ...
BT::Blackboard::Ptr getBlackboard() const
Getter function for BT Blackboard.
bool populateInternalError(typename std::shared_ptr< typename ActionT::Result > result)
populate result with internal error code and error_msg if not NONE
bool on_deactivate()
Deactivates action server.
const std::shared_ptr< const typename ActionT::Goal > getCurrentGoal() const
Wrapper function to get current goal.
~BtActionServer()
A destructor for nav2_behavior_tree::BtActionServer class.
const BT::Tree & getTree() const
Getter function for the current BT tree.
bool on_configure()
Configures member variables Initializes action server for, builds behavior tree from xml file,...
const std::shared_ptr< const typename ActionT::Goal > getPendingGoal() const
Wrapper function to get pending goal.
void terminatePendingGoal()
Wrapper function to terminate pending goal if a preempt has been requested.
std::string getDefaultBTFilenameOrID() const
Getter function for default BT XML filename or ID.
void publishFeedback(typename std::shared_ptr< typename ActionT::Feedback > feedback)
Wrapper function to publish action feedback.
void resetInternalError(void)
reset internal error code and message
void executeCallback()
Action server callback.
void cleanErrorCodes()
Setting BT error codes to success. Used to clean blackboard between different BT runs.
void populateErrorCode(typename std::shared_ptr< typename ActionT::Result > result)
updates the action server result to the highest priority error code posted on the blackboard
bool on_activate()
Activates action server.
std::string getCurrentBTFilenameOrID() const
Getter function for current BT XML filename.
void setInternalError(uint16_t error_code, const std::string &error_msg)
Set internal error code and message.