Class IsGoalReached

Inheritance Relationships

Base Type

  • public BT::ConditionNode

Class Documentation

class IsGoalReached : public BT::ConditionNode

Class implementing a condition node for checking if navigation goal is reached.

This class monitors the robot’s position relative to the navigation goal and provides functionality to determine when the goal has been successfully reached. It inherits from BT::ConditionNode to integrate with the behavior tree framework.

Public Functions

IsGoalReached(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

IsGoalReached() = delete

Deleted default constructor to enforce proper initialization.

~IsGoalReached() override

Virtual destructor for cleanup.

void goalReceivedCB(const move_base_msgs::MoveBaseActionGoal &goal_msg)

Callback for receiving new navigation goals.

Parameters:

goal_msg – Message containing the new goal pose

void resultCB(const move_base_msgs::MoveBaseActionResult &result_msg)

Callback for receiving goal status updates.

Parameters:

result_msg – Message containing the goal status result

BT::NodeStatus tick() override

Method called to evaluate if goal is reached.

Returns:

SUCCESS if goal is reached or updated, FAILURE if still in progress

Public Static Functions

static inline BT::PortsList providedPorts()

Defines input and output ports for condition evaluation.

Returns:

Ports list containing agents_info as input and nav_goal as output

Private Functions

bool goalReachedCheck()

Helper method to check if robot has reached goal position.

Returns:

True if robot is at goal position and orientation, false otherwise

Private Members

ros::Subscriber goal_sub_
ros::Subscriber status_sub_

Subscribers for goal and status updates.

bool goal_reached_

Flag indicating if goal is reached.

bool updated_

Flag indicating if goal was updated.

geometry_msgs::Pose goal_

Current navigation goal pose.

agent_path_prediction::AgentsInfo agents_info_

Information about agents in the environment.

std::string name_

Name of the node.