Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends
actionlib::ActionServerBase< ActionSpec > Class Template Reference

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

#include <action_server_base.h>

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

List of all members.

Public Types

typedef ServerGoalHandle
< ActionSpec > 
GoalHandle

Public Member Functions

 ACTION_DEFINITION (ActionSpec)
 ActionServerBase (boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start=false)
 Constructor for an ActionServer.
void cancelCallback (const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id)
 The ROS callback for cancel requests coming into the ActionServerBase.
void goalCallback (const boost::shared_ptr< const ActionGoal > &goal)
 The ROS callback for goals coming into the ActionServerBase.
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.
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.
void start ()
 Explicitly start the action server, used it auto_start is set to false.
virtual ~ActionServerBase ()
 Destructor for the ActionServerBase.

Protected Member Functions

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

Protected Attributes

boost::function< void(GoalHandle)> cancel_callback_
boost::function< void(GoalHandle)> goal_callback_
boost::shared_ptr
< DestructionGuard
guard_
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 62 of file action_server_base.h.


Member Typedef Documentation

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

Constructor & Destructor Documentation

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 wheteher 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 160 of file action_server_base.h.

template<class ActionSpec >
actionlib::ActionServerBase< ActionSpec >::~ActionServerBase ( ) [virtual]

Destructor for the ActionServerBase.

Definition at line 172 of file action_server_base.h.


Member Function Documentation

template<class ActionSpec>
actionlib::ActionServerBase< ActionSpec >::ACTION_DEFINITION ( ActionSpec  )
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 259 of file action_server_base.h.

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 200 of file action_server_base.h.

template<class ActionSpec>
virtual void actionlib::ActionServerBase< ActionSpec >::initialize ( ) [protected, pure virtual]

Initialize all ROS connections and setup timers.

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

template<class ActionSpec>
virtual void actionlib::ActionServerBase< ActionSpec >::publishFeedback ( const actionlib_msgs::GoalStatus &  status,
const Feedback &  feedback 
) [protected, pure 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 >.

template<class ActionSpec>
virtual void actionlib::ActionServerBase< ActionSpec >::publishResult ( const actionlib_msgs::GoalStatus &  status,
const Result &  result 
) [protected, pure 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 >.

template<class ActionSpec>
virtual void actionlib::ActionServerBase< ActionSpec >::publishStatus ( ) [protected, pure virtual]

Explicitly publish status.

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

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 185 of file action_server_base.h.

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 179 of file action_server_base.h.

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

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

Definition at line 191 of file action_server_base.h.


Friends And Related Function Documentation

template<class ActionSpec>
friend class HandleTrackerDeleter< ActionSpec > [friend]

Definition at line 118 of file action_server_base.h.

template<class ActionSpec>
friend class ServerGoalHandle< ActionSpec > [friend]

Definition at line 117 of file action_server_base.h.


Member Data Documentation

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

Definition at line 149 of file action_server_base.h.

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

Definition at line 148 of file action_server_base.h.

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

Definition at line 156 of file action_server_base.h.

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

Definition at line 154 of file action_server_base.h.

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

Definition at line 151 of file action_server_base.h.

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

Definition at line 144 of file action_server_base.h.

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

Definition at line 155 of file action_server_base.h.

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

Definition at line 146 of file action_server_base.h.

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

Definition at line 152 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
autogenerated on Fri Aug 28 2015 10:04:41