Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
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>

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

Public Types

typedef ServerGoalHandle< ActionSpec > GoalHandle
 
- Public Types inherited from actionlib::ActionServerBase< ActionSpec >
typedef ServerGoalHandle< ActionSpec > GoalHandle
 

Public Member Functions

 ACTION_DEFINITION (ActionSpec)
 
 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. More...
 
 ActionServer (ros::NodeHandle n, std::string name, boost::function< void(GoalHandle)> goal_cb, bool auto_start)
 Constructor for an ActionServer. More...
 
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. More...
 
 ActionServer (ros::NodeHandle n, std::string name, bool auto_start)
 Constructor for an ActionServer. More...
 
ROS_DEPRECATED ActionServer (ros::NodeHandle n, std::string name)
 DEPRECATED Constructor for an ActionServer. More...
 
virtual ~ActionServer ()
 Destructor for the ActionServer. More...
 
- Public Member Functions inherited from actionlib::ActionServerBase< ActionSpec >
 ACTION_DEFINITION (ActionSpec)
 
 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...
 

Private Member Functions

virtual void initialize ()
 Initialize all ROS connections and setup timers. More...
 
virtual void publishFeedback (const actionlib_msgs::GoalStatus &status, const Feedback &feedback)
 Publishes feedback for a given goal. More...
 
virtual void publishResult (const actionlib_msgs::GoalStatus &status, const Result &result)
 Publishes a result for a given goal. More...
 
virtual void publishStatus ()
 Explicitly publish status. More...
 
void publishStatus (const ros::TimerEvent &e)
 Publish status for all goals on a timer event. More...
 

Private Attributes

ros::Subscriber cancel_sub_
 
ros::Publisher feedback_pub_
 
ros::Subscriber goal_sub_
 
ros::NodeHandle node_
 
ros::Publisher result_pub_
 
ros::Publisher status_pub_
 
ros::Timer status_timer_
 

Additional Inherited Members

- Protected Attributes inherited from actionlib::ActionServerBase< ActionSpec >
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_
 

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 72 of file action_server.h.

Member Typedef Documentation

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

Definition at line 76 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 
)

Constructor for an ActionServer.

Parameters
nA NodeHandle to create a namespace under
nameThe name of the action
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 80 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 
)

Constructor for an ActionServer.

Parameters
nA NodeHandle to create a namespace under
nameThe name of the action
goal_cbA goal callback to be called when the ActionServer receives a new goal 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 115 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)>() 
)

DEPRECATED Constructor for an ActionServer.

Parameters
nA NodeHandle to create a namespace under
nameThe name of the action
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

Definition at line 98 of file action_server_imp.h.

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

Constructor for an ActionServer.

Parameters
nA NodeHandle to create a namespace under
nameThe name of the action
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 47 of file action_server_imp.h.

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

DEPRECATED Constructor for an ActionServer.

Parameters
nA NodeHandle to create a namespace under
nameThe name of the action

Definition at line 64 of file action_server_imp.h.

template<class ActionSpec >
actionlib::ActionServer< ActionSpec >::~ActionServer ( )
virtual

Destructor for the ActionServer.

Definition at line 132 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 >::initialize ( )
privatevirtual

Initialize all ROS connections and setup timers.

Implements actionlib::ActionServerBase< ActionSpec >.

Definition at line 137 of file action_server_imp.h.

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

Publishes feedback for a given goal.

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

Implements actionlib::ActionServerBase< ActionSpec >.

Definition at line 203 of file action_server_imp.h.

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

Publishes a result for a given goal.

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

Implements actionlib::ActionServerBase< ActionSpec >.

Definition at line 187 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::publishStatus ( )
privatevirtual

Explicitly publish status.

Implements actionlib::ActionServerBase< ActionSpec >.

Definition at line 230 of file action_server_imp.h.

template<class ActionSpec >
void actionlib::ActionServer< ActionSpec >::publishStatus ( const ros::TimerEvent e)
private

Publish status for all goals on a timer event.

Definition at line 218 of file action_server_imp.h.

Member Data Documentation

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

Definition at line 170 of file action_server.h.

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

Definition at line 171 of file action_server.h.

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

Definition at line 170 of file action_server.h.

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

Definition at line 168 of file action_server.h.

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

Definition at line 171 of file action_server.h.

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

Definition at line 171 of file action_server.h.

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

Definition at line 173 of file action_server.h.


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


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 18 2019 03:59:59