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

#include <client_helpers.h>

List of all members.

Public Types

typedef boost::function< void(const
actionlib_msgs::GoalID &)> 
CancelFunc
typedef boost::function< void(GoalHandleT,
const FeedbackConstPtr &) > 
FeedbackCallback
typedef ClientGoalHandle
< ActionSpec > 
GoalHandleT
typedef GoalManager< ActionSpec > GoalManagerT
typedef ManagedList
< boost::shared_ptr
< CommStateMachine< ActionSpec > > > 
ManagedListT
typedef boost::function< void(const
ActionGoalConstPtr)> 
SendGoalFunc
typedef boost::function< void(GoalHandleT) > TransitionCallback

Public Member Functions

 ACTION_DEFINITION (ActionSpec)
 GoalManager (const boost::shared_ptr< DestructionGuard > &guard)
GoalHandleT initGoal (const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
void registerCancelFunc (CancelFunc cancel_func)
void registerSendGoalFunc (SendGoalFunc send_goal_func)
void updateFeedbacks (const ActionFeedbackConstPtr &action_feedback)
void updateResults (const ActionResultConstPtr &action_result)
void updateStatuses (const actionlib_msgs::GoalStatusArrayConstPtr &status_array)

Public Attributes

ManagedListT list_

Private Member Functions

void listElemDeleter (typename ManagedListT::iterator it)

Private Attributes

CancelFunc cancel_func_
boost::shared_ptr
< DestructionGuard
guard_
GoalIDGenerator id_generator_
boost::recursive_mutex list_mutex_
SendGoalFunc send_goal_func_

Friends

class ClientGoalHandle< ActionSpec >

Detailed Description

template<class ActionSpec>
class actionlib::GoalManager< ActionSpec >

Definition at line 69 of file client_helpers.h.


Member Typedef Documentation

template<class ActionSpec >
typedef boost::function<void (const actionlib_msgs::GoalID&)> actionlib::GoalManager< ActionSpec >::CancelFunc

Definition at line 78 of file client_helpers.h.

template<class ActionSpec >
typedef boost::function<void (GoalHandleT, const FeedbackConstPtr&) > actionlib::GoalManager< ActionSpec >::FeedbackCallback

Definition at line 76 of file client_helpers.h.

template<class ActionSpec >
typedef ClientGoalHandle<ActionSpec> actionlib::GoalManager< ActionSpec >::GoalHandleT

Definition at line 74 of file client_helpers.h.

template<class ActionSpec >
typedef GoalManager<ActionSpec> actionlib::GoalManager< ActionSpec >::GoalManagerT

Definition at line 73 of file client_helpers.h.

template<class ActionSpec >
typedef ManagedList< boost::shared_ptr<CommStateMachine<ActionSpec> > > actionlib::GoalManager< ActionSpec >::ManagedListT

Definition at line 96 of file client_helpers.h.

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

Definition at line 77 of file client_helpers.h.

template<class ActionSpec >
typedef boost::function<void (GoalHandleT) > actionlib::GoalManager< ActionSpec >::TransitionCallback

Definition at line 75 of file client_helpers.h.


Constructor & Destructor Documentation

template<class ActionSpec >
actionlib::GoalManager< ActionSpec >::GoalManager ( const boost::shared_ptr< DestructionGuard > &  guard) [inline]

Definition at line 80 of file client_helpers.h.


Member Function Documentation

template<class ActionSpec >
actionlib::GoalManager< ActionSpec >::ACTION_DEFINITION ( ActionSpec  )
template<class ActionSpec >
ClientGoalHandle< ActionSpec > actionlib::GoalManager< ActionSpec >::initGoal ( const Goal &  goal,
TransitionCallback  transition_cb = TransitionCallback(),
FeedbackCallback  feedback_cb = FeedbackCallback() 
)

Definition at line 56 of file goal_manager_imp.h.

template<class ActionSpec >
void actionlib::GoalManager< ActionSpec >::listElemDeleter ( typename ManagedListT::iterator  it) [private]

Definition at line 80 of file goal_manager_imp.h.

template<class ActionSpec >
void actionlib::GoalManager< ActionSpec >::registerCancelFunc ( CancelFunc  cancel_func)

Definition at line 49 of file goal_manager_imp.h.

template<class ActionSpec >
void actionlib::GoalManager< ActionSpec >::registerSendGoalFunc ( SendGoalFunc  send_goal_func)

Definition at line 43 of file goal_manager_imp.h.

template<class ActionSpec >
void actionlib::GoalManager< ActionSpec >::updateFeedbacks ( const ActionFeedbackConstPtr &  action_feedback)

Definition at line 111 of file goal_manager_imp.h.

template<class ActionSpec >
void actionlib::GoalManager< ActionSpec >::updateResults ( const ActionResultConstPtr &  action_result)

Definition at line 125 of file goal_manager_imp.h.

template<class ActionSpec >
void actionlib::GoalManager< ActionSpec >::updateStatuses ( const actionlib_msgs::GoalStatusArrayConstPtr &  status_array)

Definition at line 97 of file goal_manager_imp.h.


Friends And Related Function Documentation

template<class ActionSpec >
friend class ClientGoalHandle< ActionSpec > [friend]

Definition at line 93 of file client_helpers.h.


Member Data Documentation

template<class ActionSpec >
CancelFunc actionlib::GoalManager< ActionSpec >::cancel_func_ [private]

Definition at line 100 of file client_helpers.h.

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

Definition at line 102 of file client_helpers.h.

template<class ActionSpec >
GoalIDGenerator actionlib::GoalManager< ActionSpec >::id_generator_ [private]

Definition at line 106 of file client_helpers.h.

template<class ActionSpec >
ManagedListT actionlib::GoalManager< ActionSpec >::list_

Definition at line 97 of file client_helpers.h.

template<class ActionSpec >
boost::recursive_mutex actionlib::GoalManager< ActionSpec >::list_mutex_ [private]

Definition at line 104 of file client_helpers.h.

template<class ActionSpec >
SendGoalFunc actionlib::GoalManager< ActionSpec >::send_goal_func_ [private]

Definition at line 99 of file client_helpers.h.


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


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Thu Jan 2 2014 11:03:50