|
| | RefServer (ros::NodeHandle &n, const std::string &name) |
| |
| ROS_DEPRECATED | ActionServer (ros::NodeHandle n, std::string name) |
| | DEPRECATED Constructor for an ActionServer. More...
|
| |
| | ActionServer (ros::NodeHandle n, std::string name, 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...
|
| |
| | 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...
|
| |
| 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...
|
| |
| virtual | ~ActionServer () |
| | Destructor for the ActionServer. More...
|
| |
| | 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...
|
| |
Definition at line 78 of file ref_server.cpp.