Public Member Functions | Public Attributes
actionlib.action_client.ClientGoalHandle Class Reference

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

List of all members.

Public Member Functions

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

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 106 of file action_client.py.


Constructor & Destructor Documentation

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 111 of file action_client.py.


Member Function Documentation

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

Definition at line 117 of file action_client.py.

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

Definition at line 123 of file action_client.py.

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

Also transitions the client state to WAITING_FOR_CANCEL_ACK

Definition at line 132 of file action_client.py.

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 145 of file action_client.py.

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 157 of file action_client.py.

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 168 of file action_client.py.

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 177 of file action_client.py.

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 192 of file action_client.py.


Member Data Documentation

Definition at line 111 of file action_client.py.


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


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Fri Aug 28 2015 10:04:41