actionlib::ActionServer< ActionSpec > Class Template Reference

The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specify callbacks that are invoked when goal or cancel requests come over the wire, and passes back GoalHandles that can be used to track the state of a given goal request. The ActionServer makes no assumptions about the policy used to service these goals, and sends status for each goal over the wire until the last GoalHandle associated with a goal request is destroyed. More...

#include <action_server.h>

List of all members.

Public Types

typedef ServerGoalHandle
< ActionSpec > 
GoalHandle

Public Member Functions

 ACTION_DEFINITION (ActionSpec)
ROS_DEPRECATED ActionServer (ros::NodeHandle n, std::string name)
 DEPRECATED Constructor for an ActionServer.
 ActionServer (ros::NodeHandle n, std::string name, bool auto_start)
 Constructor for an ActionServer.
ROS_DEPRECATED ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb=boost::function< void(GoalHandle)>())
 DEPRECATED Constructor for an ActionServer.
 ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, bool auto_start)
 Constructor for an ActionServer.
 ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start)
 Constructor for an ActionServer.
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.
 ~ActionServer ()
 Destructor for the ActionServer.

Private Member Functions

void cancelCallback (const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id)
 The ROS callback for cancel requests coming into the ActionServer.
void goalCallback (const boost::shared_ptr< const ActionGoal > &goal)
 The ROS callback for goals coming into the ActionServer.
void initialize ()
 Initialize all ROS connections and setup timers.
void publishFeedback (const actionlib_msgs::GoalStatus &status, const Feedback &feedback)
 Publishes feedback for a given goal.
void publishResult (const actionlib_msgs::GoalStatus &status, const Result &result)
 Publishes a result for a given goal.
void publishStatus ()
 Explicitly publish status.
void publishStatus (const ros::TimerEvent &e)
 Publish status for all goals on a timer event.

Private Attributes

boost::function< void(GoalHandle)> cancel_callback_
ros::Subscriber cancel_sub_
ros::Publisher feedback_pub_
boost::function< void(GoalHandle)> goal_callback_
ros::Subscriber goal_sub_
boost::shared_ptr
< DestructionGuard
guard_
GoalIDGenerator id_generator_
ros::Time last_cancel_
boost::recursive_mutex lock_
ros::NodeHandle node_
ros::Publisher result_pub_
bool started_
std::list< StatusTracker
< ActionSpec > > 
status_list_
ros::Duration status_list_timeout_
ros::Publisher status_pub_
ros::Timer status_timer_

Friends

class HandleTrackerDeleter< ActionSpec >
class ServerGoalHandle< ActionSpec >

Detailed Description

template<class ActionSpec>
class actionlib::ActionServer< ActionSpec >

The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specify callbacks that are invoked when goal or cancel requests come over the wire, and passes back GoalHandles that can be used to track the state of a given goal request. The ActionServer makes no assumptions about the policy used to service these goals, and sends status for each goal over the wire until the last GoalHandle associated with a goal request is destroyed.

Definition at line 64 of file action_server.h.


Member Typedef Documentation

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

Reimplemented in actionlib::RefServer.

Definition at line 67 of file action_server.h.


Constructor & Destructor Documentation

template<class ActionSpec >
actionlib::ActionServer< ActionSpec >::ActionServer ( ros::NodeHandle  n,
std::string  name,
boost::function< void(GoalHandle)>  goal_cb,
boost::function< void(GoalHandle)>  cancel_cb,
bool  auto_start 
) [inline]

Constructor for an ActionServer.

Parameters:
n A NodeHandle to create a namespace under
name The name of the action
goal_cb A goal callback to be called when the ActionServer receives a new goal over the wire
cancel_cb A cancel callback to be called when the ActionServer receives a new cancel request over the wire
auto_start A 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 66 of file action_server_imp.h.

template<class ActionSpec >
actionlib::ActionServer< ActionSpec >::ActionServer ( ros::NodeHandle  n,
std::string  name,
boost::function< void(GoalHandle)>  goal_cb,
bool  auto_start 
) [inline]

Constructor for an ActionServer.

Parameters:
n A NodeHandle to create a namespace under
name The name of the action
goal_cb A goal callback to be called when the ActionServer receives a new goal over the wire
auto_start A 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 93 of file action_server_imp.h.

template<class ActionSpec >
actionlib::ActionServer< ActionSpec >::ActionServer ( ros::NodeHandle  n,
std::string  name,
boost::function< void(GoalHandle)>  goal_cb,
boost::function< void(GoalHandle)>  cancel_cb = boost::function<void (GoalHandle)>() 
) [inline]

DEPRECATED Constructor for an ActionServer.

Parameters:
n A NodeHandle to create a namespace under
name The name of the action
goal_cb A goal callback to be called when the ActionServer receives a new goal over the wire
cancel_cb A cancel callback to be called when the ActionServer receives a new cancel request over the wire

Definition at line 80 of file action_server_imp.h.

template<class ActionSpec >
actionlib::ActionServer< ActionSpec >::ActionServer ( ros::NodeHandle  n,
std::string  name,
bool  auto_start 
) [inline]

