15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONTROL__RECOVERY_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONTROL__RECOVERY_NODE_HPP_
19 #include "behaviortree_cpp/control_node.h"
21 namespace nav2_behavior_tree
44 const std::string & name,
45 const BT::NodeConfiguration & conf);
59 BT::InputPort<int>(
"number_of_retries", 1,
"Number of retries")
64 unsigned int current_child_idx_;
65 unsigned int number_of_retries_;
66 unsigned int retry_count_;
72 BT::NodeStatus tick()
override;
The RecoveryNode has only two children and returns SUCCESS if and only if the first child returns SUC...
static BT::PortsList providedPorts()
Creates list of BT ports.
RecoveryNode(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::RecoveryNode.
~RecoveryNode() override=default
A destructor for nav2_behavior_tree::RecoveryNode.