Template Class BtServiceNode
Defined in File bt_service_node.hpp
Inheritance Relationships
Base Type
public BT::ActionNodeBase
Class Documentation
-
template<class ServiceT>
class BtServiceNode : public BT::ActionNodeBase Abstract class representing a service based BT node.
- Template Parameters:
ServiceT – Type of service
Public Functions
-
inline BtServiceNode(const std::string &service_node_name, const BT::NodeConfiguration &conf)
A as2_behavior_tree::BtServiceNode constructor.
- Parameters:
service_node_name – Service name this node creates a client for
conf – BT node configuration
-
BtServiceNode() = delete
-
inline virtual ~BtServiceNode()
-
inline BT::NodeStatus tick() override
The main override required by a BT service.
- Returns:
BT::NodeStatus Status of tick execution
-
inline void halt() override
The other (optional) override required by a BT service.
-
inline virtual void on_tick()
Function to perform some user-defined operation on tick Fill in service request with information if necessary.
Function to perform some user-defined operation upon successful completion of the service. Could put a value on the blackboard.
- Parameters:
response – can be used to get the result of the service call in the BT Node.
- Returns:
BT::NodeStatus Returns SUCCESS by default, user may override to return another value
-
inline virtual BT::NodeStatus check_future()
Check the future and decide the status of BT.
- Returns:
BT::NodeStatus SUCCESS if future complete before timeout, FAILURE otherwise
-
inline virtual void on_wait_for_result()
Function to perform some user-defined operation after a timeout waiting for a result that hasn’t been received yet.
Public Static Functions
-
static inline BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtServiceNode 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 void increment_recovery_count()
Function to increment recovery count on blackboard if this node wraps a recovery.
Protected Attributes
-
std::string service_name_
-
std::string service_node_name_
-
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_
-
bool request_sent_ = {false}
-
rclcpp::Time sent_time_