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

A Simple client implementation of the ActionInterface which supports only one goal at a time. More...

#include <simple_action_client.h>

Public Types

typedef boost::function< void()> SimpleActiveCallback
 
typedef boost::function< void(const SimpleClientGoalState &state, const ResultConstPtr &result)> SimpleDoneCallback
 
typedef boost::function< void(const FeedbackConstPtr &feedback)> SimpleFeedbackCallback
 

Public Member Functions

void cancelAllGoals ()
 Cancel all goals currently running on the action server. More...
 
void cancelGoal ()
 Cancel the goal that we are currently pursuing. More...
 
void cancelGoalsAtAndBeforeTime (const ros::Time &time)
 Cancel all goals that were stamped at and before the specified time. More...
 
ResultConstPtr getResult () const
 Get the Result of the current goal. More...
 
SimpleClientGoalState getState () const
 Get the state information for this goal. More...
 
bool isServerConnected () const
 Checks if the action client is successfully connected to the action server. More...
 
void sendGoal (const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
 Sends a goal to the ActionServer, and also registers callbacks. More...
 
SimpleClientGoalState sendGoalAndWait (const Goal &goal, const ros::Duration &execute_timeout=ros::Duration(0, 0), const ros::Duration &preempt_timeout=ros::Duration(0, 0))
 Sends a goal to the ActionServer, and waits until the goal completes or a timeout is exceeded. More...
 
 SimpleActionClient (const std::string &name, bool spin_thread=true)
 Simple constructor. More...
 
 SimpleActionClient (ros::NodeHandle &n, const std::string &name, bool spin_thread=true)
 Constructor with namespacing options. More...
 
void stopTrackingGoal ()
 Stops tracking the state of the current goal. Unregisters this goal's callbacks. More...
 
bool waitForResult (const ros::Duration &timeout=ros::Duration(0, 0))
 Blocks until this goal finishes. More...
 
bool waitForServer (const ros::Duration &timeout=ros::Duration(0, 0)) const
 Waits for the ActionServer to connect to this client. More...
 
 ~SimpleActionClient ()
 

Private Types

typedef ActionClient< ActionSpec > ActionClientT
 
typedef ClientGoalHandle< ActionSpec > GoalHandleT
 
typedef SimpleActionClient< ActionSpec > SimpleActionClientT
 

Private Member Functions

 ACTION_DEFINITION (ActionSpec)
 
void handleFeedback (GoalHandleT gh, const FeedbackConstPtr &feedback)
 
void handleTransition (GoalHandleT gh)
 
void initSimpleClient (ros::NodeHandle &n, const std::string &name, bool spin_thread)
 
void setSimpleState (const SimpleGoalState::StateEnum &next_state)
 
void setSimpleState (const SimpleGoalState &next_state)
 
void spinThread ()
 

Private Attributes

boost::scoped_ptr< ActionClientTac_
 
SimpleActiveCallback active_cb_
 
ros::CallbackQueue callback_queue
 
SimpleGoalState cur_simple_state_
 
SimpleDoneCallback done_cb_
 
boost::condition done_condition_
 
boost::mutex done_mutex_
 
SimpleFeedbackCallback feedback_cb_
 
GoalHandleT gh_
 
bool need_to_terminate_
 
ros::NodeHandle nh_
 
boost::thread * spin_thread_
 
boost::mutex terminate_mutex_
 

Detailed Description

template<class ActionSpec>
class actionlib::SimpleActionClient< ActionSpec >

A Simple client implementation of the ActionInterface which supports only one goal at a time.

The SimpleActionClient wraps the existing ActionClient, and exposes a limited set of easy-to-use hooks for the user. Note that the concept of GoalHandles has been completely hidden from the user, and that they must query the SimplyActionClient directly in order to monitor a goal.

Definition at line 72 of file simple_action_client.h.

Member Typedef Documentation

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

Definition at line 223 of file simple_action_client.h.

template<class ActionSpec>
typedef ClientGoalHandle<ActionSpec> actionlib::SimpleActionClient< ActionSpec >::GoalHandleT
private

Definition at line 76 of file simple_action_client.h.

template<class ActionSpec>
typedef SimpleActionClient<ActionSpec> actionlib::SimpleActionClient< ActionSpec >::SimpleActionClientT
private

Definition at line 77 of file simple_action_client.h.

template<class ActionSpec>
typedef boost::function<void ()> actionlib::SimpleActionClient< ActionSpec >::SimpleActiveCallback

Definition at line 82 of file simple_action_client.h.

template<class ActionSpec>
typedef boost::function<void (const SimpleClientGoalState & state, const ResultConstPtr & result)> actionlib::SimpleActionClient< ActionSpec >::SimpleDoneCallback

Definition at line 81 of file simple_action_client.h.

template<class ActionSpec>
typedef boost::function<void (const FeedbackConstPtr & feedback)> actionlib::SimpleActionClient< ActionSpec >::SimpleFeedbackCallback

Definition at line 83 of file simple_action_client.h.

Constructor & Destructor Documentation

template<class ActionSpec>
actionlib::SimpleActionClient< ActionSpec >::SimpleActionClient ( const std::string &  name,
bool  spin_thread = true 
)
inline

Simple constructor.

Constructs a SingleGoalActionClient and sets up the necessary ros topics for the ActionInterface

Parameters
nameThe action name. Defines the namespace in which the action communicates
spin_threadIf true, spins up a thread to service this action's subscriptions. If false, then the user has to call ros::spin() themselves. Defaults to True

Definition at line 93 of file simple_action_client.h.

template<class ActionSpec>
actionlib::SimpleActionClient< ActionSpec >::SimpleActionClient ( ros::NodeHandle n,
const std::string &  name,
bool  spin_thread = true 
)
inline

Constructor with namespacing options.

Constructs a SingleGoalActionClient 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
spin_threadIf true, spins up a thread to service this action's subscriptions. If false, then the user has to call ros::spin() themselves. Defaults to True

Definition at line 109 of file simple_action_client.h.

template<class ActionSpec >
actionlib::SimpleActionClient< ActionSpec >::~SimpleActionClient ( )

Definition at line 273 of file simple_action_client.h.

Member Function Documentation

template<class ActionSpec>
actionlib::SimpleActionClient< ActionSpec >::ACTION_DEFINITION ( ActionSpec  )
private
template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::cancelAllGoals ( )

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 424 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::cancelGoal ( )

Cancel the goal that we are currently pursuing.

Definition at line 436 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::cancelGoalsAtAndBeforeTime ( const ros::Time time)

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 430 of file simple_action_client.h.

template<class ActionSpec >
SimpleActionClient< ActionSpec >::ResultConstPtr actionlib::SimpleActionClient< ActionSpec >::getResult ( ) const

Get the Result of the current goal.

Returns
shared pointer to the result. Note that this pointer will NEVER be NULL

Definition at line 407 of file simple_action_client.h.

template<class ActionSpec >
SimpleClientGoalState actionlib::SimpleActionClient< ActionSpec >::getState ( ) const

Get the state information for this goal.

Possible States Are: PENDING, ACTIVE, RECALLED, REJECTED, PREEMPTED, ABORTED, SUCCEEDED, LOST.

Returns
The goal's state. Returns LOST if this SimpleActionClient isn't tracking a goal.

Definition at line 338 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::handleFeedback ( GoalHandleT  gh,
const FeedbackConstPtr &  feedback 
)
private

Definition at line 457 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::handleTransition ( GoalHandleT  gh)
private

Definition at line 472 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::initSimpleClient ( ros::NodeHandle n,
const std::string &  name,
bool  spin_thread 
)
private

Definition at line 257 of file simple_action_client.h.

template<class ActionSpec>
bool actionlib::SimpleActionClient< ActionSpec >::isServerConnected ( ) const
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 140 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::sendGoal ( const Goal &  goal,
SimpleDoneCallback  done_cb = SimpleDoneCallback(),
SimpleActiveCallback  active_cb = SimpleActiveCallback(),
SimpleFeedbackCallback  feedback_cb = SimpleFeedbackCallback() 
)

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

If a previous goal is already active when this is called. We simply forget about that goal and start tracking the new goal. No cancel requests are made.

Parameters
done_cbCallback that gets called on transitions to Done
active_cbCallback that gets called on transitions to Active
feedback_cbCallback that gets called whenever feedback for this goal is received

Definition at line 317 of file simple_action_client.h.

template<class ActionSpec >
SimpleClientGoalState actionlib::SimpleActionClient< ActionSpec >::sendGoalAndWait ( const Goal &  goal,
const ros::Duration execute_timeout = ros::Duration(0, 0),
const ros::Duration preempt_timeout = ros::Duration(0, 0) 
)

Sends a goal to the ActionServer, and waits until the goal completes or a timeout is exceeded.

If the goal doesn't complete by the execute_timeout, then a preempt message is sent. This call then waits up to the preempt_timeout for the goal to then finish.

Parameters
goalThe goal to be sent to the ActionServer
execute_timeoutTime to wait until a preempt is sent. 0 implies wait forever
preempt_timeoutTime to wait after a preempt is sent. 0 implies wait forever
Returns
The state of the goal when this call is completed

Definition at line 610 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::setSimpleState ( const SimpleGoalState::StateEnum next_state)
private

Definition at line 302 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::setSimpleState ( const SimpleGoalState next_state)
private

Definition at line 308 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::spinThread ( )
private

Definition at line 288 of file simple_action_client.h.

template<class ActionSpec >
void actionlib::SimpleActionClient< ActionSpec >::stopTrackingGoal ( )

Stops tracking the state of the current goal. Unregisters this goal's callbacks.

This is useful if we want to make sure we stop calling our callbacks before sending a new goal. Note that this does not cancel the goal, it simply stops looking for status info about this goal.

Definition at line 447 of file simple_action_client.h.

template<class ActionSpec >
bool actionlib::SimpleActionClient< ActionSpec >::waitForResult ( const ros::Duration timeout = ros::Duration(0, 0))

Blocks until this goal finishes.

Parameters
timeoutMax time to block before returning. A zero timeout is interpreted as an infinite timeout.
Returns
True if the goal finished. False if the goal didn't finish within the allocated timeout

Definition at line 564 of file simple_action_client.h.

template<class ActionSpec>
bool actionlib::SimpleActionClient< ActionSpec >::waitForServer ( const ros::Duration timeout = ros::Duration(0, 0)) const
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 131 of file simple_action_client.h.

Member Data Documentation

template<class ActionSpec>
boost::scoped_ptr<ActionClientT> actionlib::SimpleActionClient< ActionSpec >::ac_
private

Definition at line 244 of file simple_action_client.h.

template<class ActionSpec>
SimpleActiveCallback actionlib::SimpleActionClient< ActionSpec >::active_cb_
private

Definition at line 235 of file simple_action_client.h.

template<class ActionSpec>
ros::CallbackQueue actionlib::SimpleActionClient< ActionSpec >::callback_queue
private

Definition at line 242 of file simple_action_client.h.

template<class ActionSpec>
SimpleGoalState actionlib::SimpleActionClient< ActionSpec >::cur_simple_state_
private

Definition at line 227 of file simple_action_client.h.

template<class ActionSpec>
SimpleDoneCallback actionlib::SimpleActionClient< ActionSpec >::done_cb_
private

Definition at line 234 of file simple_action_client.h.

template<class ActionSpec>
boost::condition actionlib::SimpleActionClient< ActionSpec >::done_condition_
private

Definition at line 230 of file simple_action_client.h.

template<class ActionSpec>
boost::mutex actionlib::SimpleActionClient< ActionSpec >::done_mutex_
private

Definition at line 231 of file simple_action_client.h.

template<class ActionSpec>
SimpleFeedbackCallback actionlib::SimpleActionClient< ActionSpec >::feedback_cb_
private

Definition at line 236 of file simple_action_client.h.

template<class ActionSpec>
GoalHandleT actionlib::SimpleActionClient< ActionSpec >::gh_
private

Definition at line 225 of file simple_action_client.h.

template<class ActionSpec>
bool actionlib::SimpleActionClient< ActionSpec >::need_to_terminate_
private

Definition at line 240 of file simple_action_client.h.

template<class ActionSpec>
ros::NodeHandle actionlib::SimpleActionClient< ActionSpec >::nh_
private

Definition at line 224 of file simple_action_client.h.

template<class ActionSpec>
boost::thread* actionlib::SimpleActionClient< ActionSpec >::spin_thread_
private

Definition at line 241 of file simple_action_client.h.

template<class ActionSpec>
boost::mutex actionlib::SimpleActionClient< ActionSpec >::terminate_mutex_
private

Definition at line 239 of file simple_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 Mon Feb 18 2019 03:59:59