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

#include <queued_action_server.h>

Public Types

using ExecuteCallback = boost::function< void(GoalConstPtr const &)>
 
using GoalHandle = typename actionlib::ActionServer< ActionSpec >::GoalHandle
 

Public Member Functions

bool isPreemptRequested ()
 
void publishFeedback (FeedbackConstPtr const &feedback)
 
void publishFeedback (Feedback const &feedback)
 
 QueuedActionServer (ros::NodeHandle nodeHandle, std::string const &name, ExecuteCallback callback, bool autoStart=false)
 
void setAborted (Result const &result=Result(), std::string const &text="")
 
void setPreempted (Result const &result=Result(), std::string const &text="")
 
void setSucceeded (Result const &result=Result(), std::string const &text="")
 
void shutdown ()
 
void start ()
 
 ~QueuedActionServer ()
 

Private Member Functions

void loop ()
 
void onCancelReceived (GoalHandle goal)
 
void onGoalReceived (GoalHandle goal)
 

Private Attributes

std::unique_ptr< actionlib::ActionServer< ActionSpec > > actionServer
 
ExecuteCallback callback
 
GoalHandle currentGoal
 
std::queue< GoalHandlegoalQueue
 
std::condition_variable loopCondition
 
std::thread loopThread
 
std::mutex mutex
 
ros::NodeHandle nodeHandle
 
bool preemptRequested = false
 
volatile bool shutdownRequested = false
 

Detailed Description

template<class ActionSpec>
class QueuedActionServer< ActionSpec >

An action server that remembers a queue of goals that still have to be processed. This server will never reject or cancel any requests on its own.

The API is the same as for the SimpleActionServer.

Definition at line 24 of file queued_action_server.h.

Member Typedef Documentation

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

Definition at line 30 of file queued_action_server.h.

template<class ActionSpec >
using QueuedActionServer< ActionSpec >::GoalHandle = typename actionlib::ActionServer<ActionSpec>::GoalHandle

Definition at line 28 of file queued_action_server.h.

Constructor & Destructor Documentation

template<class ActionSpec >
QueuedActionServer< ActionSpec >::QueuedActionServer ( ros::NodeHandle  nodeHandle,
std::string const &  name,
ExecuteCallback  callback,
bool  autoStart = false 
)
inline

Definition at line 33 of file queued_action_server.h.

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

Definition at line 47 of file queued_action_server.h.

Member Function Documentation

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

Definition at line 67 of file queued_action_server.h.

template<class ActionSpec >
void QueuedActionServer< ActionSpec >::loop ( )
inlineprivate

Definition at line 136 of file queued_action_server.h.

template<class ActionSpec >
void QueuedActionServer< ActionSpec >::onCancelReceived ( GoalHandle  goal)
inlineprivate

Definition at line 116 of file queued_action_server.h.

template<class ActionSpec >
void QueuedActionServer< ActionSpec >::onGoalReceived ( GoalHandle  goal)
inlineprivate

Definition at line 107 of file queued_action_server.h.

template<class ActionSpec >
void QueuedActionServer< ActionSpec >::publishFeedback ( FeedbackConstPtr const &  feedback)
inline

Definition at line 96 of file queued_action_server.h.

template<class ActionSpec >
void QueuedActionServer< ActionSpec >::publishFeedback ( Feedback const &  feedback)
inline

Definition at line 101 of file queued_action_server.h.

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

Definition at line 80 of file queued_action_server.h.

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

Definition at line 88 of file queued_action_server.h.

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

Definition at line 72 of file queued_action_server.h.

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

Definition at line 58 of file queued_action_server.h.

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

Definition at line 52 of file queued_action_server.h.

Member Data Documentation

template<class ActionSpec >
std::unique_ptr<actionlib::ActionServer<ActionSpec> > QueuedActionServer< ActionSpec >::actionServer
private

Definition at line 189 of file queued_action_server.h.

template<class ActionSpec >
ExecuteCallback QueuedActionServer< ActionSpec >::callback
private

Definition at line 196 of file queued_action_server.h.

template<class ActionSpec >
GoalHandle QueuedActionServer< ActionSpec >::currentGoal
private

Definition at line 198 of file queued_action_server.h.

template<class ActionSpec >
std::queue<GoalHandle> QueuedActionServer< ActionSpec >::goalQueue
private

Definition at line 199 of file queued_action_server.h.

template<class ActionSpec >
std::condition_variable QueuedActionServer< ActionSpec >::loopCondition
private

Definition at line 194 of file queued_action_server.h.

template<class ActionSpec >
std::thread QueuedActionServer< ActionSpec >::loopThread
private

Definition at line 191 of file queued_action_server.h.

template<class ActionSpec >
std::mutex QueuedActionServer< ActionSpec >::mutex
private

Definition at line 193 of file queued_action_server.h.

template<class ActionSpec >
ros::NodeHandle QueuedActionServer< ActionSpec >::nodeHandle
private

Definition at line 188 of file queued_action_server.h.

template<class ActionSpec >
bool QueuedActionServer< ActionSpec >::preemptRequested = false
private

Definition at line 202 of file queued_action_server.h.

template<class ActionSpec >
volatile bool QueuedActionServer< ActionSpec >::shutdownRequested = false
private

Definition at line 204 of file queued_action_server.h.


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


ensenso_camera
Author(s): Ensenso
autogenerated on Thu May 6 2021 02:50:06