Class GoalManager

Nested Relationships

Nested Types

Class Documentation

class GoalManager

Handles navigation goals, their lifecycle, and command interface.

Manages goal state, handles external control messages, and interacts with navigation components.

Public Types

enum class State

Current internal goal state.

Values:

enumerator IDLE

No active goal.

enumerator ACTIVE

A goal is currently being pursued.

Public Functions

GoalManager(NavState &nav_state, rclcpp_lifecycle::LifecycleNode::SharedPtr parent_node)

Constructor.

Parameters:
  • nav_state – Shared pointer to navigation state.

  • parent_node – Lifecycle node for parameter and interface management.

inline nav_msgs::msg::Goals get_goals() const

Get current goals.

Returns:

Goals message.

inline State get_state() const

Get current internal goal state.

Returns:

GoalManager::State value.

void set_finished()

Mark the current goal as successfully completed.

void set_failed(const std::string &reason)

Mark the current goal as failed.

Parameters:

reason – Textual explanation.

void set_error(const std::string &reason)

Mark the system as in error state.

Parameters:

reason – Textual explanation.

void update(NavState &nav_state)

Update internal logic, including preemption and timeout checks.

void check_goals(const geometry_msgs::msg::Pose &current_pose, const GoalTolerance &goal_tolerance)

Check if the robot is currently at the first goal.

Compares the current pose against the first target in the list using positional and angular tolerances.

Parameters:
  • current_pose – Current pose of the robot.

  • goal_tolerance – Maximum allowed error for the goal position and orientation.

struct GoalTolerance

A structure to represent the goal tolerances.

Public Members

double position = {0.03}

Positional tolerance for x/y in meters.

double height = {std::numeric_limits<double>::max()}

Positional tolerance for z axis in meters. Very big number as default.

double yaw = {0.01}

Angular tolerance in radians for the yaw angle.