Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
actionlib::ActionClient< ActionSpec > Class Template Reference

Full interface to an ActionServer. More...

#include <action_client.h>

List of all members.

Public Types

typedef ClientGoalHandle
< ActionSpec > 
GoalHandle

Public Member Functions

 ActionClient (const std::string &name, ros::CallbackQueueInterface *queue=NULL)
 Simple constructor.
 ActionClient (const ros::NodeHandle &n, const std::string &name, ros::CallbackQueueInterface *queue=NULL)
 Constructor with namespacing options.
void cancelAllGoals ()
 Cancel all goals currently running on the action server.
void cancelGoalsAtAndBeforeTime (const ros::Time &time)
 Cancel all goals that were stamped at and before the specified time.
bool isServerConnected ()
 Checks if the action client is successfully connected to the action server.
GoalHandle sendGoal (const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
 Sends a goal to the ActionServer, and also registers callbacks.
bool waitForActionServerToStart (const ros::Duration &timeout=ros::Duration(0, 0))
 Waits for the ActionServer to connect to this client Often, it can take a second for the action server & client to negotiate a connection, thus, risking the first few goals to be dropped. This call lets the user wait until the network connection to the server is negotiated NOTE: Using this call in a single threaded ROS application, or any application where the action client's callback queue is not being serviced, will not work. Without a separate thread servicing the queue, or a multi-threaded spinner, there is no way for the client to tell whether or not the server is up because it can't receive a status message.
 ~ActionClient ()

Private Types

typedef ActionClient< ActionSpec > ActionClientT
typedef boost::function< void(GoalHandle,
const FeedbackConstPtr &)> 
FeedbackCallback
typedef boost::function< void(const
ActionGoalConstPtr)> 
SendGoalFunc
typedef boost::function< void(GoalHandle)> TransitionCallback

Private Member Functions

 ACTION_DEFINITION (ActionSpec)
void feedbackCb (const ros::MessageEvent< ActionFeedback const > &action_feedback)
void initClient (ros::CallbackQueueInterface *queue)
template<class M >
ros::Publisher queue_advertise (const std::string &topic, uint32_t queue_size, const ros::SubscriberStatusCallback &connect_cb, const ros::SubscriberStatusCallback &disconnect_cb, ros::CallbackQueueInterface *queue)
template<class M , class T >
ros::Subscriber queue_subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const ros::MessageEvent< M const > &), T *obj, ros::CallbackQueueInterface *queue)
void resultCb (const ros::MessageEvent< ActionResult const > &action_result)
void sendCancelFunc (const actionlib_msgs::GoalID &cancel_msg)
void sendGoalFunc (const ActionGoalConstPtr &action_goal)
void statusCb (const ros::MessageEvent< actionlib_msgs::GoalStatusArray const > &status_array_event)

Private Attributes

ros::Publisher cancel_pub_
boost::shared_ptr
< ConnectionMonitor
connection_monitor_
ros::Subscriber feedback_sub_
ros::Publisher goal_pub_
boost::shared_ptr
< DestructionGuard
guard_
GoalManager< ActionSpec > manager_
ros::NodeHandle n_
ros::Subscriber result_sub_
ros::Subscriber status_sub_

Detailed Description

template<class ActionSpec>
class actionlib::ActionClient< ActionSpec >

Full interface to an ActionServer.

ActionClient provides a complete client side implementation of the ActionInterface protocol. It provides callbacks for every client side transition, giving the user full observation into the client side state machine.

Definition at line 59 of file action_client.h.


Member Typedef Documentation

template<class ActionSpec>
typedef ActionClient<ActionSpec> actionlib::ActionClient< ActionSpec >::ActionClientT [private]

Definition at line 66 of file action_client.h.

template<class ActionSpec>
typedef boost::function<void (GoalHandle, const FeedbackConstPtr &)> actionlib::ActionClient< ActionSpec >::FeedbackCallback [private]

Definition at line 68 of file action_client.h.

template<class ActionSpec>
typedef ClientGoalHandle<ActionSpec> actionlib::ActionClient< ActionSpec >::GoalHandle

Definition at line 62 of file action_client.h.

template<class ActionSpec>
typedef boost::function<void (const ActionGoalConstPtr)> actionlib::ActionClient< ActionSpec >::SendGoalFunc [private]

Definition at line 69 of file action_client.h.

template<class ActionSpec>
typedef boost::function<void (GoalHandle)> actionlib::ActionClient< ActionSpec >::TransitionCallback [private]

Definition at line 67 of file action_client.h.


Constructor & Destructor Documentation

template<class ActionSpec>
actionlib::ActionClient< ActionSpec >::ActionClient ( const std::string &  name,
ros::CallbackQueueInterface queue = NULL 
) [inline]

Simple constructor.

Constructs an ActionClient and sets up the necessary ros topics for the ActionInterface

Parameters:
nameThe action name. Defines the namespace in which the action communicates
queueCallbackQueue from which this action will process messages. The default (NULL) is to use the global queue

Definition at line 80 of file action_client.h.

template<class ActionSpec>
actionlib::ActionClient< ActionSpec >::ActionClient ( const ros::NodeHandle n,
const std::string &  name,
ros::CallbackQueueInterface queue = NULL 
) [inline]

Constructor with namespacing options.

Constructs an ActionClient and sets up the necessary ros topics for the ActionInterface, and namespaces them according the a specified NodeHandle

Parameters:
nThe node handle on top of which we want to namespace our action
nameThe action name. Defines the namespace in which the action communicates
queueCallbackQueue from which this action will process messages. The default (NULL) is to use the global queue

