Public Types | Public Member Functions | Private Member Functions | List of all members
actionlib::RefServer Class Reference
Inheritance diagram for actionlib::RefServer:
Inheritance graph
[legend]

Public Types

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

Public Member Functions

 RefServer (ros::NodeHandle &n, const std::string &name)
 
- Public Member Functions inherited from actionlib::ActionServer< TestAction >
 ACTION_DEFINITION (TestAction)
 
 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< TestAction >
 ACTION_DEFINITION (TestAction)
 
 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

void cancelCallback (GoalHandle gh)
 
void goalCallback (GoalHandle gh)
 

Additional Inherited Members

- Protected Attributes inherited from actionlib::ActionServerBase< TestAction >
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< TestAction > > status_list_
 
ros::Duration status_list_timeout_
 

Detailed Description

Definition at line 46 of file ref_server.cpp.

Member Typedef Documentation

Definition at line 49 of file ref_server.cpp.

Constructor & Destructor Documentation

RefServer::RefServer ( ros::NodeHandle n,
const std::string &  name 
)

Definition at line 62 of file ref_server.cpp.

Member Function Documentation

void RefServer::cancelCallback ( GoalHandle  gh)
private

Definition at line 93 of file ref_server.cpp.

void RefServer::goalCallback ( GoalHandle  gh)
private

Definition at line 72 of file ref_server.cpp.


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


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