Constructor for an ActionServer.

Parameters:
n A NodeHandle to create a namespace under
name The name of the action
auto_start A 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 41 of file action_server_imp.h.

template<class ActionSpec >
actionlib::ActionServer< ActionSpec >::ActionServer ( ros::NodeHandle  n,
std::string  name 
) [inline]

DEPRECATED Constructor for an ActionServer.

Parameters:
n A NodeHandle to create a namespace under
name The name of the action

Definition at line 54 of file action_server_imp.h.

template<class ActionSpec >
actionlib::ActionServer< ActionSpec >::~ActionServer (  )  [inline]

Destructor for the ActionServer.

Definition at line 106 of file action_server_imp.h.


Member Function Documentation

template<class ActionSpec>
actionlib::ActionServer< ActionSpec >::ACTION_DEFINITION ( ActionSpec   ) 
template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::cancelCallback ( const boost::shared_ptr< const actionlib_msgs::GoalID > &  goal_id  )  [inline, private]

The ROS callback for cancel requests coming into the ActionServer.

Definition at line 172 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::goalCallback ( const boost::shared_ptr< const ActionGoal > &  goal  )  [inline, private]

The ROS callback for goals coming into the ActionServer.

Definition at line 237 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::initialize (  )  [inline, private]

Initialize all ROS connections and setup timers.

Definition at line 112 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::publishFeedback ( const actionlib_msgs::GoalStatus &  status,
const Feedback &  feedback 
) [inline, private]

Publishes feedback for a given goal.

Parameters:
status The status of the goal with which the feedback is associated
feedback The feedback to publish

Definition at line 160 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::publishResult ( const actionlib_msgs::GoalStatus &  status,
const Result &  result 
) [inline, private]

Publishes a result for a given goal.

Parameters:
status The status of the goal with which the result is associated
result The result to publish

Definition at line 148 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::publishStatus (  )  [inline, private]

Explicitly publish status.

Definition at line 312 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::publishStatus ( const ros::TimerEvent &  e  )  [inline, private]

Publish status for all goals on a timer event.

Definition at line 302 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::registerCancelCallback ( boost::function< void(GoalHandle)>  cb  )  [inline]

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

Parameters:
cb The callback to invoke

Definition at line 143 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::registerGoalCallback ( boost::function< void(GoalHandle)>  cb  )  [inline]

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

Parameters:
cb The callback to invoke

Definition at line 138 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::start (  )  [inline]

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

Definition at line 295 of file action_server_imp.h.


Friends And Related Function Documentation

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

Definition at line 204 of file action_server.h.

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

Definition at line 203 of file action_server.h.


Member Data Documentation

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

Definition at line 197 of file action_server.h.

template<class ActionSpec>
ros::Subscriber actionlib::ActionServer< ActionSpec >::cancel_sub_ [private]

Definition at line 187 of file action_server.h.

template<class ActionSpec>
ros::Publisher actionlib::ActionServer< ActionSpec >::feedback_pub_ [private]

Definition at line 188 of file action_server.h.

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

Definition at line 196 of file action_server.h.

template<class ActionSpec>
ros::Subscriber actionlib::ActionServer< ActionSpec >::goal_sub_ [private]

Definition at line 187 of file action_server.h.

template<class ActionSpec>
boost::shared_ptr<DestructionGuard> actionlib::ActionServer< ActionSpec >::guard_ [private]

Definition at line 208 of file action_server.h.

template<class ActionSpec>
GoalIDGenerator actionlib::ActionServer< ActionSpec >::id_generator_ [private]

Definition at line 206 of file action_server.h.

template<class ActionSpec>
ros::Time actionlib::ActionServer< ActionSpec >::last_cancel_ [private]

Definition at line 199 of file action_server.h.

template<class ActionSpec>
boost::recursive_mutex actionlib::ActionServer< ActionSpec >::lock_ [private]

Definition at line 190 of file action_server.h.

template<class ActionSpec>
ros::NodeHandle actionlib::ActionServer< ActionSpec >::node_ [private]

Definition at line 185 of file action_server.h.

template<class ActionSpec>
ros::Publisher actionlib::ActionServer< ActionSpec >::result_pub_ [private]

Definition at line 188 of file action_server.h.

template<class ActionSpec>
bool actionlib::ActionServer< ActionSpec >::started_ [private]

Definition at line 207 of file action_server.h.

template<class ActionSpec>
std::list<StatusTracker<ActionSpec> > actionlib::ActionServer< ActionSpec >::status_list_ [private]

Definition at line 194 of file action_server.h.

template<class ActionSpec>
ros::Duration actionlib::ActionServer< ActionSpec >::status_list_timeout_ [private]

Definition at line 200 of file action_server.h.

template<class ActionSpec>
ros::Publisher actionlib::ActionServer< ActionSpec >::status_pub_ [private]

Definition at line 188 of file action_server.h.

template<class ActionSpec>
ros::Timer actionlib::ActionServer< ActionSpec >::status_timer_ [private]

Definition at line 192 of file action_server.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Fri Jan 11 09:41:44 2013