flexbe_core.proxy.proxy_action_client module
A proxy for calling actions provides a single point for all state action interfaces.
- class flexbe_core.proxy.proxy_action_client.ProxyActionClient(topics=None, wait_duration=10)
Bases:
object
A proxy for calling actions.
- classmethod cancel(topic)
Cancel the current action call on the given action topic.
@type topic: string @param topic: The topic of interest.
- classmethod destroy_client(client, topic)
Handle client destruction from within the executor threads.
- classmethod get_feedback(topic)
Return the latest feedback message of the given action call.
@type topic: string @param topic: The topic of interest.
- classmethod get_result(topic)
Return the result message of the given action call.
@type topic: string @param topic: The topic of interest.
- classmethod get_state(topic)
Determine 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.
- classmethod has_feedback(topic)
Check if the given action call has any feedback.
@type topic: string @param topic: The topic of interest.
- classmethod has_result(topic)
Check if the given action call already has a result.
@type topic: string @param topic: The topic of interest.
- static initialize(node)
Initialize ROS setup for proxy action client.
- classmethod is_active(topic)
Determine if an action request is already being processed on the given topic.
@type topic: string @param topic: The topic of interest.
- classmethod is_available(topic)
Check if the client and server for the given action topic is available.
@type topic: string @param topic: The topic of interest.
- classmethod remove_feedback(topic)
Remove the latest feedback message of the given action call.
@type topic: string @param topic: The topic of interest.
- classmethod remove_result(topic)
Remove the latest results of the given action call.
@type topic: string @param topic: The topic of interest.
- classmethod send_goal(topic, goal, wait_duration=0.0)
Call action 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.
@type wait_duration: float seconds @param wait_duration: How long to wait for server
- classmethod setupClient(topic, action_type, wait_duration=10)
Set up an action client for calling it later.
@type topic: string @param topic: The topic of the action to call.
@type action_type: action type @param action_type: The type of Action for 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.
- static shutdown()
Shuts this proxy down by reseting all action clients.