16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__TIME_EXPIRED_CONDITION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__TIME_EXPIRED_CONDITION_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "behaviortree_cpp/condition_node.h"
24 namespace nav2_behavior_tree
42 const std::string & condition_name,
43 const BT::NodeConfiguration & conf);
51 BT::NodeStatus
tick()
override;
65 BT::InputPort<double>(
"seconds", 1.0,
"Seconds")
70 rclcpp::Node::SharedPtr node_;
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.
void initialize()
Function to read parameters and initialize class variables.
static BT::PortsList providedPorts()
Creates list of BT ports.