File tree Expand file tree Collapse file tree 3 files changed +12
-4
lines changed
include/nav2_behavior_tree Expand file tree Collapse file tree 3 files changed +12
-4
lines changed Original file line number Diff line number Diff line change @@ -47,7 +47,8 @@ class BehaviorTreeEngine
4747 * @param plugin_libraries vector of BT plugin library names to load
4848 */
4949 explicit BehaviorTreeEngine (
50- const std::vector<std::string> & plugin_libraries);
50+ const std::vector<std::string> & plugin_libraries,
51+ rclcpp::Node::SharedPtr node);
5152 virtual ~BehaviorTreeEngine () {}
5253
5354 /* *
@@ -93,6 +94,9 @@ class BehaviorTreeEngine
9394protected:
9495 // The factory that will be used to dynamically construct the behavior tree
9596 BT::BehaviorTreeFactory factory_;
97+
98+ // Clock
99+ rclcpp::Clock::SharedPtr clock_;
96100};
97101
98102} // namespace nav2_behavior_tree
Original file line number Diff line number Diff line change @@ -173,7 +173,7 @@ bool BtActionServer<ActionT>::on_configure()
173173 error_code_names_ = node->get_parameter (" error_code_names" ).as_string_array ();
174174
175175 // Create the class that registers our custom nodes and executes the BT
176- bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_);
176+ bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_, client_node_ );
177177
178178 // Create the blackboard that will be shared by all of the nodes in the tree
179179 blackboard_ = BT::Blackboard::create ();
Original file line number Diff line number Diff line change @@ -26,13 +26,16 @@ namespace nav2_behavior_tree
2626{
2727
2828BehaviorTreeEngine::BehaviorTreeEngine (
29- const std::vector<std::string> & plugin_libraries)
29+ const std::vector<std::string> & plugin_libraries, rclcpp::Node::SharedPtr node )
3030{
3131 BT::SharedLibrary loader;
3232 for (const auto & p : plugin_libraries) {
3333 factory_.registerFromPlugin (loader.getOSName (p));
3434 }
3535
36+ // clock for throttled debug log
37+ clock_ = node->get_clock ();
38+
3639 // FIXME: the next two line are needed for back-compatibility with BT.CPP 3.8.x
3740 // Note that the can be removed, once we migrate from BT.CPP 4.5.x to 4.6+
3841 BT::ReactiveSequence::EnableException (false );
@@ -62,8 +65,9 @@ BehaviorTreeEngine::run(
6265 onLoop ();
6366
6467 if (!loopRate.sleep ()) {
65- RCLCPP_WARN (
68+ RCLCPP_DEBUG_THROTTLE (
6669 rclcpp::get_logger (" BehaviorTreeEngine" ),
70+ *clock_, 1000 ,
6771 " Behavior Tree tick rate %0.2f was exceeded!" ,
6872 1.0 / (loopRate.period ().count () * 1.0e-9 ));
6973 }
You can’t perform that action at this time.
0 commit comments