Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
actionlib::ActionServerBase< ActionSpec > Class Template Referenceabstract

The ActionServerBase implements the logic for an ActionServer. More...

#include <action_server_base.h>

Inheritance diagram for actionlib::ActionServerBase< ActionSpec >:
Inheritance graph
[legend]

Public Types

typedef ServerGoalHandle< ActionSpec > GoalHandle
 

Public Member Functions

 ActionServerBase (boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start=false)
 Constructor for an ActionServer. More...
 
void cancelCallback (const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id)
 The ROS callback for cancel requests coming into the ActionServerBase. More...
 
void goalCallback (const boost::shared_ptr< const ActionGoal > &goal)
 The ROS callback for goals coming into the ActionServerBase. More...
 
void registerCancelCallback (boost::function< void(GoalHandle)> cb)
 Register a callback to be invoked when a new cancel is received, this will replace any previously registered callback. More...
 
void registerGoalCallback (boost::function< void(GoalHandle)> cb)
 Register a callback to be invoked when a new goal is received, this will replace any previously registered callback. More...
 
void start ()
 Explicitly start the action server, used it auto_start is set to false. More...
 
virtual ~ActionServerBase ()
 Destructor for the ActionServerBase. More...
 

Protected Member Functions

virtual void initialize ()=0
 Initialize all ROS connections and setup timers. More...
 
virtual void publishFeedback (const actionlib_msgs::GoalStatus &status, const Feedback &feedback)=0
 Publishes feedback for a given goal. More...
 
virtual void publishResult (const actionlib_msgs::GoalStatus &status, const Result &result)=0
 Publishes a result for a given goal. More...
 
virtual void publishStatus ()=0
 Explicitly publish status. More...
 

Protected Attributes

boost::function< void(GoalHandle)> cancel_callback_
 
boost::function< void(GoalHandle)> goal_callback_
 
boost::shared_ptr< DestructionGuardguard_
 
GoalIDGenerator id_generator_
 
ros::Time last_cancel_
 
boost::recursive_mutex lock_
 
bool started_
 
std::list< StatusTracker< ActionSpec > > status_list_
 
ros::Duration status_list_timeout_
 

Friends

class HandleTrackerDeleter< ActionSpec >
 
class ServerGoalHandle< ActionSpec >
 

Detailed Description

template<class ActionSpec>
class actionlib::ActionServerBase< ActionSpec >

The ActionServerBase implements the logic for an ActionServer.

Definition at line 99 of file action_server_base.h.

Member Typedef Documentation

◆ GoalHandle

template<class ActionSpec >
typedef ServerGoalHandle<ActionSpec> actionlib::ActionServerBase< ActionSpec >::GoalHandle

Definition at line 103 of file action_server_base.h.

Constructor & Destructor Documentation

◆ ActionServerBase()

template<class ActionSpec >
actionlib::ActionServerBase< ActionSpec >::ActionServerBase ( boost::function< void(GoalHandle)>  goal_cb,
boost::function< void(GoalHandle)>  cancel_cb,
bool  auto_start = false 
)

Constructor for an ActionServer.

Parameters
goal_cbA goal callback to be called when the ActionServer receives a new goal over the wire
cancel_cbA cancel callback to be called when the ActionServer receives a new cancel request over the wire
auto_startA boolean value that tells the ActionServer whether or not to start publishing as soon as it comes up. THIS SHOULD ALWAYS BE SET TO FALSE TO AVOID RACE CONDITIONS and start() should be called after construction of the server.

Definition at line 199 of file action_server_base.h.

◆ ~ActionServerBase()

template<class ActionSpec >
actionlib::ActionServerBase< ActionSpec >::~ActionServerBase
virtual

Destructor for the ActionServerBase.

Definition at line 211 of file action_server_base.h.

Member Function Documentation

◆ cancelCallback()

template<class ActionSpec >
void actionlib::ActionServerBase< ActionSpec >::cancelCallback ( const boost::shared_ptr< const actionlib_msgs::GoalID > &  goal_id)

The ROS callback for cancel requests coming into the ActionServerBase.

Definition at line 300 of file action_server_base.h.

◆ goalCallback()

template<class ActionSpec >
void actionlib::ActionServerBase< ActionSpec >::goalCallback ( const boost::shared_ptr< const ActionGoal > &  goal)

The ROS callback for goals coming into the ActionServerBase.

Definition at line 239 of file action_server_base.h.

◆ initialize()

template<class ActionSpec >
virtual void actionlib::ActionServerBase< ActionSpec >::initialize ( )
protectedpure virtual

