15 #ifndef NAV2_BEHAVIOR_TREE__ROS_TOPIC_LOGGER_HPP_
16 #define NAV2_BEHAVIOR_TREE__ROS_TOPIC_LOGGER_HPP_
22 #include "behaviortree_cpp/loggers/abstract_logger.h"
23 #include "rclcpp/rclcpp.hpp"
24 #include "nav2_msgs/msg/behavior_tree_log.hpp"
25 #include "nav2_msgs/msg/behavior_tree_status_change.h"
26 #include "tf2/time.hpp"
27 #include "tf2_ros/buffer_interface.h"
29 namespace nav2_behavior_tree
43 RosTopicLogger(
const rclcpp::Node::WeakPtr & ros_node,
const BT::Tree & tree)
44 : StatusChangeLogger(tree.rootNode())
46 auto node = ros_node.lock();
47 clock_ = node->get_clock();
48 logger_ = node->get_logger();
49 log_pub_ = node->create_publisher<nav2_msgs::msg::BehaviorTreeLog>(
62 BT::Duration timestamp,
63 const BT::TreeNode & node,
64 BT::NodeStatus prev_status,
65 BT::NodeStatus status)
override
67 nav2_msgs::msg::BehaviorTreeStatusChange event;
71 event.timestamp = tf2_ros::toMsg(tf2::TimePoint(timestamp));
72 event.node_name = node.name();
73 event.uid = node.UID();
74 event.previous_status = toStr(prev_status,
false);
75 event.current_status = toStr(status,
false);
76 event_log_.push_back(std::move(event));
79 logger_,
"[%.3f]: %25s %s -> %s",
80 std::chrono::duration<double>(timestamp).count(),
82 toStr(prev_status,
true).c_str(),
83 toStr(status,
true).c_str() );
91 if (!event_log_.empty()) {
92 auto log_msg = std::make_unique<nav2_msgs::msg::BehaviorTreeLog>();
93 log_msg->timestamp = clock_->now();
94 log_msg->event_log = event_log_;
95 log_pub_->publish(std::move(log_msg));
101 rclcpp::Clock::SharedPtr clock_;
102 rclcpp::Logger logger_{rclcpp::get_logger(
"bt_navigator")};
103 rclcpp::Publisher<nav2_msgs::msg::BehaviorTreeLog>::SharedPtr log_pub_;
104 std::vector<nav2_msgs::msg::BehaviorTreeStatusChange> event_log_;
A class to publish BT logs on BT status change.
RosTopicLogger(const rclcpp::Node::WeakPtr &ros_node, const BT::Tree &tree)
A constructor for nav2_behavior_tree::RosTopicLogger.
void flush() override
Clear log buffer if any.
void callback(BT::Duration timestamp, const BT::TreeNode &node, BT::NodeStatus prev_status, BT::NodeStatus status) override
Callback function which is called each time BT changes status.