AutoAPMS
Resilient Robot Mission Management
|
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 |
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.
TreeStateObserver | ( | const BT::Tree & | tree, |
const rclcpp::Logger & | node_logger, | ||
std::chrono::seconds | max_logging_interval = std::chrono::seconds(0) ) |
Constructor.
tree | Behavior tree object to attach to. |
node_logger | ROS 2 logger that this observer writes state transitions of behavior tree nodes to. |
max_logging_interval | Maximum logging interval. 0 means to log every state transition regardless the interval between them. |
Definition at line 22 of file state_observer.cpp.
|
overridevirtual |
Reset the internal state variables.
Definition at line 31 of file state_observer.cpp.
void setLogging | ( | bool | active | ) |
Configure whether the observer should write to the logger.
active | true to allow to write to the logger, false to disable it. |
Definition at line 33 of file state_observer.cpp.
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.
Definition at line 35 of file state_observer.cpp.
const std::string & getLastRunningActionName | ( | ) | const |
Get the name of the last action node that returned BT::NodeStatus::RUNNING
.
Definition at line 37 of file state_observer.cpp.
|
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.