Public Member Functions | Protected Types | Protected Member Functions | Private Types | Private Member Functions | Private Attributes
convenience_ros_functions::ActionServer< ActionMessage > Class Template Reference

Helper class with an action server and commonly required fields already defined. Can be derived to provide a new action server. More...

#include <ActionServer.h>

List of all members.

Public Member Functions

 ActionServer (ros::NodeHandle &_node, const std::string &action_topic)
bool executingGoal ()
bool init ()
void shutdown ()
virtual ~ActionServer ()

Protected Types

typedef ActionFeedbackConstPtr ActionFeedbackConstPtrT
typedef ActionFeedback ActionFeedbackT
typedef ActionGoalConstPtr ActionGoalConstPtrT
typedef
ROSActionServerT::GoalHandle 
ActionGoalHandleT
typedef ActionGoalPtr ActionGoalPtrT
typedef ActionGoal ActionGoalT
typedef ActionResultConstPtr ActionResultConstPtrT
typedef ActionResult ActionResultT
typedef FeedbackConstPtr FeedbackConstPtrT
typedef Feedback FeedbackT
typedef GoalConstPtr GoalConstPtrT
typedef Goal GoalT
typedef ResultConstPtr ResultConstPtrT
typedef Result ResultT
typedef ROSActionServerTROSActionServerPtr
typedef
actionlib::ActionServer
< ActionMessage > 
ROSActionServerT
typedef ActionServer
< ActionMessage > 
Self

Protected Member Functions

virtual void actionCallbackImpl (const ActionGoalHandleT &goal)=0
virtual void actionCancelCallbackImpl (const ActionGoalHandleT &goal)
virtual bool canAccept (const ActionGoalHandleT &goal)=0
void currentActionDone (ResultT &result, const actionlib::SimpleClientGoalState &state)
void currentActionDone (const actionlib::SimpleClientGoalState &state)
void currentActionSuccess (const bool success)
virtual bool initImpl ()
virtual void shutdownImpl ()
double timeRunning ()
virtual float waitForExecution (float timeout)

Private Types

typedef
baselib_binding::condition_variable 
condition_variable
typedef baselib_binding::mutex mutex
typedef
baselib_binding::recursive_mutex 
recursive_mutex
typedef
baselib_binding::unique_lock
< mutex >::type 
unique_lock
typedef
baselib_binding::unique_lock
< recursive_mutex >::type 
unique_recursive_lock

Private Member Functions

void actionCallback (ActionGoalHandleT &goal)
void actionCancelCallback (ActionGoalHandleT &goal)
void deleteServer ()
bool hasCurrentGoal ()
void startServer ()

Private Attributes

ROSActionServerPtr actionServer
std::string actionTopic
ActionGoalHandleT currentGoal
ros::Time endTime
condition_variable executionFinishedCondition
mutex executionFinishedMutex
mutex goalLock
bool hasGoal
bool initialized
bool lastExeSuccess
ros::NodeHandle node
ros::Time startTime

Detailed Description

template<class ActionMessage>
class convenience_ros_functions::ActionServer< ActionMessage >

Helper class with an action server and commonly required fields already defined. Can be derived to provide a new action server.

As a template parameter, pass the action message type. For example, if there is a message type your_msgs::Example.action, pass your_msgs::ExampleAction

Author:
Jennifer Buehler
Date:
March 2016

Definition at line 24 of file ActionServer.h.


Member Typedef Documentation

template<class ActionMessage>
typedef ActionFeedbackConstPtr convenience_ros_functions::ActionServer< ActionMessage >::ActionFeedbackConstPtrT [protected]

Definition at line 47 of file ActionServer.h.

template<class ActionMessage>
typedef ActionFeedback convenience_ros_functions::ActionServer< ActionMessage >::ActionFeedbackT [protected]

Definition at line 46 of file ActionServer.h.

template<class ActionMessage>
typedef ActionGoalConstPtr convenience_ros_functions::ActionServer< ActionMessage >::ActionGoalConstPtrT [protected]

Definition at line 39 of file ActionServer.h.

template<class ActionMessage>
typedef ROSActionServerT::GoalHandle convenience_ros_functions::ActionServer< ActionMessage >::ActionGoalHandleT [protected]

Definition at line 33 of file ActionServer.h.

template<class ActionMessage>
typedef ActionGoalPtr convenience_ros_functions::ActionServer< ActionMessage >::ActionGoalPtrT [protected]

Definition at line 38 of file ActionServer.h.

template<class ActionMessage>
typedef ActionGoal convenience_ros_functions::ActionServer< ActionMessage >::ActionGoalT [protected]

Definition at line 37 of file ActionServer.h.

template<class ActionMessage>
typedef ActionResultConstPtr convenience_ros_functions::ActionServer< ActionMessage >::ActionResultConstPtrT [protected]

Definition at line 41 of file ActionServer.h.

template<class ActionMessage>
typedef ActionResult convenience_ros_functions::ActionServer< ActionMessage >::ActionResultT [protected]

