Class DualBandExitCondition
Defined in File dual_band_exit_condition.h
Inheritance Relationships
Base Type
public BT::ConditionNode
Class Documentation
-
class DualBandExitCondition : public BT::ConditionNode
Class implementing a condition node for dual band exit criteria.
This class checks conditions to determine when to exit the dual band planning mode. It monitors robot’s progress and agent states to make this decision. It inherits from BT::ConditionNode to integrate with the behavior tree framework.
Public Functions
-
DualBandExitCondition(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
-
DualBandExitCondition() = delete
Deleted default constructor to enforce proper initialization.
-
~DualBandExitCondition() override
Virtual destructor for cleanup.
-
BT::NodeStatus tick() override
Method called to evaluate the condition.
- Returns:
SUCCESS if dual band mode should be exited, FAILURE otherwise
Public Static Functions
-
static inline BT::PortsList providedPorts()
Defines input ports for condition evaluation.
- Returns:
Ports list containing agents_info, distance threshold and navigation goal as inputs
Private Functions
-
bool isRobotStuck()
Checks if the robot has been stuck in place.
- Returns:
True if robot hasn’t made progress, false otherwise
Private Members
-
agent_path_prediction::AgentsInfo agents_info_
Information about agents in the environment.
-
geometry_msgs::PoseStamped goal_
Current navigation goal.
-
double dist_threshold_
Distance threshold for dual band mode.
-
double goal_dist_
Distance to goal for progress tracking.
-
ros::Time stopped_time_
Time when robot was last detected as stopped.
-
std::string name_
Name of the node.
-
DualBandExitCondition(const std::string &condition_name, const BT::NodeConfiguration &conf)