Class VelObsExitCondition
Defined in File vel_obs_exit_condition.h
Inheritance Relationships
Base Type
public BT::ConditionNode
Class Documentation
-
class VelObsExitCondition : public BT::ConditionNode
Condition node that checks if an obstacle (human) has stopped in the environment.
This class implements a behavior tree condition that monitors the velocity state of nearby human agents and determines if any have come to a stop. It is used to detect situations where the robot’s path may be blocked by a stationary human obstacle.
Public Functions
-
VelObsExitCondition(const std::string &condition_name, const BT::NodeConfiguration &conf)
Constructor for the VelObsExitCondition node.
- Parameters:
condition_name – Name of the condition node
conf – Node configuration containing the input/output ports
-
VelObsExitCondition() = delete
-
~VelObsExitCondition() override
Destructor.
-
BT::NodeStatus tick() override
Main execution tick of the condition node.
- Returns:
NodeStatus SUCCESS if a human has stopped, FAILURE otherwise
Public Static Functions
-
static inline BT::PortsList providedPorts()
Defines the input and output ports for the condition node.
- Returns:
PortsList containing the node’s ports configuration
Private Functions
-
bool hasHumanStopped()
Checks if any human agent in the environment has stopped moving.
- Returns:
true if a human has stopped, false otherwise
Private Members
-
agent_path_prediction::AgentsInfo agents_info_
Current information about all agents in the environment.
-
std::string name_
Name of this behavior tree node.
-
int nearest_human_id_
ID of the nearest human agent.
-
int t_stuck_
Time counter for how long an agent has been stuck.
-
std::mutex agents_mutex_
Mutex to protect concurrent access to agent data.
-
VelObsExitCondition(const std::string &condition_name, const BT::NodeConfiguration &conf)