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 = ensenso::std::function< void(GoalConstPtr const &)>
 
using GoalHandle = typename actionlib::ActionServer< ActionSpec >::GoalHandle
 

Public Member Functions

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

Private Member Functions

std::string getLoggerName ()
 
void loop ()
 
void onCancelReceived (GoalHandle goal)
 
void onGoalReceived (GoalHandle goal)
 
void shutdown ()
 

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
 
std::string name
 
ensenso::ros::NodeHandle nh
 
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 26 of file queued_action_server.h.

Member Typedef Documentation

◆ ExecuteCallback

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

Definition at line 32 of file queued_action_server.h.

◆ GoalHandle

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

Definition at line 30 of file queued_action_server.h.

Constructor & Destructor Documentation

◆ QueuedActionServer()

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

Definition at line 35 of file queued_action_server.h.

◆ ~QueuedActionServer()

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

Definition at line 49 of file queued_action_server.h.

Member Function Documentation

◆ getLoggerName()

template<class ActionSpec >
std::string QueuedActionServer< ActionSpec >::getLoggerName ( )
inlineprivate

Definition at line 109 of file queued_action_server.h.

◆ isPreemptRequested()

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

Definition at line 60 of file queued_action_server.h.

◆ loop()

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

Definition at line 141 of file queued_action_server.h.

◆ onCancelReceived()

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

Definition at line 123 of file queued_action_server.h.

◆ onGoalReceived()

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

Definition at line 114 of file queued_action_server.h.

◆ publishFeedback() [1/2]

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

Definition at line 94 of file queued_action_server.h.

◆ publishFeedback() [2/2]

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

Definition at line 89 of file queued_action_server.h.

◆ setAborted()

template<class ActionSpec >
void QueuedActionServer< ActionSpec >::setAborted ( Result  result = Result())
inline

Definition at line 73 of file queued_action_server.h.

◆ setPreempted()

template<class ActionSpec >
void QueuedActionServer< ActionSpec >::setPreempted ( Result  result = Result())
inline

Definition at line 81 of file queued_action_server.h.

◆ setSucceeded()

template<class ActionSpec >
void QueuedActionServer< ActionSpec >::setSucceeded ( Result  result = Result())
inline

Definition at line 65 of file queued_action_server.h.

◆ shutdown()

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

Definition at line 100 of file queued_action_server.h.

◆ start()

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

Definition at line 54 of file queued_action_server.h.

Member Data Documentation

◆ actionServer

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

Definition at line 193 of file queued_action_server.h.

◆ callback

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

Definition at line 200 of file queued_action_server.h.

◆ currentGoal

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

Definition at line 202 of file queued_action_server.h.

◆ goalQueue

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

Definition at line 203 of file queued_action_server.h.

◆ loopCondition

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

Definition at line 198 of file queued_action_server.h.

◆ loopThread

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

Definition at line 195 of file queued_action_server.h.

◆ mutex

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

Definition at line 197 of file queued_action_server.h.

◆ name

template<class ActionSpec >
std::string QueuedActionServer< ActionSpec >::name
private

Definition at line 192 of file queued_action_server.h.

◆ nh

template<class ActionSpec >
ensenso::ros::NodeHandle QueuedActionServer< ActionSpec >::nh
private

Definition at line 191 of file queued_action_server.h.

◆ preemptRequested

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

Definition at line 206 of file queued_action_server.h.

◆ shutdownRequested

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

Definition at line 208 of file queued_action_server.h.


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


ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46