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

#include <client_helpers.h>

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

 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< DestructionGuardguard_
 
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 102 of file client_helpers.h.

Member Typedef Documentation

◆ CancelFunc

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

Definition at line 111 of file client_helpers.h.

◆ FeedbackCallback

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

Definition at line 109 of file client_helpers.h.

◆ GoalHandleT

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

Definition at line 107 of file client_helpers.h.

◆ GoalManagerT

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

Definition at line 106 of file client_helpers.h.

◆ ManagedListT

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

Definition at line 130 of file client_helpers.h.

◆ SendGoalFunc

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

Definition at line 110 of file client_helpers.h.

◆ TransitionCallback

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

Definition at line 108 of file client_helpers.h.

Constructor & Destructor Documentation

◆ GoalManager()

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

Definition at line 113 of file client_helpers.h.

Member Function Documentation

◆ initGoal()

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

Definition at line 93 of file goal_manager_imp.h.

◆ listElemDeleter()

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

Definition at line 122 of file goal_manager_imp.h.

◆ registerCancelFunc()

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

Definition at line 86 of file goal_manager_imp.h.

◆ registerSendGoalFunc()

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

Definition at line 80 of file goal_manager_imp.h.

◆ updateFeedbacks()

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

Definition at line 158 of file goal_manager_imp.h.

◆ updateResults()

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

Definition at line 171 of file goal_manager_imp.h.

◆ updateStatuses()

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

Definition at line 144 of file goal_manager_imp.h.

Friends And Related Function Documentation

◆ ClientGoalHandle< ActionSpec >

template<class ActionSpec >
friend class ClientGoalHandle< ActionSpec >
friend

Definition at line 127 of file client_helpers.h.

Member Data Documentation

◆ cancel_func_

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

Definition at line 135 of file client_helpers.h.

◆ guard_

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

Definition at line 137 of file client_helpers.h.

◆ id_generator_

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

Definition at line 141 of file client_helpers.h.

◆ list_

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

Definition at line 131 of file client_helpers.h.

◆ list_mutex_

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

Definition at line 139 of file client_helpers.h.

◆ send_goal_func_

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

Definition at line 134 of file client_helpers.h.


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


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55