Client side handle to monitor goal progress. More...
Public Member Functions | |
def | __eq__ |
True iff the two ClientGoalHandle's are tracking the same goal. | |
def | __hash__ |
Hash function for ClientGoalHandle | |
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 |
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.
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.
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 function for ClientGoalHandle
Definition at line 133 of file action_client.py.
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.
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 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
Definition at line 152 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.
Definition at line 164 of file action_client.py.
Returns the current status text of the goal.
The text is sent by the action server.
Definition at line 175 of file action_client.py.
Gets the result produced by the action server for this goal.
Definition at line 184 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
Definition at line 199 of file action_client.py.
Definition at line 115 of file action_client.py.