Initialize all ROS connections and setup timers.

Implemented in actionlib::ActionServer< ActionSpec >, and actionlib::ActionServer< TestAction >.

◆ publishFeedback()

template<class ActionSpec >
virtual void actionlib::ActionServerBase< ActionSpec >::publishFeedback ( const actionlib_msgs::GoalStatus &  status,
const Feedback &  feedback 
)
protectedpure virtual

Publishes feedback for a given goal.

Parameters
statusThe status of the goal with which the feedback is associated
feedbackThe feedback to publish

Implemented in actionlib::ActionServer< ActionSpec >, and actionlib::ActionServer< TestAction >.

◆ publishResult()

template<class ActionSpec >
virtual void actionlib::ActionServerBase< ActionSpec >::publishResult ( const actionlib_msgs::GoalStatus &  status,
const Result &  result 
)
protectedpure virtual

Publishes a result for a given goal.

Parameters
statusThe status of the goal with which the result is associated
resultThe result to publish

Implemented in actionlib::ActionServer< ActionSpec >, and actionlib::ActionServer< TestAction >.

◆ publishStatus()

template<class ActionSpec >
virtual void actionlib::ActionServerBase< ActionSpec >::publishStatus ( )
protectedpure virtual

Explicitly publish status.

Implemented in actionlib::ActionServer< ActionSpec >, and actionlib::ActionServer< TestAction >.

◆ registerCancelCallback()

template<class ActionSpec >
void actionlib::ActionServerBase< ActionSpec >::registerCancelCallback ( boost::function< void(GoalHandle)>  cb)

Register a callback to be invoked when a new cancel is received, this will replace any previously registered callback.

Parameters
cbThe callback to invoke

Definition at line 224 of file action_server_base.h.

◆ registerGoalCallback()

template<class ActionSpec >
void actionlib::ActionServerBase< ActionSpec >::registerGoalCallback ( boost::function< void(GoalHandle)>  cb)

Register a callback to be invoked when a new goal is received, this will replace any previously registered callback.

Parameters
cbThe callback to invoke

Definition at line 218 of file action_server_base.h.

◆ start()

template<class ActionSpec >
void actionlib::ActionServerBase< ActionSpec >::start

Explicitly start the action server, used it auto_start is set to false.

Definition at line 230 of file action_server_base.h.

Friends And Related Function Documentation

◆ HandleTrackerDeleter< ActionSpec >

template<class ActionSpec >
friend class HandleTrackerDeleter< ActionSpec >
friend

Definition at line 156 of file action_server_base.h.

◆ ServerGoalHandle< ActionSpec >

template<class ActionSpec >
friend class ServerGoalHandle< ActionSpec >
friend

Definition at line 155 of file action_server_base.h.

Member Data Documentation

◆ cancel_callback_

template<class ActionSpec >
boost::function<void(GoalHandle)> actionlib::ActionServerBase< ActionSpec >::cancel_callback_
protected

Definition at line 188 of file action_server_base.h.

◆ goal_callback_

template<class ActionSpec >
boost::function<void(GoalHandle)> actionlib::ActionServerBase< ActionSpec >::goal_callback_
protected

Definition at line 187 of file action_server_base.h.

◆ guard_

template<class ActionSpec >
boost::shared_ptr<DestructionGuard> actionlib::ActionServerBase< ActionSpec >::guard_
protected

Definition at line 195 of file action_server_base.h.

◆ id_generator_

template<class ActionSpec >
GoalIDGenerator actionlib::ActionServerBase< ActionSpec >::id_generator_
protected

Definition at line 193 of file action_server_base.h.

◆ last_cancel_

template<class ActionSpec >
ros::Time actionlib::ActionServerBase< ActionSpec >::last_cancel_
protected

Definition at line 190 of file action_server_base.h.

◆ lock_

template<class ActionSpec >
boost::recursive_mutex actionlib::ActionServerBase< ActionSpec >::lock_
protected

Definition at line 183 of file action_server_base.h.

◆ started_

template<class ActionSpec >
bool actionlib::ActionServerBase< ActionSpec >::started_
protected

Definition at line 194 of file action_server_base.h.

◆ status_list_

template<class ActionSpec >
std::list<StatusTracker<ActionSpec> > actionlib::ActionServerBase< ActionSpec >::status_list_
protected

Definition at line 185 of file action_server_base.h.

◆ status_list_timeout_

template<class ActionSpec >
ros::Duration actionlib::ActionServerBase< ActionSpec >::status_list_timeout_
protected

Definition at line 191 of file action_server_base.h.


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


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