Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
ros_topic_logger.hpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_BEHAVIOR_TREE__ROS_TOPIC_LOGGER_HPP_
16 #define NAV2_BEHAVIOR_TREE__ROS_TOPIC_LOGGER_HPP_
17 
18 #include <vector>
19 #include <memory>
20 #include <utility>
21 
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_ros/buffer_interface.h"
27 
28 namespace nav2_behavior_tree
29 {
30 
34 class RosTopicLogger : public BT::StatusChangeLogger
35 {
36 public:
42  RosTopicLogger(const rclcpp::Node::WeakPtr & ros_node, const BT::Tree & tree)
43  : StatusChangeLogger(tree.rootNode())
44  {
45  auto node = ros_node.lock();
46  clock_ = node->get_clock();
47  logger_ = node->get_logger();
48  log_pub_ = node->create_publisher<nav2_msgs::msg::BehaviorTreeLog>(
49  "behavior_tree_log",
50  rclcpp::QoS(10));
51  }
52 
60  void callback(
61  BT::Duration timestamp,
62  const BT::TreeNode & node,
63  BT::NodeStatus prev_status,
64  BT::NodeStatus status) override
65  {
66  nav2_msgs::msg::BehaviorTreeStatusChange event;
67 
68  // BT timestamps are a duration since the epoch. Need to convert to a time_point
69  // before converting to a msg.
70  event.timestamp = tf2_ros::toMsg(tf2::TimePoint(timestamp));
71  event.node_name = node.name();
72  event.uid = node.UID();
73  event.previous_status = toStr(prev_status, false);
74  event.current_status = toStr(status, false);
75  event_log_.push_back(std::move(event));
76 
77  RCLCPP_DEBUG(
78  logger_, "[%.3f]: %25s %s -> %s",
79  std::chrono::duration<double>(timestamp).count(),
80  node.name().c_str(),
81  toStr(prev_status, true).c_str(),
82  toStr(status, true).c_str() );
83  }
84 
88  void flush() override
89  {
90  if (!event_log_.empty()) {
91  auto log_msg = std::make_unique<nav2_msgs::msg::BehaviorTreeLog>();
92  log_msg->timestamp = clock_->now();
93  log_msg->event_log = event_log_;
94  log_pub_->publish(std::move(log_msg));
95  event_log_.clear();
96  }
97  }
98 
99 protected:
100  rclcpp::Clock::SharedPtr clock_;
101  rclcpp::Logger logger_{rclcpp::get_logger("bt_navigator")};
102  rclcpp::Publisher<nav2_msgs::msg::BehaviorTreeLog>::SharedPtr log_pub_;
103  std::vector<nav2_msgs::msg::BehaviorTreeStatusChange> event_log_;
104 };
105 
106 } // namespace nav2_behavior_tree
107 
108 #endif // NAV2_BEHAVIOR_TREE__ROS_TOPIC_LOGGER_HPP_
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.