Class BackoffExitCondition
Defined in File backoff_exit_condition.h
Inheritance Relationships
Base Type
public BT::ConditionNode
Class Documentation
-
class BackoffExitCondition : public BT::ConditionNode
Class implementing a condition node for managing backoff recovery behavior.
This class provides functionality to control when to exit the backoff recovery mode. It monitors agent states and recovery progress to determine when to resume normal navigation. It inherits from BT::ConditionNode to integrate with the behavior tree framework.
Public Functions
-
BackoffExitCondition(const std::string &condition_name, const BT::NodeConfiguration &conf)
Constructor with condition name and configuration.
- Parameters:
condition_name – Name of the condition node
conf – Configuration for the behavior tree node
-
BackoffExitCondition() = delete
Deleted default constructor to enforce proper initialization.
-
~BackoffExitCondition() override
Virtual destructor for cleanup.
-
BT::NodeStatus tick() override
Method called to evaluate the condition.
- Returns:
SUCCESS if backoff recovery should be exited, FAILURE otherwise
Public Static Functions
-
static inline BT::PortsList providedPorts()
Defines input and output ports for recovery condition.
- Returns:
Ports list containing agents_info, backoff_ptr, nav_goal, agents_ptr as inputs, and recovery status as output
Private Functions
-
bool isRecoveryComplete()
Checks if the recovery behavior is complete.
- Returns:
True if recovery is complete, false otherwise
Private Members
-
agent_path_prediction::AgentsInfo agents_info_
Information about agents in the environment.
-
geometry_msgs::PoseStamped current_goal_
Current navigation goal.
-
int stuck_agent_
ID of the agent that is stuck.
-
double dist_max_
Maximum distance threshold.
-
std::string name_
Name of the node.
-
bool started_
Flag indicating if recovery has started.
-
bool new_goal_
Flag indicating if a new goal was received.
-
bool backed_off_
Flag indicating if robot has backed off.
-
BackoffExitCondition(const std::string &condition_name, const BT::NodeConfiguration &conf)