Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_behavior_tree::BtActionNode< ActionT > Class Template Reference

Abstract class representing an action based BT node. More...

#include <nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp>

Inheritance diagram for nav2_behavior_tree::BtActionNode< ActionT >:
Inheritance graph
[legend]
Collaboration diagram for nav2_behavior_tree::BtActionNode< ActionT >:
Collaboration graph
[legend]

Public Member Functions

 BtActionNode (const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
 A nav2_behavior_tree::BtActionNode constructor. More...
 
void createActionClient (const std::string &action_name)
 Create instance of an action client. More...
 
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.
 
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. More...
 
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. More...
 
virtual BT::NodeStatus on_aborted ()
 Function to perform some user-defined operation when the action is aborted. More...
 
virtual BT::NodeStatus on_cancelled ()
 Function to perform some user-defined operation when the action is cancelled. More...
 
BT::NodeStatus tick () override
 The main override required by a BT action. More...
 
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.
 

Static Public Member Functions

static BT::PortsList providedBasicPorts (BT::PortsList addition)
 Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call providedBasicPorts in it. More...
 
static BT::PortsList providedPorts ()
 Creates list of BT ports. More...
 

Protected Member Functions

bool should_cancel_goal ()
 Function to check if current goal should be cancelled. More...
 
void send_new_goal ()
 Function to send new goal to action server.
 
bool is_future_goal_handle_complete (std::chrono::milliseconds &elapsed)
 Function to check if the action server acknowledged a new goal. More...
 
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 max_timeout_
 
std::chrono::milliseconds wait_for_service_timeout_
 
std::shared_ptr< std::shared_future< typename rclcpp_action::ClientGoalHandle< ActionT >::SharedPtr > > future_goal_handle_
 
rclcpp::Time time_goal_sent_
 
bool should_send_goal_
 

Detailed Description

template<class ActionT>
class nav2_behavior_tree::BtActionNode< ActionT >

Abstract class representing an action based BT node.

Template Parameters
ActionTType of action

Definition at line 37 of file bt_action_node.hpp.

Constructor & Destructor Documentation

◆ BtActionNode()

template<class ActionT >
nav2_behavior_tree::BtActionNode< ActionT >::BtActionNode ( const std::string &  xml_tag_name,
const std::string &  action_name,
const BT::NodeConfiguration &  conf 
)
inline

A nav2_behavior_tree::BtActionNode constructor.

Parameters
xml_tag_nameName for the XML tag for this node
action_nameAction name this node creates a client for
confBT node configuration

Definition at line 46 of file bt_action_node.hpp.

Member Function Documentation

◆ createActionClient()

template<class ActionT >
void nav2_behavior_tree::BtActionNode< ActionT >::createActionClient ( const std::string &  action_name)
inline

Create instance of an action client.

Parameters
action_nameAction name to create client for

Definition at line 94 of file bt_action_node.hpp.

◆ is_future_goal_handle_complete()

template<class ActionT >
bool nav2_behavior_tree::BtActionNode< ActionT >::is_future_goal_handle_complete ( std::chrono::milliseconds &  elapsed)
inlineprotected

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

Parameters
elapsedDuration 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

Definition at line 402 of file bt_action_node.hpp.

◆ on_aborted()

template<class ActionT >
virtual BT::NodeStatus nav2_behavior_tree::BtActionNode< ActionT >::on_aborted ( )
inlinevirtual

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

Reimplemented in nav2_behavior_tree::ComputeRouteAction, nav2_behavior_tree::ComputePathToPoseAction, nav2_behavior_tree::ComputePathThroughPosesAction, nav2_behavior_tree::ComputeAndTrackRouteAction, and nav2_behavior_tree::AssistedTeleopAction.

Definition at line 174 of file bt_action_node.hpp.

◆ on_cancelled()

template<class ActionT >
virtual BT::NodeStatus nav2_behavior_tree::BtActionNode< ActionT >::on_cancelled ( )
inlinevirtual

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

Reimplemented in nav2_behavior_tree::ComputeRouteAction, nav2_behavior_tree::ComputePathToPoseAction, nav2_behavior_tree::ComputePathThroughPosesAction, and nav2_behavior_tree::ComputeAndTrackRouteAction.

Definition at line 183 of file bt_action_node.hpp.

◆ on_success()

template<class ActionT >
virtual BT::NodeStatus nav2_behavior_tree::BtActionNode< ActionT >::on_success ( )
inlinevirtual

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

Reimplemented in nav2_behavior_tree::SmoothPathAction, nav2_behavior_tree::ComputeRouteAction, nav2_behavior_tree::ComputePathToPoseAction, nav2_behavior_tree::ComputePathThroughPosesAction, and nav2_behavior_tree::ComputeAndTrackRouteAction.

Definition at line 165 of file bt_action_node.hpp.

◆ on_wait_for_result()

template<class ActionT >
virtual void nav2_behavior_tree::BtActionNode< ActionT >::on_wait_for_result ( std::shared_ptr< const typename ActionT::Feedback >  )
inlinevirtual

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
feedbackshared_ptr to latest feedback message, nullptr if no new feedback was received

Definition at line 156 of file bt_action_node.hpp.

◆ providedBasicPorts()

template<class ActionT >
static BT::PortsList nav2_behavior_tree::BtActionNode< ActionT >::providedBasicPorts ( BT::PortsList  addition)
inlinestatic

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

Parameters
additionAdditional ports to add to BT port list
Returns
BT::PortsList Containing basic ports along with node-specific ports

Definition at line 118 of file bt_action_node.hpp.

◆ providedPorts()

template<class ActionT >
static BT::PortsList nav2_behavior_tree::BtActionNode< ActionT >::providedPorts ( )
inlinestatic

Creates list of BT ports.

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

Definition at line 133 of file bt_action_node.hpp.

◆ should_cancel_goal()

template<class ActionT >
bool nav2_behavior_tree::BtActionNode< ActionT >::should_cancel_goal ( )
inlineprotected

Function to check if current goal should be cancelled.

Returns
bool True if current goal should be cancelled, false otherwise

Definition at line 339 of file bt_action_node.hpp.

◆ tick()

template<class ActionT >
BT::NodeStatus nav2_behavior_tree::BtActionNode< ActionT >::tick ( )
inlineoverride

The main override required by a BT action.

Returns
BT::NodeStatus Status of tick execution

Definition at line 192 of file bt_action_node.hpp.


The documentation for this class was generated from the following file: