Easy Navigation
Loading...
Searching...
No Matches
GoalManagerClient Class Reference

Client-side interface for interacting with GoalManager. More...

#include <GoalManagerClient.hpp>

Public Types

enum class  State {
  IDLE , SENT_GOAL , SENT_PREEMPT , ACCEPTED_AND_NAVIGATING ,
  NAVIGATION_FINISHED , NAVIGATION_REJECTED , NAVIGATION_FAILED , NAVIGATION_CANCELLED ,
  ERROR
}
 Internal state of the client-side goal manager. More...
 

Public Member Functions

void cancel ()
 Cancel the current goal.
 
const easynav_interfaces::msg::NavigationControl & get_feedback () const
 Get the most recent feedback received.
 
const easynav_interfaces::msg::NavigationControl & get_last_control () const
 Get the last control message sent or received.
 
const easynav_interfaces::msg::NavigationControl & get_result () const
 Get the last result message received.
 
State get_state () const
 Get the current internal state.
 
 GoalManagerClient (rclcpp::Node::SharedPtr node)
 Constructor.
 
void reset ()
 Reset internal client state.
 
void send_goal (const geometry_msgs::msg::PoseStamped &goal)
 Send a single goal to the GoalManager.
 
void send_goals (const nav_msgs::msg::Goals &goals)
 Send a list of goals to the GoalManager.
 

Detailed Description

Client-side interface for interacting with GoalManager.

Sends navigation goals, handles feedback and result updates, and manages goal lifecycle state.

Member Enumeration Documentation

◆ State

enum class State
strong

Internal state of the client-side goal manager.

Enumerator
IDLE 
SENT_GOAL 
SENT_PREEMPT 
ACCEPTED_AND_NAVIGATING 
NAVIGATION_FINISHED 
NAVIGATION_REJECTED 
NAVIGATION_FAILED 
NAVIGATION_CANCELLED 
ERROR 

Constructor & Destructor Documentation

◆ GoalManagerClient()

GoalManagerClient ( rclcpp::Node::SharedPtr node)

Constructor.

Parameters
nodeShared pointer to a ROS 2 node.

Member Function Documentation

◆ cancel()

void cancel ( )

Cancel the current goal.

◆ get_feedback()

const easynav_interfaces::msg::NavigationControl & get_feedback ( ) const
nodiscard

Get the most recent feedback received.

Returns
Reference to the last feedback message.

◆ get_last_control()

const easynav_interfaces::msg::NavigationControl & get_last_control ( ) const
nodiscard

Get the last control message sent or received.

Returns
Reference to the last control message.

◆ get_result()

const easynav_interfaces::msg::NavigationControl & get_result ( ) const
nodiscard

Get the last result message received.

Returns
Reference to the last result message.

◆ get_state()

State get_state ( ) const
nodiscard

Get the current internal state.

Returns
Current State.

◆ reset()

void reset ( )

Reset internal client state.

◆ send_goal()

void send_goal ( const geometry_msgs::msg::PoseStamped & goal)

Send a single goal to the GoalManager.

Parameters
goalPoseStamped representing the goal.

◆ send_goals()

void send_goals ( const nav_msgs::msg::Goals & goals)

Send a list of goals to the GoalManager.

Parameters
goalsList of goals to navigate.

The documentation for this class was generated from the following files: