|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
A BT::ConditionNode that returns SUCCESS every time the robot travels a specified distance and FAILURE otherwise. More...
#include <nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp>


Public Member Functions | |
| DistanceTraveledCondition (const std::string &condition_name, const BT::NodeConfiguration &conf) | |
| A constructor for nav2_behavior_tree::DistanceTraveledCondition. More... | |
| BT::NodeStatus | tick () override |
| The main override required by a BT action. More... | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| Creates list of BT ports. More... | |
A BT::ConditionNode that returns SUCCESS every time the robot travels a specified distance and FAILURE otherwise.
Definition at line 35 of file distance_traveled_condition.hpp.
| nav2_behavior_tree::DistanceTraveledCondition::DistanceTraveledCondition | ( | const std::string & | condition_name, |
| const BT::NodeConfiguration & | conf | ||
| ) |
A constructor for nav2_behavior_tree::DistanceTraveledCondition.
| condition_name | Name for the XML tag for this node |
| conf | BT node configuration |
Definition at line 27 of file distance_traveled_condition.cpp.
|
inlinestatic |
Creates list of BT ports.
Definition at line 59 of file distance_traveled_condition.hpp.
|
override |
The main override required by a BT action.
Definition at line 44 of file distance_traveled_condition.cpp.