AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
TreeStateObserver Class Reference

State observer for a particular behavior tree object that writes introspection and debugging information related to behavior tree node transitions to a ROS 2 logger. More...

#include <auto_apms_behavior_tree/executor/state_observer.hpp>

Public Member Functions

 TreeStateObserver (const BT::Tree &tree, const rclcpp::Logger &node_logger, std::chrono::seconds max_logging_interval=std::chrono::seconds(0))
 Constructor.
 
virtual void flush () override
 Reset the internal state variables.
 
void setLogging (bool active)
 Configure whether the observer should write to the logger.
 
const std::vector< std::string > & getRunningActionHistory () const
 Get all names of action nodes that returned BT::NodeStatus::RUNNING since the last time TreeStateObserver::flush was called.
 
const std::string & getLastRunningActionName () const
 Get the name of the last action node that returned BT::NodeStatus::RUNNING.
 

Private Member Functions

virtual void callback (BT::Duration timestamp, const BT::TreeNode &node, BT::NodeStatus prev_status, BT::NodeStatus status) override
 

Detailed Description

State observer for a particular behavior tree object that writes introspection and debugging information related to behavior tree node transitions to a ROS 2 logger.

This is integrated with TreeExecutorNode.

Definition at line 31 of file state_observer.hpp.

Constructor & Destructor Documentation

◆ TreeStateObserver()

TreeStateObserver ( const BT::Tree & tree,
const rclcpp::Logger & node_logger,
std::chrono::seconds max_logging_interval = std::chrono::seconds(0) )

Constructor.

Parameters
treeBehavior tree object to attach to.
node_loggerROS 2 logger that this observer writes state transitions of behavior tree nodes to.
max_logging_intervalMaximum logging interval. 0 means to log every state transition regardless the interval between them.

Definition at line 22 of file state_observer.cpp.

Member Function Documentation

◆ flush()

void flush ( )
overridevirtual

Reset the internal state variables.

Definition at line 31 of file state_observer.cpp.

◆ setLogging()

void setLogging ( bool active)

Configure whether the observer should write to the logger.

Parameters
activetrue to allow to write to the logger, false to disable it.

Definition at line 33 of file state_observer.cpp.

◆ getRunningActionHistory()

const std::vector< std::string > & getRunningActionHistory ( ) const

Get all names of action nodes that returned BT::NodeStatus::RUNNING since the last time TreeStateObserver::flush was called.

Returns
Names of action nodes that were running recently.

Definition at line 35 of file state_observer.cpp.

◆ getLastRunningActionName()

const std::string & getLastRunningActionName ( ) const

Get the name of the last action node that returned BT::NodeStatus::RUNNING.

Returns
Name of the action node that was running most recently.

Definition at line 37 of file state_observer.cpp.

◆ callback()

void callback ( BT::Duration timestamp,
const BT::TreeNode & node,
BT::NodeStatus prev_status,
BT::NodeStatus status )
overrideprivatevirtual

Write to ROS2 logger but respect a maximum interval if a specific node triggers the same state transitions (e.g. conditions in reactive control statements or loops).

Definition at line 44 of file state_observer.cpp.


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