Template Class BtActionNode

Inheritance Relationships

Base Type

  • public BT::ActionNodeBase

Class Documentation

template<class ActionT>
class BtActionNode : public BT::ActionNodeBase

Abstract class representing an action based BT node.

Template Parameters:

ActionT – Type of action

Public Functions

inline BtActionNode(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)

A nav2_behavior_tree::BtActionNode constructor.

Parameters:
  • xml_tag_name – Name for the XML tag for this node

  • action_name – Action name this node creates a client for

  • conf – BT node configuration

BtActionNode() = delete
inline virtual ~BtActionNode()
inline void createActionClient(const std::string &action_name)

Create instance of an action client.

Parameters:

action_name – Action name to create client for

inline virtual void on_tick()

Function to perform some user-defined operation on tick Could do dynamic checks, such as getting updates to values on the blackboard.

inline virtual void on_wait_for_result(std::shared_ptr<const typename ActionT::Feedback>)

Function to perform some user-defined operation after a timeout waiting for a result that hasn’t been received yet. Also provides access to the latest feedback message from the action server. Feedback will be nullptr in subsequent calls to this function if no new feedback is received while waiting for a result.

Parameters:

feedback – shared_ptr to latest feedback message, nullptr if no new feedback was received

inline virtual BT::NodeStatus on_success()

Function to perform some user-defined operation upon successful completion of the action. Could put a value on the blackboard.

Returns:

BT::NodeStatus Returns SUCCESS by default, user may override return another value

inline virtual BT::NodeStatus on_aborted()

Function to perform some user-defined operation when the action is aborted.

Returns:

BT::NodeStatus Returns FAILURE by default, user may override return another value

inline virtual BT::NodeStatus on_cancelled()

Function to perform some user-defined operation when the action is cancelled.

Returns:

BT::NodeStatus Returns SUCCESS by default, user may override return another value

inline BT::NodeStatus tick() override

The main override required by a BT action.

Returns:

BT::NodeStatus Status of tick execution

inline void halt() override

The other (optional) override required by a BT action. In this case, we make sure to cancel the ROS2 action if it is still running.

Public Static Functions

static inline BT::PortsList providedBasicPorts(BT::PortsList addition)

Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call providedBasicPorts in it.

Parameters:

addition – Additional ports to add to BT port list

Returns:

BT::PortsList Containing basic ports along with node-specific ports

static inline BT::PortsList providedPorts()

Creates list of BT ports.

Returns:

BT::PortsList Containing basic ports along with node-specific ports

Protected Functions

inline bool should_cancel_goal()

Function to check if current goal should be cancelled.

Returns:

bool True if current goal should be cancelled, false otherwise

inline void send_new_goal()

Function to send new goal to action server.

inline bool is_future_goal_handle_complete(std::chrono::milliseconds &elapsed)

Function to check if the action server acknowledged a new goal.

Parameters:

elapsed – Duration since the last goal was sent and future goal handle has not completed. After waiting for the future to complete, this value is incremented with the timeout value.

Returns:

boolean True if future_goal_handle_ returns SUCCESS, False otherwise

inline void increment_recovery_count()

Function to increment recovery count on blackboard if this node wraps a recovery.

Protected Attributes

std::string action_name_
std::shared_ptr<rclcpp_action::Client<ActionT>> action_client_
ActionT::Goal goal_
bool goal_updated_ = {false}
bool goal_result_available_ = {false}
rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr goal_handle_
rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult result_
std::shared_ptr<const typename ActionT::Feedback> feedback_
rclcpp::Node::SharedPtr node_
rclcpp::CallbackGroup::SharedPtr callback_group_
rclcpp::executors::SingleThreadedExecutor callback_group_executor_
std::chrono::milliseconds server_timeout_
std::chrono::milliseconds bt_loop_duration_
std::shared_ptr<std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>> future_goal_handle_
rclcpp::Time time_goal_sent_
bool should_send_goal_