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

#include <queued_action_server.h>

Public Types

typedef boost::function< void(const GoalConstPtr &)> ExecuteCallback
 
typedef ActionServer< ActionSpec >::GoalHandle GoalHandle
 

Public Member Functions

boost::shared_ptr< const Goal > acceptNewGoal ()
 
 ACTION_DEFINITION (ActionSpec)
 
bool isActive ()
 
bool isNewGoalAvailable ()
 
bool isPreemptRequested ()
 
 QueuedActionServer (std::string name, ExecuteCallback execute_callback)
 
 QueuedActionServer (ros::NodeHandle n, std::string name, ExecuteCallback execute_callback)
 
void setAborted (const Result &result=Result(), const std::string &text=std::string(""))
 
void setPreempted (const Result &result=Result(), const std::string &text=std::string(""))
 
void setSucceeded (const Result &result=Result(), const std::string &text=std::string(""))
 
void shutdown ()
 
void start ()
 
 ~QueuedActionServer ()
 

Private Member Functions

void executeLoop ()
 
void goalCallback (GoalHandle preempt)
 
void preemptCallback (GoalHandle preempt)
 

Private Attributes

std::shared_ptr< ActionServer< ActionSpec > > as
 
GoalHandle current_goal
 
ExecuteCallback execute_callback
 
std::condition_variable_any execute_condition
 
std::thread * execute_thread
 
std::recursive_mutex lock
 
ros::NodeHandle n_
 
std::atomic< bool > need_to_terminate
 
bool new_goal_
 
bool new_goal_preempt_request_
 
GoalHandle next_goal
 
bool preempt_request_
 

Detailed Description

template<class ActionSpec>
class actionlib::QueuedActionServer< ActionSpec >

Definition at line 51 of file queued_action_server.h.

Member Typedef Documentation

template<class ActionSpec >
typedef boost::function<void(const GoalConstPtr &)> actionlib::QueuedActionServer< ActionSpec >::ExecuteCallback

Definition at line 58 of file queued_action_server.h.

template<class ActionSpec >
typedef ActionServer<ActionSpec>::GoalHandle actionlib::QueuedActionServer< ActionSpec >::GoalHandle

Definition at line 57 of file queued_action_server.h.

Constructor & Destructor Documentation

template<class ActionSpec >
actionlib::QueuedActionServer< ActionSpec >::QueuedActionServer ( std::string  name,
ExecuteCallback  execute_callback 
)

Definition at line 47 of file queued_action_server_imp.h.

template<class ActionSpec >
actionlib::QueuedActionServer< ActionSpec >::QueuedActionServer ( ros::NodeHandle  n,
std::string  name,
ExecuteCallback  execute_callback 
)

Definition at line 66 of file queued_action_server_imp.h.

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

Definition at line 86 of file queued_action_server_imp.h.

Member Function Documentation

template<class ActionSpec >
boost::shared_ptr< const typename QueuedActionServer< ActionSpec >::Goal > actionlib::QueuedActionServer< ActionSpec >::acceptNewGoal ( )

Definition at line 108 of file queued_action_server_imp.h.

template<class ActionSpec >
actionlib::QueuedActionServer< ActionSpec >::ACTION_DEFINITION ( ActionSpec  )
template<class ActionSpec >
void actionlib::QueuedActionServer< ActionSpec >::executeLoop ( )
private

Definition at line 226 of file queued_action_server_imp.h.

template<class ActionSpec >
void actionlib::QueuedActionServer< ActionSpec >::goalCallback ( GoalHandle  preempt)
private

Definition at line 175 of file queued_action_server_imp.h.

template<class ActionSpec >
bool actionlib::QueuedActionServer< ActionSpec >::isActive ( )

Definition at line 144 of file queued_action_server_imp.h.

template<class ActionSpec >
bool actionlib::QueuedActionServer< ActionSpec >::isNewGoalAvailable ( )

Definition at line 134 of file queued_action_server_imp.h.

template<class ActionSpec >
bool actionlib::QueuedActionServer< ActionSpec >::isPreemptRequested ( )

Definition at line 139 of file queued_action_server_imp.h.

template<class ActionSpec >
void actionlib::QueuedActionServer< ActionSpec >::preemptCallback ( GoalHandle  preempt)
private

Definition at line 206 of file queued_action_server_imp.h.

template<class ActionSpec >
void actionlib::QueuedActionServer< ActionSpec >::setAborted ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Definition at line 161 of file queued_action_server_imp.h.

template<class ActionSpec >
void actionlib::QueuedActionServer< ActionSpec >::setPreempted ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Definition at line 168 of file queued_action_server_imp.h.

template<class ActionSpec >
void actionlib::QueuedActionServer< ActionSpec >::setSucceeded ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Definition at line 154 of file queued_action_server_imp.h.

template<class ActionSpec >
void actionlib::QueuedActionServer< ActionSpec >::shutdown ( )

Definition at line 93 of file queued_action_server_imp.h.

template<class ActionSpec >
void actionlib::QueuedActionServer< ActionSpec >::start ( )

Definition at line 272 of file queued_action_server_imp.h.

Member Data Documentation

template<class ActionSpec >
std::shared_ptr<ActionServer<ActionSpec> > actionlib::QueuedActionServer< ActionSpec >::as
private

Definition at line 82 of file queued_action_server.h.

template<class ActionSpec >
GoalHandle actionlib::QueuedActionServer< ActionSpec >::current_goal
private

Definition at line 84 of file queued_action_server.h.

template<class ActionSpec >
ExecuteCallback actionlib::QueuedActionServer< ActionSpec >::execute_callback
private

Definition at line 90 of file queued_action_server.h.

template<class ActionSpec >
std::condition_variable_any actionlib::QueuedActionServer< ActionSpec >::execute_condition
private

Definition at line 91 of file queued_action_server.h.

template<class ActionSpec >
std::thread* actionlib::QueuedActionServer< ActionSpec >::execute_thread
private

Definition at line 92 of file queued_action_server.h.

template<class ActionSpec >
std::recursive_mutex actionlib::QueuedActionServer< ActionSpec >::lock
private

Definition at line 88 of file queued_action_server.h.

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

Definition at line 80 of file queued_action_server.h.

template<class ActionSpec >
std::atomic<bool> actionlib::QueuedActionServer< ActionSpec >::need_to_terminate
private

Definition at line 94 of file queued_action_server.h.

template<class ActionSpec >
bool actionlib::QueuedActionServer< ActionSpec >::new_goal_
private

Definition at line 86 of file queued_action_server.h.

template<class ActionSpec >
bool actionlib::QueuedActionServer< ActionSpec >::new_goal_preempt_request_
private

Definition at line 86 of file queued_action_server.h.

template<class ActionSpec >
GoalHandle actionlib::QueuedActionServer< ActionSpec >::next_goal
private

Definition at line 84 of file queued_action_server.h.

template<class ActionSpec >
bool actionlib::QueuedActionServer< ActionSpec >::preempt_request_
private

Definition at line 86 of file queued_action_server.h.


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


move_basic
Author(s): Jim Vaughan
autogenerated on Fri Mar 26 2021 02:46:58