Definition at line 40 of file ActionServer.h.

template<class ActionMessage>
typedef baselib_binding::condition_variable convenience_ros_functions::ActionServer< ActionMessage >::condition_variable [private]

Definition at line 180 of file ActionServer.h.

template<class ActionMessage>
typedef FeedbackConstPtr convenience_ros_functions::ActionServer< ActionMessage >::FeedbackConstPtrT [protected]

Definition at line 45 of file ActionServer.h.

template<class ActionMessage>
typedef Feedback convenience_ros_functions::ActionServer< ActionMessage >::FeedbackT [protected]

Definition at line 44 of file ActionServer.h.

template<class ActionMessage>
typedef GoalConstPtr convenience_ros_functions::ActionServer< ActionMessage >::GoalConstPtrT [protected]

Definition at line 36 of file ActionServer.h.

template<class ActionMessage>
typedef Goal convenience_ros_functions::ActionServer< ActionMessage >::GoalT [protected]

Definition at line 35 of file ActionServer.h.

template<class ActionMessage>
typedef baselib_binding::mutex convenience_ros_functions::ActionServer< ActionMessage >::mutex [private]

Definition at line 177 of file ActionServer.h.

template<class ActionMessage>
typedef baselib_binding::recursive_mutex convenience_ros_functions::ActionServer< ActionMessage >::recursive_mutex [private]

Definition at line 176 of file ActionServer.h.

template<class ActionMessage>
typedef ResultConstPtr convenience_ros_functions::ActionServer< ActionMessage >::ResultConstPtrT [protected]

Definition at line 43 of file ActionServer.h.

template<class ActionMessage>
typedef Result convenience_ros_functions::ActionServer< ActionMessage >::ResultT [protected]

Definition at line 42 of file ActionServer.h.

template<class ActionMessage>
typedef ROSActionServerT* convenience_ros_functions::ActionServer< ActionMessage >::ROSActionServerPtr [protected]

Definition at line 32 of file ActionServer.h.

template<class ActionMessage>
typedef actionlib::ActionServer<ActionMessage> convenience_ros_functions::ActionServer< ActionMessage >::ROSActionServerT [protected]

Definition at line 30 of file ActionServer.h.

template<class ActionMessage>
typedef ActionServer<ActionMessage> convenience_ros_functions::ActionServer< ActionMessage >::Self [protected]

Definition at line 28 of file ActionServer.h.

template<class ActionMessage>
typedef baselib_binding::unique_lock<mutex>::type convenience_ros_functions::ActionServer< ActionMessage >::unique_lock [private]

Definition at line 178 of file ActionServer.h.

template<class ActionMessage>
typedef baselib_binding::unique_lock<recursive_mutex>::type convenience_ros_functions::ActionServer< ActionMessage >::unique_recursive_lock [private]

Definition at line 179 of file ActionServer.h.


Constructor & Destructor Documentation

template<class ActionMessage>
ActionServer::ActionServer ( ros::NodeHandle _node,
const std::string &  action_topic 
)

Definition at line 2 of file ActionServer.hpp.

template<class ActionMessage>
ActionServer::~ActionServer ( ) [virtual]

Definition at line 15 of file ActionServer.hpp.


Member Function Documentation

template<class ActionMessage>
void ActionServer::actionCallback ( ActionGoalHandleT goal) [private]

Receive a new goal

Definition at line 164 of file ActionServer.hpp.

template<class ActionMessage>
virtual void convenience_ros_functions::ActionServer< ActionMessage >::actionCallbackImpl ( const ActionGoalHandleT goal) [protected, pure virtual]

Receive a new goal: subclasses implementation. No need to set the goal to accepted, rejected, etc. This function should just be used to initialize interal fields based on the values of the goal handle, and to kick off the execution of the action. Method canAccept() should have been used before to rule out that this action can be started.

Once the action is done, call method currentActionDone() to finalize the execution of this goal.

template<class ActionMessage>
void ActionServer::actionCancelCallback ( ActionGoalHandleT goal) [private]

Receive a cancel instruction

Definition at line 206 of file ActionServer.hpp.

template<class ActionMessage>
virtual void convenience_ros_functions::ActionServer< ActionMessage >::actionCancelCallbackImpl ( const ActionGoalHandleT goal) [inline, protected, virtual]

Receive a cancel instruction: subclasses implementation. Only needs to be implemented if any special actions are required upon canceling the action.

Definition at line 144 of file ActionServer.h.

template<class ActionMessage>
virtual bool convenience_ros_functions::ActionServer< ActionMessage >::canAccept ( const ActionGoalHandleT goal) [protected, pure virtual]

Subclasses should implement here whether this goal is eligible. No need to set goal to any state, this will be done if this method returns false. Will *always* be called immediately before actionCallbackImpl().

template<class ActionMessage>
void ActionServer::currentActionDone ( ResultT result,
const actionlib::SimpleClientGoalState state 
) [protected]