Definition at line 97 of file action_client.h.

template<class ActionSpec>
actionlib::ActionClient< ActionSpec >::~ActionClient ( ) [inline]

Definition at line 105 of file action_client.h.


Member Function Documentation

template<class ActionSpec>
actionlib::ActionClient< ActionSpec >::ACTION_DEFINITION ( ActionSpec  ) [private]
template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::cancelAllGoals ( ) [inline]

Cancel all goals currently running on the action server.

This preempts all goals running on the action server at the point that this message is serviced by the ActionServer.

Definition at line 135 of file action_client.h.

template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::cancelGoalsAtAndBeforeTime ( const ros::Time time) [inline]

Cancel all goals that were stamped at and before the specified time.

Parameters:
timeAll goals stamped at or before `time` will be canceled

Definition at line 148 of file action_client.h.

template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::feedbackCb ( const ros::MessageEvent< ActionFeedback const > &  action_feedback) [inline, private]

Definition at line 294 of file action_client.h.

template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::initClient ( ros::CallbackQueueInterface queue) [inline, private]

Definition at line 217 of file action_client.h.

template<class ActionSpec>
bool actionlib::ActionClient< ActionSpec >::isServerConnected ( ) [inline]

Checks if the action client is successfully connected to the action server.

Returns:
True if the server is connected, false otherwise

Definition at line 187 of file action_client.h.

template<class ActionSpec>
template<class M >
ros::Publisher actionlib::ActionClient< ActionSpec >::queue_advertise ( const std::string &  topic,
uint32_t  queue_size,
const ros::SubscriberStatusCallback connect_cb,
const ros::SubscriberStatusCallback disconnect_cb,
ros::CallbackQueueInterface queue 
) [inline, private]

Definition at line 253 of file action_client.h.

template<class ActionSpec>
template<class M , class T >
ros::Subscriber actionlib::ActionClient< ActionSpec >::queue_subscribe ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(const ros::MessageEvent< M const > &)  fp,
T *  obj,
ros::CallbackQueueInterface queue 
) [inline, private]

Definition at line 267 of file action_client.h.

template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::resultCb ( const ros::MessageEvent< ActionResult const > &  action_result) [inline, private]

Definition at line 299 of file action_client.h.

template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::sendCancelFunc ( const actionlib_msgs::GoalID &  cancel_msg) [inline, private]

Definition at line 212 of file action_client.h.

template<class ActionSpec>
GoalHandle actionlib::ActionClient< ActionSpec >::sendGoal ( const Goal &  goal,
TransitionCallback  transition_cb = TransitionCallback(),
FeedbackCallback  feedback_cb = FeedbackCallback() 
) [inline]

Sends a goal to the ActionServer, and also registers callbacks.

Parameters:
transition_cbCallback that gets called on every client state transition
feedback_cbCallback that gets called whenever feedback for this goal is received

Definition at line 118 of file action_client.h.

template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::sendGoalFunc ( const ActionGoalConstPtr &  action_goal) [inline, private]

Definition at line 207 of file action_client.h.

template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::statusCb ( const ros::MessageEvent< actionlib_msgs::GoalStatusArray const > &  status_array_event) [inline, private]

Definition at line 284 of file action_client.h.

template<class ActionSpec>
bool actionlib::ActionClient< ActionSpec >::waitForActionServerToStart ( const ros::Duration timeout = ros::Duration(0, 0)) [inline]

Waits for the ActionServer to connect to this client Often, it can take a second for the action server & client to negotiate a connection, thus, risking the first few goals to be dropped. This call lets the user wait until the network connection to the server is negotiated NOTE: Using this call in a single threaded ROS application, or any application where the action client's callback queue is not being serviced, will not work. Without a separate thread servicing the queue, or a multi-threaded spinner, there is no way for the client to tell whether or not the server is up because it can't receive a status message.

Parameters:
timeoutMax time to block before returning. A zero timeout is interpreted as an infinite timeout.
Returns:
True if the server connected in the allocated time. False on timeout

Definition at line 169 of file action_client.h.


Member Data Documentation

template<class ActionSpec>
ros::Publisher actionlib::ActionClient< ActionSpec >::cancel_pub_ [private]

Definition at line 204 of file action_client.h.

template<class ActionSpec>
boost::shared_ptr<ConnectionMonitor> actionlib::ActionClient< ActionSpec >::connection_monitor_ [private]

Definition at line 201 of file action_client.h.

template<class ActionSpec>
ros::Subscriber actionlib::ActionClient< ActionSpec >::feedback_sub_ [private]

Definition at line 199 of file action_client.h.

template<class ActionSpec>
ros::Publisher actionlib::ActionClient< ActionSpec >::goal_pub_ [private]

Definition at line 203 of file action_client.h.

template<class ActionSpec>
boost::shared_ptr<DestructionGuard> actionlib::ActionClient< ActionSpec >::guard_ [private]

Definition at line 195 of file action_client.h.

template<class ActionSpec>
GoalManager<ActionSpec> actionlib::ActionClient< ActionSpec >::manager_ [private]

Definition at line 196 of file action_client.h.

template<class ActionSpec>
ros::NodeHandle actionlib::ActionClient< ActionSpec >::n_ [private]

Definition at line 193 of file action_client.h.

template<class ActionSpec>
ros::Subscriber actionlib::ActionClient< ActionSpec >::result_sub_ [private]

Definition at line 198 of file action_client.h.

template<class ActionSpec>
ros::Subscriber actionlib::ActionClient< ActionSpec >::status_sub_ [private]

Definition at line 205 of file action_client.h.


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


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Sat Feb 16 2019 03:21:29