Template Class BtActionServer

Class Documentation

template<class ActionT>
class BtActionServer

An action server that uses behavior tree to execute an action.

Public Types

using ActionServer = nav2_util::SimpleActionServer<ActionT>
typedef std::function<bool(typename ActionT::Goal::ConstSharedPtr)> OnGoalReceivedCallback
typedef std::function<void()> OnLoopCallback
typedef std::function<void(typename ActionT::Goal::ConstSharedPtr)> OnPreemptCallback
typedef std::function<void(typename ActionT::Result::SharedPtr, nav2_behavior_tree::BtStatus)> OnCompletionCallback

Public Functions

explicit BtActionServer(const rclcpp_lifecycle::LifecycleNode::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)

A constructor for nav2_behavior_tree::BtActionServer class.

~BtActionServer()

A destructor for nav2_behavior_tree::BtActionServer class.

bool on_configure()

Configures member variables Initializes action server for, builds behavior tree from xml file, and calls user-defined onConfigure.

Returns:

bool true on SUCCESS and false on FAILURE

bool on_activate()

Activates action server.

Returns:

bool true on SUCCESS and false on FAILURE

bool on_deactivate()

Deactivates action server.

Returns:

bool true on SUCCESS and false on FAILURE

bool on_cleanup()

Resets member variables.

Returns:

bool true on SUCCESS and false on FAILURE

bool loadBehaviorTree(const std::string &bt_xml_filename = "")

Replace current BT with another one.

Parameters:

bt_xml_filename – The file containing the new BT, uses default filename if empty

Returns:

bool true if the resulting BT correspond to the one in bt_xml_filename. false if something went wrong, and previous BT is maintained

inline BT::Blackboard::Ptr getBlackboard() const

Getter function for BT Blackboard.

Returns:

BT::Blackboard::Ptr Shared pointer to current BT blackboard

inline std::string getCurrentBTFilename() const

Getter function for current BT XML filename.

Returns:

string Containing current BT XML filename

inline std::string getDefaultBTFilename() const

Getter function for default BT XML filename.

Returns:

string Containing default BT XML filename

inline const std::shared_ptr<const typename ActionT::Goal> acceptPendingGoal()

Wrapper function to accept pending goal if a preempt has been requested.

Returns:

Shared pointer to pending action goal

inline void terminatePendingGoal()

Wrapper function to terminate pending goal if a preempt has been requested.

inline const std::shared_ptr<const typename ActionT::Goal> getCurrentGoal() const

Wrapper function to get current goal.

Returns:

Shared pointer to current action goal

inline const std::shared_ptr<const typename ActionT::Goal> getPendingGoal() const

Wrapper function to get pending goal.

Returns:

Shared pointer to pending action goal

inline void publishFeedback(typename std::shared_ptr<typename ActionT::Feedback> feedback)

Wrapper function to publish action feedback.

inline const BT::Tree &getTree() const

Getter function for the current BT tree.

Returns:

BT::Tree Current behavior tree

inline void haltTree()

Function to halt the current tree. It will interrupt the execution of RUNNING nodes by calling their halt() implementation (only for Async nodes that may return RUNNING)

Protected Functions

void executeCallback()

Action server callback.

Protected Attributes

std::string action_name_
std::shared_ptr<ActionServer> action_server_
BT::Tree tree_
BT::Blackboard::Ptr blackboard_
std::string current_bt_xml_filename_
std::string default_bt_xml_filename_
std::unique_ptr<nav2_behavior_tree::BehaviorTreeEngine> bt_
std::vector<std::string> plugin_lib_names_
rclcpp::Node::SharedPtr client_node_
rclcpp_lifecycle::LifecycleNode::WeakPtr node_
rclcpp::Clock::SharedPtr clock_
rclcpp::Logger logger_ = {rclcpp::get_logger("BtActionServer")}
std::unique_ptr<RosTopicLogger> topic_logger_
std::chrono::milliseconds bt_loop_duration_
std::chrono::milliseconds default_server_timeout_
OnGoalReceivedCallback on_goal_received_callback_
OnLoopCallback on_loop_callback_
OnPreemptCallback on_preempt_callback_
OnCompletionCallback on_completion_callback_