$search

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 ros::NodeHandle &n, const std::string &name, ros::CallbackQueueInterface *queue=NULL)
 Constructor with namespacing options.
 ActionClient (const std::string &name, ros::CallbackQueueInterface *queue=NULL)
 Simple constructor.
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.
 ~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 ActionFeedbackConstPtr &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 boost::shared_ptr< M const > &), T *obj, ros::CallbackQueueInterface *queue)
void resultCb (const ActionResultConstPtr &action_result)
void sendCancelFunc (const actionlib_msgs::GoalID &cancel_msg)
void sendGoalFunc (const ActionGoalConstPtr &action_goal)
void statusCb (const actionlib_msgs::GoalStatusArrayConstPtr &status_array)

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 57 of file action_client.h.


Member Typedef Documentation

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

Definition at line 64 of file action_client.h.

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

Definition at line 66 of file action_client.h.

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

Definition at line 60 of file action_client.h.

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

Definition at line 67 of file action_client.h.

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

Definition at line 65 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:
name The action name. Defines the namespace in which the action communicates
queue CallbackQueue from which this action will process messages. The default (NULL) is to use the global queue

Definition at line 78 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:
n The node handle on top of which we want to namespace our action
name The action name. Defines the namespace in which the action communicates
queue CallbackQueue from which this action will process messages. The default (NULL) is to use the global queue

Definition at line 95 of file action_client.h.

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

Definition at line 102 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 132 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:
time All goals stamped at or before `time` will be canceled

Definition at line 145 of file action_client.h.

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

Definition at line 256 of file action_client.h.

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

Definition at line 201 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 171 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 225 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 boost::shared_ptr< M const > &)  fp,
T *  obj,
ros::CallbackQueueInterface queue 
) [inline, private]

Definition at line 239 of file action_client.h.

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

Definition at line 261 of file action_client.h.

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

Definition at line 196 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_cb Callback that gets called on every client state transition
feedback_cb Callback that gets called whenever feedback for this goal is received

Definition at line 115 of file action_client.h.

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

Definition at line 191 of file action_client.h.

template<class ActionSpec>
void actionlib::ActionClient< ActionSpec >::statusCb ( const actionlib_msgs::GoalStatusArrayConstPtr status_array  )  [inline, private]

Definition at line 248 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.

Definition at line 159 of file action_client.h.


Member Data Documentation

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

Definition at line 188 of file action_client.h.

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

Definition at line 185 of file action_client.h.

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

Definition at line 183 of file action_client.h.

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

Definition at line 187 of file action_client.h.

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

Definition at line 179 of file action_client.h.

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

Definition at line 180 of file action_client.h.

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

Definition at line 177 of file action_client.h.

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

Definition at line 182 of file action_client.h.

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

Definition at line 189 of file action_client.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Fri Mar 1 15:00:03 2013