rtt_simple_action_server.h
Go to the documentation of this file.
1 #ifndef RTT_SIMPLE_ACTION_SERVER_HPP
2 #define RTT_SIMPLE_ACTION_SERVER_HPP
3 
4 #include <stdexcept>
5 #include <boost/bind.hpp>
6 #include <boost/function.hpp>
7 
11 
12 namespace rtt_actionlib {
13 
14 template <class ActionSpec> class RTTSimpleActionServer
15 {
16  protected:
17  // GoalHandle
19  // Goal, Feedback, Result typedefs
20  ACTION_DEFINITION(ActionSpec);
21 
22  protected:
24  GoalHandle goal_active;
25  GoalHandle goal_pending;
26 
27  // callbacks
28  boost::function<void(const Goal&)> newGoalHook;
29  boost::function<void()> cancelGoalHook;
30 
31  protected:
32 
33  void goalCallback(GoalHandle gh);
34  void cancelCallback(GoalHandle gh);
35 
36  public:
37 
45  {
46  if (!owner_service) throw std::invalid_argument("RTTSimpleActionServer: owner pointer must be valid.");
47  action_server.addPorts(owner_service);
48  action_server.registerGoalCallback(boost::bind(&RTTSimpleActionServer<ActionSpec>::goalCallback, this, _1));
50  }
51 
55  bool ready() {
56  return action_server.ready();
57  }
58 
59 
63  bool start();
64 
68  void shutdown() {
69  action_server.shutdown();
70  }
71 
75  bool isActive() const {
76  return goal_active.isValid() && goal_active.getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE;
77  }
78 
82  bool isPreempting() const {
83  return goal_active.isValid() && goal_active.getGoalStatus().status == actionlib_msgs::GoalStatus::PREEMPTING;
84  }
85 
89  bool isPending() const {
90  return goal_pending.isValid() && goal_pending.getGoalStatus().status == actionlib_msgs::GoalStatus::PENDING;
91  }
92 
97  if (isActive()) return goal_active.getGoal();
98  else return boost::shared_ptr<const Goal>(); // return NULL
99  // else nullptr;
100  }
101 
106  if (isPending()) return goal_pending.getGoal();
107  else return boost::shared_ptr<const Goal>(); // return NULL
108  // else nullptr;
109  }
110 
117  bool acceptPending(const Result& result, const std::string& msg = "");
118 
125  bool rejectPending(const Result& result, const std::string& msg = "");
126 
133  bool publishFeedback(const Feedback& feedpack);
134 
141  bool abortActive(const Result& result, const std::string& msg = "");
142 
149  bool cancelActive(const Result& result, const std::string& msg = "");
150 
157  bool succeedActive(const Result& result, const std::string& msg = "");
158 
163  void setGoalHook(boost::function< void(const Goal&)> _newGoalHook) {
164  newGoalHook = _newGoalHook;
165  }
166 
171  void setCancelHook(boost::function< void()> _cancelGoalHook) {
172  cancelGoalHook = _cancelGoalHook;
173  }
174 };
175 
176 template <class ActionSpec> bool RTTSimpleActionServer<ActionSpec>::start()
177 {
178  if (ready()) {
179  action_server.start();
180  return true;
181  }
182  else return false;
183 }
184 
185 template <class ActionSpec> bool RTTSimpleActionServer<ActionSpec>::acceptPending(const Result& result, const std::string& msg)
186 {
187  if (isPending()) {
188  if (goal_active.isValid()) {
189  switch (goal_active.getGoalStatus().status) {
190  case actionlib_msgs::GoalStatus::ACTIVE:
191  case actionlib_msgs::GoalStatus::PREEMPTING:
192  goal_active.setAborted(result, msg);
193  break;
194  }
195  }
196  goal_pending.setAccepted();
197  goal_active = goal_pending;
198  return isActive();
199  }
200  else {
201  // if pending is in RECALLING cancelHook perform necessary actions
202  return false;
203  }
204 }
205 
206 template <class ActionSpec> bool RTTSimpleActionServer<ActionSpec>::rejectPending(const Result& result, const std::string& msg)
207 {
208  if (!goal_pending.isValid()) return false;
209  switch (goal_pending.getGoalStatus().status) {
210  case actionlib_msgs::GoalStatus::PENDING:
211  case actionlib_msgs::GoalStatus::RECALLING:
212  goal_pending.setRejected(result, msg);
213  return true;
214  }
215  return false;
216 }
217 
218 template <class ActionSpec> bool RTTSimpleActionServer<ActionSpec>::publishFeedback(const Feedback& feedpack)
219 {
220  if (!isActive()) return false;
221  goal_active.publishFeedback(feedpack);
222  return true;
223 }
224 
225 template <class ActionSpec> bool RTTSimpleActionServer<ActionSpec>::abortActive(const Result& result, const std::string& msg)
226 {
227  if (!goal_active.isValid()) return false;
228  switch (goal_active.getGoalStatus().status) {
229  case actionlib_msgs::GoalStatus::ACTIVE:
230  case actionlib_msgs::GoalStatus::PREEMPTING:
231  goal_active.setAborted(result, msg);
232  return true;
233  }
234  return false;
235 }
236 
237 template <class ActionSpec> bool RTTSimpleActionServer<ActionSpec>::cancelActive(const Result& result, const std::string& msg)
238 {
239  if (!goal_active.isValid()) return false;
240  switch (goal_active.getGoalStatus().status) {
241  case actionlib_msgs::GoalStatus::ACTIVE:
242  case actionlib_msgs::GoalStatus::PREEMPTING:
243  goal_active.setCanceled(result, msg);
244  return true;
245  }
246  return true;
247 }
248 
249 template <class ActionSpec> bool RTTSimpleActionServer<ActionSpec>::succeedActive(const Result& result, const std::string& msg)
250 {
251  if (!goal_active.isValid()) return false;
252  switch (goal_active.getGoalStatus().status) {
253  case actionlib_msgs::GoalStatus::ACTIVE:
254  case actionlib_msgs::GoalStatus::PREEMPTING:
255  goal_active.setSucceeded(result, msg);
256  return true;
257  }
258  return false;
259 }
260 
261 template <class ActionSpec> void RTTSimpleActionServer<ActionSpec>::goalCallback(GoalHandle gh)
262 {
263  if (goal_pending.isValid()) {
264  switch (goal_pending.getGoalStatus().status) {
265  case actionlib_msgs::GoalStatus::PENDING:
266  case actionlib_msgs::GoalStatus::RECALLING:
267  goal_pending.setRejected(Result(), "Pending goal is replaced by new received goal.");
268  break;
269  }
270  }
271  goal_pending = gh;
272  if (isPending() && newGoalHook) {
273  newGoalHook(*goal_pending.getGoal());
274  }
275 }
276 
277 template <class ActionSpec> void RTTSimpleActionServer<ActionSpec>::cancelCallback(GoalHandle gh) {
278  if (!gh.isValid()) return;
279  switch (gh.getGoalStatus().status) {
280  case actionlib_msgs::GoalStatus::ACTIVE:
281  case actionlib_msgs::GoalStatus::PREEMPTING:
282  case actionlib_msgs::GoalStatus::PENDING:
283  case actionlib_msgs::GoalStatus::RECALLING:
284  if (goal_active == gh) {
285  if (cancelGoalHook) cancelGoalHook();
286  // cancelActive(Result(), "Active goal is canceled by client request.");
287  }
288  else if (goal_pending == gh) {
289  gh.setCanceled(Result(), "Pending goal is canceled by client request.");
290  }
291  else {
292  gh.setCanceled(Result(), "Unknown goal.");
293  }
294  break;
295  }
296 }
297 
298 } // namespace rtt_actionlib
299 
300 #endif /*RTT_SIMPLE_ACTION_SERVER_HPP*/
void publishFeedback(const Feedback &feedback)
Orocos RTT-Based Action Server.
bool addPorts(RTT::Service::shared_ptr service, const bool create_topics=false, const std::string &topic_namespace="")
Add actionlib ports to a given rtt service.
void setGoalHook(boost::function< void(const Goal &)> _newGoalHook)
Setup goal hook.
actionlib::ServerGoalHandle< ActionSpec > GoalHandle
bool succeedActive(const Result &result, const std::string &msg="")
Succeed active goal. Succeed active goal with given result, do nothing if there is no active goal...
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
boost::shared_ptr< const Goal > getGoal() const
bool publishFeedback(const Feedback &feedpack)
Publish feedback on active goal. Publish feedback on active goal, do nothing if there is no active go...
void setCancelHook(boost::function< void()> _cancelGoalHook)
Setup cancel hook.
boost::shared_ptr< const Goal > getActiveGoal() const
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
void setAccepted(const std::string &text=std::string(""))
void registerGoalCallback(boost::function< void(GoalHandle)> cb)
RTTSimpleActionServer(boost::shared_ptr< RTT::Service > owner_service)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void shutdown()
Shutdown internal timer.
bool ready()
Check if the server is ready to be started.
void registerCancelCallback(boost::function< void(GoalHandle)> cb)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
boost::function< void(const Goal &)> newGoalHook
RTTActionServer< ActionSpec > action_server
boost::shared_ptr< const Goal > getPendingGoal() const
bool rejectPending(const Result &result, const std::string &msg="")
Reject pending goal. Reject pending goal with result, do nothing if there is no pending goal...
bool cancelActive(const Result &result, const std::string &msg="")
Cancel active goal. Cancel active goal with given result, do nothing if there is no active goal...
bool acceptPending(const Result &result, const std::string &msg="")
Accept pending goal. Accept pending goal, preempt the active goal with result if present. Do nothing if there is no pending goal.
actionlib_msgs::GoalStatus getGoalStatus() const
bool abortActive(const Result &result, const std::string &msg="")
Abort active goal. Abort active goal with given result, do nothing if there is no active goal...


rtt_actionlib
Author(s): Jonathan Bohren
autogenerated on Mon May 10 2021 02:45:37