Template Class BtCancelActionNode

Inheritance Relationships

Base Type

  • public BT::ActionNodeBase

Class Documentation

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

Abstract class representing an action for cancelling BT node.

Template Parameters:

ActionT – Type of action

Public Functions

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

A nav2_behavior_tree::BtCancelActionNode 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

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

Create instance of an action client.

Parameters:

action_name – Action name to create client for

inline void halt()
inline BT::NodeStatus tick() override

The main override required by a BT action.

Returns:

BT::NodeStatus Status of tick execution

Public Static Functions

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

Any subclass of BtCancelActionNode 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 Attributes

std::string action_name_
std::shared_ptr<rclcpp_action::Client<ActionT>> action_client_
rclcpp::Node::SharedPtr node_
rclcpp::CallbackGroup::SharedPtr callback_group_
rclcpp::executors::SingleThreadedExecutor callback_group_executor_
std::chrono::milliseconds server_timeout_