|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
A BT::ConditionNode that returns SUCCESS when a specified goal is reached and FAILURE otherwise. More...
#include <nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp>


Public Member Functions | |
| GoalReachedCondition (const std::string &condition_name, const BT::NodeConfiguration &conf) | |
| A constructor for nav2_behavior_tree::GoalReachedCondition. More... | |
| ~GoalReachedCondition () override | |
| A destructor for nav2_behavior_tree::GoalReachedCondition. | |
| BT::NodeStatus | tick () override |
| The main override required by a BT action. More... | |
| void | initialize () |
| Function to read parameters and initialize class variables. | |
| bool | isGoalReached () |
| Checks if the current robot pose lies within a given distance from the goal. More... | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| Creates list of BT ports. More... | |
Protected Member Functions | |
| void | cleanup () |
| Cleanup function. | |
A BT::ConditionNode that returns SUCCESS when a specified goal is reached and FAILURE otherwise.
Definition at line 32 of file goal_reached_condition.hpp.
| nav2_behavior_tree::GoalReachedCondition::GoalReachedCondition | ( | const std::string & | condition_name, |
| const BT::NodeConfiguration & | conf | ||
| ) |
A constructor for nav2_behavior_tree::GoalReachedCondition.
| condition_name | Name for the XML tag for this node |
| conf | BT node configuration |
Definition at line 27 of file goal_reached_condition.cpp.
| bool nav2_behavior_tree::GoalReachedCondition::isGoalReached | ( | ) |
Checks if the current robot pose lies within a given distance from the goal.
Definition at line 71 of file goal_reached_condition.cpp.
Referenced by tick().

|
inlinestatic |
Creates list of BT ports.
Definition at line 72 of file goal_reached_condition.hpp.
|
override |
The main override required by a BT action.
Definition at line 44 of file goal_reached_condition.cpp.
References initialize(), and isGoalReached().
