action_server.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef ACTIONLIB__SERVER__ACTION_SERVER_H_
38 #define ACTIONLIB__SERVER__ACTION_SERVER_H_
39 
40 #include <ros/ros.h>
41 #include <boost/thread.hpp>
42 #include <boost/thread/reverse_lock.hpp>
43 #include <boost/shared_ptr.hpp>
44 #include <actionlib_msgs/GoalID.h>
45 #include <actionlib_msgs/GoalStatusArray.h>
46 #include <actionlib_msgs/GoalStatus.h>
55 
56 #include <list>
57 #include <string>
58 
59 namespace actionlib
60 {
71 template<class ActionSpec>
72 class ActionServer : public ActionServerBase<ActionSpec>
73 {
74 public:
75  // for convenience when referring to ServerGoalHandles
77 
78  // generates typedefs that we'll use to make our lives easier
79  ACTION_DEFINITION(ActionSpec);
80 
89  ActionServer(ros::NodeHandle n, std::string name,
90  boost::function<void(GoalHandle)> goal_cb,
91  boost::function<void(GoalHandle)> cancel_cb,
92  bool auto_start);
93 
101  ActionServer(ros::NodeHandle n, std::string name,
102  boost::function<void(GoalHandle)> goal_cb,
103  bool auto_start);
104 
112  ROS_DEPRECATED ActionServer(ros::NodeHandle n, std::string name,
113  boost::function<void(GoalHandle)> goal_cb,
114  boost::function<void(GoalHandle)> cancel_cb = boost::function<void(GoalHandle)>());
115 
122  ActionServer(ros::NodeHandle n, std::string name,
123  bool auto_start);
124 
130  ROS_DEPRECATED ActionServer(ros::NodeHandle n, std::string name);
131 
135  virtual ~ActionServer();
136 
137 private:
141  virtual void initialize();
142 
148  virtual void publishResult(const actionlib_msgs::GoalStatus & status, const Result & result);
149 
155  virtual void publishFeedback(const actionlib_msgs::GoalStatus & status,
156  const Feedback & feedback);
157 
161  virtual void publishStatus();
162 
166  void publishStatus(const ros::TimerEvent & e);
167 
169 
172 
174 };
175 } // namespace actionlib
176 
177 // include the implementation
179 #endif // ACTIONLIB__SERVER__ACTION_SERVER_H_
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.
virtual ~ActionServer()
Destructor for the ActionServer.
ros::Subscriber goal_sub_
ServerGoalHandle< ActionSpec > GoalHandle
Definition: action_server.h:76
ros::Publisher status_pub_
virtual void initialize()
Initialize all ROS connections and setup timers.
ros::Publisher feedback_pub_
The ActionServerBase implements the logic for an ActionServer.
virtual void publishResult(const actionlib_msgs::GoalStatus &status, const Result &result)
Publishes a result for a given goal.
Encapsulates a state machine for a given goal that the user can trigger transitions on...
#define ROS_DEPRECATED
virtual void publishStatus()
Explicitly publish status.
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specif...
Definition: action_server.h:72
ros::Subscriber cancel_sub_
ros::Publisher result_pub_
ros::NodeHandle node_
virtual void publishFeedback(const actionlib_msgs::GoalStatus &status, const Feedback &feedback)
Publishes feedback for a given goal.
ACTION_DEFINITION(ActionSpec)


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 28 2022 21:34:38