Public Member Functions | Public Attributes | List of all members
actionlib.action_client.ClientGoalHandle Class Reference

Client side handle to monitor goal progress. More...

Public Member Functions

def __eq__ (self, o)
 True iff the two ClientGoalHandle's are tracking the same goal. More...
 
def __hash__ (self)
 Hash function for ClientGoalHandle More...
 
def __init__ (self, comm_state_machine)
 Internal use only. More...
 
def __ne__ (self, o)
 True iff the two ClientGoalHandle's are tracking different goals. More...
 
def cancel (self)
 Sends a cancel message for this specific goal to the ActionServer. More...
 
def get_comm_state (self)
 Get the state of this goal's communication state machine from interaction with the server. More...
 
def get_goal_status (self)
 Returns the current status of the goal. More...
 
def get_goal_status_text (self)
 Returns the current status text of the goal. More...
 
def get_result (self)
 Gets the result produced by the action server for this goal. More...
 
def get_terminal_state (self)
 Gets the terminal state information for this goal. More...
 

Public Attributes

 comm_state_machine
 

Detailed Description

Client side handle to monitor goal progress.

A ClientGoalHandle is a reference counted object that is used to manipulate and monitor the progress of an already dispatched goal. Once all the goal handles go out of scope (or are reset), an ActionClient stops maintaining state for that goal.

Definition at line 110 of file action_client.py.

Constructor & Destructor Documentation

◆ __init__()

def actionlib.action_client.ClientGoalHandle.__init__ (   self,
  comm_state_machine 
)

Internal use only.

ClientGoalHandle objects should be created by the action client. You should never need to construct one yourself.

Definition at line 115 of file action_client.py.

Member Function Documentation

◆ __eq__()

def actionlib.action_client.ClientGoalHandle.__eq__ (   self,
  o 
)

True iff the two ClientGoalHandle's are tracking the same goal.

Definition at line 121 of file action_client.py.

◆ __hash__()

def actionlib.action_client.ClientGoalHandle.__hash__ (   self)

Hash function for ClientGoalHandle

Definition at line 133 of file action_client.py.

◆ __ne__()

def actionlib.action_client.ClientGoalHandle.__ne__ (   self,
  o 
)

True iff the two ClientGoalHandle's are tracking different goals.

Definition at line 127 of file action_client.py.

◆ cancel()

def actionlib.action_client.ClientGoalHandle.cancel (   self)

Sends a cancel message for this specific goal to the ActionServer.

Also transitions the client state to WAITING_FOR_CANCEL_ACK

Definition at line 139 of file action_client.py.

◆ get_comm_state()

def actionlib.action_client.ClientGoalHandle.get_comm_state (   self)

Get the state of this goal's communication state machine from interaction with the server.

Possible States are: WAITING_FOR_GOAL_ACK, PENDING, ACTIVE, WAITING_FOR_RESULT, WAITING_FOR_CANCEL_ACK, RECALLING, PREEMPTING, DONE

Returns
The current goal's communication state with the server

Definition at line 152 of file action_client.py.

◆ get_goal_status()

def actionlib.action_client.ClientGoalHandle.get_goal_status (   self)

Returns the current status of the goal.

Possible states are listed in the enumeration in the actionlib_msgs/GoalStatus message.

Returns
The current status of the goal.

Definition at line 164 of file action_client.py.

◆ get_goal_status_text()

def actionlib.action_client.ClientGoalHandle.get_goal_status_text (   self)

Returns the current status text of the goal.

The text is sent by the action server.

Returns
The current status text of the goal.

Definition at line 175 of file action_client.py.

◆ get_result()

def actionlib.action_client.ClientGoalHandle.get_result (   self)

Gets the result produced by the action server for this goal.

Returns
None if no result was receieved. Otherwise the goal's result as a *Result message.

Definition at line 184 of file action_client.py.

◆ get_terminal_state()

def actionlib.action_client.ClientGoalHandle.get_terminal_state (   self)

Gets the terminal state information for this goal.

Possible States Are: RECALLED, REJECTED, PREEMPTED, ABORTED, SUCCEEDED, LOST This call only makes sense if CommState==DONE. This will send ROS_WARNs if we're not in DONE

Returns
The terminal state as an integer from the GoalStatus message.

Definition at line 199 of file action_client.py.

Member Data Documentation

◆ comm_state_machine

actionlib.action_client.ClientGoalHandle.comm_state_machine

Definition at line 116 of file action_client.py.


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


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 28 2022 21:34:39