Public Member Functions | Private Member Functions | Static Private Attributes
flexbe_core.proxy.proxy_action_client.ProxyActionClient Class Reference

List of all members.

Public Member Functions

def __init__
def cancel
def get_feedback
def get_result
def get_state
def has_feedback
def has_result
def is_active
def is_available
def remove_feedback
def remove_result
def send_goal
def setupClient

Private Member Functions

def _done_callback
def _feedback_callback
def _print_wait_warning

Static Private Attributes

dictionary _clients = {}
dictionary _feedback = {}
dictionary _result = {}

Detailed Description

A proxy for calling actions.

Definition at line 12 of file proxy_action_client.py.


Constructor & Destructor Documentation

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.


Member Function Documentation

def flexbe_core.proxy.proxy_action_client.ProxyActionClient._done_callback (   self,
  topic,
  terminal_state,
  result 
) [private]

Definition at line 91 of file proxy_action_client.py.

def flexbe_core.proxy.proxy_action_client.ProxyActionClient._feedback_callback (   self,
  topic,
  feedback 
) [private]

Definition at line 94 of file proxy_action_client.py.

Definition at line 189 of file proxy_action_client.py.

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.

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.

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.

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.

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.

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.

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.

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.

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.

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.

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.


Member Data Documentation

Definition at line 16 of file proxy_action_client.py.

Definition at line 19 of file proxy_action_client.py.

Definition at line 18 of file proxy_action_client.py.


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


flexbe_core
Author(s): Philipp Schillinger
autogenerated on Thu Jun 6 2019 19:32:27