18 #include "behaviortree_cpp/condition_node.h"
20 #include "nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.hpp"
22 namespace nav2_behavior_tree
25 PathExpiringTimerCondition::PathExpiringTimerCondition(
26 const std::string & condition_name,
27 const BT::NodeConfiguration & conf)
28 : BT::ConditionNode(condition_name, conf),
32 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
38 getInput(
"seconds", period_);
39 getInput(
"path", prev_path_);
41 start_ = node_->now();
42 return BT::NodeStatus::FAILURE;
46 nav_msgs::msg::Path path;
47 getInput(
"path", path);
50 if (prev_path_ != path) {
52 start_ = node_->now();
56 auto elapsed = node_->now() - start_;
59 auto seconds = elapsed.seconds();
61 if (seconds < period_) {
62 return BT::NodeStatus::FAILURE;
65 start_ = node_->now();
66 return BT::NodeStatus::SUCCESS;
71 #include "behaviortree_cpp/bt_factory.h"
72 BT_REGISTER_NODES(factory)
A BT::ConditionNode that returns SUCCESS every time a specified time period passes and FAILURE otherw...
BT::NodeStatus tick() override
The main override required by a BT action.