All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines
Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
actionlib::MyActionClient< ActionSpec > Class Template Reference

#include <actionlib_controller.h>

List of all members.

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.
void cancelGoal ()
 Cancel the goal that we are currently pursuing.
void cancelGoalsAtAndBeforeTime (const ros::Time &time)
 Cancel all goals that were stamped at and before the specified time.
ResultConstPtr getResult ()
 Get the Result of the current goal.
SimpleClientGoalState getState ()
 Get the state information for this goal.
bool isGoalExpired ()
 MyActionClient (const std::string &name, bool spin_thread=true)
 Simple constructor.
 MyActionClient (ros::NodeHandle &n, const std::string &name, bool spin_thread=false)
 Constructor with namespacing options.
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.
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.
void stopTrackingGoal ()
 Stops tracking the state of the current goal. Unregisters this goal's callbacks.
bool waitForResult (const ros::Duration &timeout=ros::Duration(0, 0))
 Blocks until this goal finishes.
bool waitForServer (const ros::Duration &timeout=ros::Duration(0, 0))
 Waits for the ActionServer to connect to this client.
 ~MyActionClient ()

Private Types

typedef ActionClient< ActionSpec > ActionClientT
typedef ClientGoalHandle
< ActionSpec > 
GoalHandleT
typedef MyActionClient
< ActionSpec > 
MyActionClientT

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::MyActionClient< ActionSpec >

Definition at line 58 of file actionlib_controller.h.


Member Typedef Documentation

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

Definition at line 191 of file actionlib_controller.h.

template<class ActionSpec >
typedef ClientGoalHandle<ActionSpec> actionlib::MyActionClient< ActionSpec >::GoalHandleT [private]

Definition at line 62 of file actionlib_controller.h.

template<class ActionSpec >
typedef MyActionClient<ActionSpec> actionlib::MyActionClient< ActionSpec >::MyActionClientT [private]

Definition at line 63 of file actionlib_controller.h.

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

Definition at line 67 of file actionlib_controller.h.

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

Definition at line 66 of file actionlib_controller.h.

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

Definition at line 68 of file actionlib_controller.h.


Constructor & Destructor Documentation

template<class ActionSpec >
actionlib::MyActionClient< ActionSpec >::MyActionClient ( 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 78 of file actionlib_controller.h.

template<class ActionSpec >
actionlib::MyActionClient< ActionSpec >::MyActionClient ( ros::NodeHandle n,
const std::string name,
bool  spin_thread = false 
) [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().

Definition at line 93 of file actionlib_controller.h.

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

Definition at line 243 of file actionlib_controller.h.


Member Function Documentation

template<class ActionSpec >
actionlib::MyActionClient< ActionSpec >::ACTION_DEFINITION ( ActionSpec  ) [private]
template<class ActionSpec >
void actionlib::MyActionClient< 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 386 of file actionlib_controller.h.

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

Cancel the goal that we are currently pursuing.

Definition at line 398 of file actionlib_controller.h.

template<class ActionSpec >
void actionlib::MyActionClient< 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 392 of file actionlib_controller.h.

template<class ActionSpec >
MyActionClient< ActionSpec >::ResultConstPtr actionlib::MyActionClient< ActionSpec >::getResult ( )

Get the Result of the current goal.

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

Definition at line 373 of file actionlib_controller.h.

template<class ActionSpec >
SimpleClientGoalState actionlib::MyActionClient< ActionSpec >::getState ( )

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 MyActionClient isn't tracking a goal.

Definition at line 309 of file actionlib_controller.h.

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

Definition at line 415 of file actionlib_controller.h.

template<class ActionSpec >
void actionlib::MyActionClient< ActionSpec >::handleTransition ( GoalHandleT  gh) [private]

Definition at line 426 of file actionlib_controller.h.

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

Definition at line 226 of file actionlib_controller.h.

template<class ActionSpec >
bool actionlib::MyActionClient< ActionSpec >::isGoalExpired ( ) [inline]

Definition at line 189 of file actionlib_controller.h.

template<class ActionSpec >
void actionlib::MyActionClient< 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 288 of file actionlib_controller.h.

template<class ActionSpec >
SimpleClientGoalState actionlib::MyActionClient< 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 556 of file actionlib_controller.h.

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

Definition at line 273 of file actionlib_controller.h.

template<class ActionSpec >
void actionlib::MyActionClient< ActionSpec >::setSimpleState ( const SimpleGoalState next_state) [private]

Definition at line 279 of file actionlib_controller.h.

template<class ActionSpec >
void actionlib::MyActionClient< ActionSpec >::spinThread ( ) [private]

Definition at line 259 of file actionlib_controller.h.

template<class ActionSpec >
void actionlib::MyActionClient< 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 407 of file actionlib_controller.h.

template<class ActionSpec >
bool actionlib::MyActionClient< 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 515 of file actionlib_controller.h.

template<class ActionSpec >
bool actionlib::MyActionClient< ActionSpec >::waitForServer ( 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

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 110 of file actionlib_controller.h.


Member Data Documentation

template<class ActionSpec >
boost::scoped_ptr<ActionClientT> actionlib::MyActionClient< ActionSpec >::ac_ [private]

Definition at line 212 of file actionlib_controller.h.

template<class ActionSpec >
SimpleActiveCallback actionlib::MyActionClient< ActionSpec >::active_cb_ [private]

Definition at line 203 of file actionlib_controller.h.

template<class ActionSpec >
ros::CallbackQueue actionlib::MyActionClient< ActionSpec >::callback_queue [private]

Definition at line 210 of file actionlib_controller.h.

template<class ActionSpec >
SimpleGoalState actionlib::MyActionClient< ActionSpec >::cur_simple_state_ [private]

Definition at line 195 of file actionlib_controller.h.

template<class ActionSpec >
SimpleDoneCallback actionlib::MyActionClient< ActionSpec >::done_cb_ [private]

Definition at line 202 of file actionlib_controller.h.

template<class ActionSpec >
boost::condition actionlib::MyActionClient< ActionSpec >::done_condition_ [private]

Definition at line 198 of file actionlib_controller.h.

template<class ActionSpec >
boost::mutex actionlib::MyActionClient< ActionSpec >::done_mutex_ [private]

Definition at line 199 of file actionlib_controller.h.

template<class ActionSpec >
SimpleFeedbackCallback actionlib::MyActionClient< ActionSpec >::feedback_cb_ [private]

Definition at line 204 of file actionlib_controller.h.

template<class ActionSpec >
GoalHandleT actionlib::MyActionClient< ActionSpec >::gh_ [private]

Definition at line 193 of file actionlib_controller.h.

template<class ActionSpec >
bool actionlib::MyActionClient< ActionSpec >::need_to_terminate_ [private]

Definition at line 208 of file actionlib_controller.h.

template<class ActionSpec >
ros::NodeHandle actionlib::MyActionClient< ActionSpec >::nh_ [private]

Definition at line 192 of file actionlib_controller.h.

template<class ActionSpec >
boost::thread* actionlib::MyActionClient< ActionSpec >::spin_thread_ [private]

Definition at line 209 of file actionlib_controller.h.

template<class ActionSpec >
boost::mutex actionlib::MyActionClient< ActionSpec >::terminate_mutex_ [private]

Definition at line 207 of file actionlib_controller.h.


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


openrave_actionlib
Author(s): rdiankov
autogenerated on Sun Mar 24 2013 05:08:46