|
def | __init__ (self, topics={}, wait_duration=10) |
|
def | cancel (self, topic) |
|
def | get_feedback (self, topic) |
|
def | get_result (self, topic) |
|
def | get_state (self, topic) |
|
def | has_feedback (self, topic) |
|
def | has_result (self, topic) |
|
def | is_active (self, topic) |
|
def | is_available (self, topic) |
|
def | remove_feedback (self, topic) |
|
def | remove_result (self, topic) |
|
def | send_goal (self, topic, goal) |
|
def | setupClient (self, topic, msg_type, wait_duration=10) |
|
A proxy for calling actions.
Definition at line 12 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.__init__ |
( |
|
self, |
|
|
|
topics = {} , |
|
|
|
wait_duration = 10 |
|
) |
| |
Initializes the proxy with optionally a given set of clients.
@type topics: dictionary string - message class
@param topics: A dictionay containing a collection of topic - message type pairs.
@type wait_duration: int
@param wait_duration: Defines how long to wait for each client in the
given set to become available (if it is not already available).
Definition at line 21 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient._done_callback |
( |
|
self, |
|
|
|
topic, |
|
|
|
terminal_state, |
|
|
|
result |
|
) |
| |
|
private |
def flexbe_core.proxy.proxy_action_client.ProxyActionClient._feedback_callback |
( |
|
self, |
|
|
|
topic, |
|
|
|
feedback |
|
) |
| |
|
private |
def flexbe_core.proxy.proxy_action_client.ProxyActionClient._print_wait_warning |
( |
|
self, |
|
|
|
topic |
|
) |
| |
|
private |
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.cancel |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Cancels the current action call on the given action topic.
@type topic: string
@param topic: The topic of interest.
Definition at line 180 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.get_feedback |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Returns the latest feedback message of the given action call.
@type topic: string
@param topic: The topic of interest.
Definition at line 143 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.get_result |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Returns the result message of the given action call.
@type topic: string
@param topic: The topic of interest.
Definition at line 116 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.get_state |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Determines the current actionlib state of the given action topic.
A list of possible states is defined in actionlib_msgs/GoalStatus.
@type topic: string
@param topic: The topic of interest.
Definition at line 161 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.has_feedback |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Checks if the given action call has any feedback.
@type topic: string
@param topic: The topic of interest.
Definition at line 134 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.has_result |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Checks if the given action call already has a result.
@type topic: string
@param topic: The topic of interest.
Definition at line 107 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.is_active |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Determines if an action request is already being processed on the given topic.
@type topic: string
@param topic: The topic of interest.
Definition at line 171 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.is_available |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Checks if the client on the given action topic is available.
@type topic: string
@param topic: The topic of interest.
Definition at line 98 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.remove_feedback |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Removes the latest feedback message of the given action call.
@type topic: string
@param topic: The topic of interest.
Definition at line 152 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.remove_result |
( |
|
self, |
|
|
|
topic |
|
) |
| |
Removes the latest result message of the given action call.
@type topic: string
@param topic: The topic of interest.
Definition at line 125 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.send_goal |
( |
|
self, |
|
|
|
topic, |
|
|
|
goal |
|
) |
| |
Performs an action call on the given topic.
@type topic: string
@param topic: The topic to call.
@type goal: action goal
@param goal: The request to send to the action server.
Definition at line 70 of file proxy_action_client.py.
def flexbe_core.proxy.proxy_action_client.ProxyActionClient.setupClient |
( |
|
self, |
|
|
|
topic, |
|
|
|
msg_type, |
|
|
|
wait_duration = 10 |
|
) |
| |
Tries to set up an action client for calling it later.
@type topic: string
@param topic: The topic of the action to call.
@type msg_type: msg type
@param msg_type: The type of messages of this action client.
@type wait_duration: int
@param wait_duration: Defines how long to wait for the given client if it is not available right now.
Definition at line 37 of file proxy_action_client.py.
dictionary flexbe_core.proxy.proxy_action_client.ProxyActionClient._clients = {} |
|
staticprivate |
dictionary flexbe_core.proxy.proxy_action_client.ProxyActionClient._feedback = {} |
|
staticprivate |
dictionary flexbe_core.proxy.proxy_action_client.ProxyActionClient._result = {} |
|
staticprivate |
The documentation for this class was generated from the following file: