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

Full interface to an ActionServer. More...

#include <action_client.h>

Public Types

typedef ClientGoalHandle< ActionSpec > GoalHandle
 

Public Member Functions

 ActionClient (const ros::NodeHandle &n, const std::string &name, ros::CallbackQueueInterface *queue=nullptr)
 Constructor with namespacing options. More...
 
 ActionClient (const std::string &name, ros::CallbackQueueInterface *queue=nullptr)
 Simple constructor. More...
 
void cancelAllGoals ()
 Cancel all goals currently running on the action server. More...
 
void cancelGoalsAtAndBeforeTime (const ros::Time &time)
 Cancel all goals that were stamped at and before the specified time. More...
 
bool isServerConnected ()
 Checks if the action client is successfully connected to the action server. More...
 
GoalHandle sendGoal (const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
 Sends a goal to the ActionServer, and also registers callbacks. More...
 
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. More...
 
 ~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

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< ConnectionMonitorconnection_monitor_
 
ros::Subscriber feedback_sub_
 
ros::Publisher goal_pub_
 
boost::shared_ptr< DestructionGuardguard_
 
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 91 of file action_client.h.

Member Typedef Documentation

◆ ActionClientT

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

Definition at line 130 of file action_client.h.

◆ FeedbackCallback

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

Definition at line 132 of file action_client.h.

◆ GoalHandle

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

Definition at line 126 of file action_client.h.

◆ SendGoalFunc

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

Definition at line 133 of file action_client.h.

◆ TransitionCallback

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

Definition at line 131 of file action_client.h.

Constructor & Destructor Documentation

◆ ActionClient() [1/2]

template<class ActionSpec >
actionlib::ActionClient< ActionSpec >::ActionClient ( const std::string &  name,
ros::CallbackQueueInterface queue = nullptr 
)
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 (nullptr) is to use the global queue

Definition at line 144 of file action_client.h.

◆ ActionClient() [2/2]

template<class ActionSpec >
actionlib::ActionClient< ActionSpec >::ActionClient ( const ros::NodeHandle n,
const std::string &  name,
ros::CallbackQueueInterface queue = nullptr 
)
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 (nullptr) is to use the global queue

Definition at line 161 of file action_client.h.

◆ ~ActionClient()

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

Definition at line 169 of file action_client.h.

Member Function Documentation

◆ cancelAllGoals()

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

◆ cancelGoalsAtAndBeforeTime()

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

◆ feedbackCb()

template<class ActionSpec >
void actionlib::ActionClient< ActionSpec >::feedbackCb ( const ros::MessageEvent< ActionFeedback const > &  action_feedback)
inlineprivate

Definition at line 358 of file action_client.h.

◆ initClient()

template<class ActionSpec >
void actionlib::ActionClient< ActionSpec >::initClient ( ros::CallbackQueueInterface queue)
inlineprivate

Definition at line 281 of file action_client.h.

◆ isServerConnected()

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

◆ queue_advertise()

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 
)
inlineprivate

Definition at line 317 of file action_client.h.

◆ queue_subscribe()

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 
)
inlineprivate

Definition at line 331 of file action_client.h.

◆ resultCb()

template<class ActionSpec >
void actionlib::ActionClient< ActionSpec >::resultCb ( const ros::MessageEvent< ActionResult const > &  action_result)
inlineprivate

Definition at line 363 of file action_client.h.

◆ sendCancelFunc()

template<class ActionSpec >
void actionlib::ActionClient< ActionSpec >::sendCancelFunc ( const actionlib_msgs::GoalID &  cancel_msg)
inlineprivate

Definition at line 276 of file action_client.h.

◆ sendGoal()

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

◆ sendGoalFunc()

template<class ActionSpec >
void actionlib::ActionClient< ActionSpec >::sendGoalFunc ( const ActionGoalConstPtr &  action_goal)
inlineprivate

Definition at line 271 of file action_client.h.

◆ statusCb()

template<class ActionSpec >
void actionlib::ActionClient< ActionSpec >::statusCb ( const ros::MessageEvent< actionlib_msgs::GoalStatusArray const > &  status_array_event)
inlineprivate

Definition at line 348 of file action_client.h.

◆ waitForActionServerToStart()

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

Member Data Documentation

◆ cancel_pub_

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

Definition at line 268 of file action_client.h.

◆ connection_monitor_

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

Definition at line 265 of file action_client.h.

◆ feedback_sub_

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

Definition at line 263 of file action_client.h.

◆ goal_pub_

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

Definition at line 267 of file action_client.h.

◆ guard_

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

Definition at line 259 of file action_client.h.

◆ manager_

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

Definition at line 260 of file action_client.h.

◆ n_

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

Definition at line 257 of file action_client.h.

◆ result_sub_

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

Definition at line 262 of file action_client.h.

◆ status_sub_

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

Definition at line 269 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 Fri May 19 2023 02:36:55