Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Type of sequence node that ticks children in a round-robin fashion. More...
#include <nav2_behavior_tree/include/nav2_behavior_tree/plugins/control/round_robin_node.hpp>
Public Member Functions | |
RoundRobinNode (const std::string &name) | |
A constructor for nav2_behavior_tree::RoundRobinNode. More... | |
RoundRobinNode (const std::string &name, const BT::NodeConfiguration &config) | |
A constructor for nav2_behavior_tree::RoundRobinNode. More... | |
BT::NodeStatus | tick () override |
The main override required by a BT action. More... | |
void | halt () override |
The other (optional) override required by a BT action to reset node state. | |
Static Public Member Functions | |
static BT::PortsList | providedPorts () |
Creates list of BT ports. More... | |
Type of sequence node that ticks children in a round-robin fashion.
RoundRobin | Tick Next Child | Return Running
If the current child return failure, the next child is ticked and if the last child returns failure, the first child is ticked and the cycle continues until a child returns success
As an example, let's say this node has 3 children: A, B and C. At the start, they are all IDLE.
| IDLE | IDLE | IDLE | | RUNNING | IDLE | IDLE | - at first A gets ticked. Assume it returns RUNNING
If all children return FAILURE, RoundRobin will return FAILURE and halt all children, ending the sequence.
Usage in XML: <RoundRobin>
Definition at line 54 of file round_robin_node.hpp.
|
explicit |
A constructor for nav2_behavior_tree::RoundRobinNode.
name | Name for the XML tag for this node |
Definition at line 22 of file round_robin_node.cpp.
nav2_behavior_tree::RoundRobinNode::RoundRobinNode | ( | const std::string & | name, |
const BT::NodeConfiguration & | config | ||
) |
A constructor for nav2_behavior_tree::RoundRobinNode.
name | Name for the XML tag for this node |
config | BT node configuration |
Definition at line 27 of file round_robin_node.cpp.
|
inlinestatic |
Creates list of BT ports.
Definition at line 85 of file round_robin_node.hpp.
|
override |
The main override required by a BT action.
Definition at line 34 of file round_robin_node.cpp.
References halt().