Method to call from subclasses to signal that the currently running goal has finished. Alternatively, other methods called currentActionDone() can be called which have the same effect but less descriptive outcomes for the action result.

Definition at line 99 of file ActionServer.hpp.

template<class ActionMessage>
void ActionServer::currentActionDone ( const actionlib::SimpleClientGoalState state) [protected]

Simpler implementation of currentActionDone(ActionResult&, const actionlib::SimpleClientGoalState&) which does not take a result.

Definition at line 112 of file ActionServer.hpp.

template<class ActionMessage>
void ActionServer::currentActionSuccess ( const bool  success) [protected]

Simple implementation of other currentActionDone() methods but which has same effect. When successful, it works the same. On error, the goal is always set to "aborted". The only reason this action is called "currentActionSuccess" instead of "currentActionDone" is that while it compiles, at runtime there is the problem that it recursively calls itself, instead of calling currentActionDone(const actionlib::SimpleClientGoalState).

Definition at line 126 of file ActionServer.hpp.

template<class ActionMessage>
void ActionServer::deleteServer ( ) [private]

Definition at line 153 of file ActionServer.hpp.

template<class ActionMessage>
bool ActionServer::executingGoal ( )

Checks whether there is currently a goal, and it is also active.

Definition at line 40 of file ActionServer.hpp.

template<class ActionMessage>
bool ActionServer::hasCurrentGoal ( ) [private]

Definition at line 214 of file ActionServer.hpp.

template<class ActionMessage>
bool ActionServer::init ( )

Starts action server and does internal initialisation.

Definition at line 22 of file ActionServer.hpp.

template<class ActionMessage>
bool ActionServer::initImpl ( ) [protected, virtual]

Can be implemented by subclasses. This is called from init().

Definition at line 133 of file ActionServer.hpp.

template<class ActionMessage>
void ActionServer::shutdown ( )

Methods to be executed for shutting down the action server

Definition at line 31 of file ActionServer.hpp.

template<class ActionMessage>
virtual void convenience_ros_functions::ActionServer< ActionMessage >::shutdownImpl ( ) [inline, protected, virtual]

Can be implemented by subclasses. This is called from shutdown().

Definition at line 118 of file ActionServer.h.

template<class ActionMessage>
void ActionServer::startServer ( ) [private]

Definition at line 138 of file ActionServer.hpp.

template<class ActionMessage>
double ActionServer::timeRunning ( ) [protected]

Time (in seconds) which has passed since the action has been started.

Definition at line 85 of file ActionServer.hpp.

template<class ActionMessage>
float ActionServer::waitForExecution ( float  timeout) [protected, virtual]

Can be used by subclasses to wait for the current execution of the action. Internally, waits until currentActionDone() is called by subclasses.

Returns:
the duration of the wait. If the action has already finished (is not running), returns the duration of the last executed action.

Definition at line 56 of file ActionServer.hpp.


Member Data Documentation

template<class ActionMessage>
ROSActionServerPtr convenience_ros_functions::ActionServer< ActionMessage >::actionServer [private]

Definition at line 193 of file ActionServer.h.

template<class ActionMessage>
std::string convenience_ros_functions::ActionServer< ActionMessage >::actionTopic [private]

Definition at line 185 of file ActionServer.h.

template<class ActionMessage>
ActionGoalHandleT convenience_ros_functions::ActionServer< ActionMessage >::currentGoal [private]

Definition at line 190 of file ActionServer.h.

template<class ActionMessage>
ros::Time convenience_ros_functions::ActionServer< ActionMessage >::endTime [private]

Definition at line 194 of file ActionServer.h.

template<class ActionMessage>
condition_variable convenience_ros_functions::ActionServer< ActionMessage >::executionFinishedCondition [private]

Definition at line 195 of file ActionServer.h.

template<class ActionMessage>
mutex convenience_ros_functions::ActionServer< ActionMessage >::executionFinishedMutex [private]

Definition at line 196 of file ActionServer.h.

template<class ActionMessage>
mutex convenience_ros_functions::ActionServer< ActionMessage >::goalLock [private]

Definition at line 191 of file ActionServer.h.

template<class ActionMessage>
bool convenience_ros_functions::ActionServer< ActionMessage >::hasGoal [private]

Definition at line 188 of file ActionServer.h.

template<class ActionMessage>
bool convenience_ros_functions::ActionServer< ActionMessage >::initialized [private]

Definition at line 187 of file ActionServer.h.

template<class ActionMessage>
bool convenience_ros_functions::ActionServer< ActionMessage >::lastExeSuccess [private]

Definition at line 189 of file ActionServer.h.

template<class ActionMessage>
ros::NodeHandle convenience_ros_functions::ActionServer< ActionMessage >::node [private]

Definition at line 183 of file ActionServer.h.

template<class ActionMessage>
ros::Time convenience_ros_functions::ActionServer< ActionMessage >::startTime [private]

Definition at line 194 of file ActionServer.h.


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


convenience_ros_functions
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:21:42