abstract_action.h
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Sebastian Pütz
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * abstract_action.h
34  *
35  * author: Sebastian Pütz <spuetz@uni-osnabrueck.de>
36  *
37  */
38 
39 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_
40 #define MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_
41 
43 #include <mbf_abstract_nav/MoveBaseFlexConfig.h>
45 
46 namespace mbf_abstract_nav{
47 
48 template <typename Action, typename Execution>
50 {
51  public:
54  typedef boost::function<void (GoalHandle &goal_handle, Execution &execution)> RunMethod;
55  typedef struct{
56  typename Execution::Ptr execution;
57  boost::thread* thread_ptr;
58  GoalHandle goal_handle;
60 
61 
63  const std::string& name,
64  const RobotInformation &robot_info,
65  const RunMethod run_method
66  ) : name_(name), robot_info_(robot_info), run_(run_method){}
67 
68  virtual void start(
69  GoalHandle &goal_handle,
70  typename Execution::Ptr execution_ptr
71  )
72  {
73  uint8_t slot = goal_handle.getGoal()->concurrency_slot;
74 
75  if(goal_handle.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
76  {
77  goal_handle.setCanceled();
78  }
79  else {
80  slot_map_mtx_.lock();
81  typename std::map<uint8_t, ConcurrencySlot>::iterator slot_it =
82  concurrency_slots_.find(slot);
83  slot_map_mtx_.unlock();
84  if (slot_it != concurrency_slots_.end()) {
85  // if there is a plugin running on the same slot, cancel it
86  slot_it->second.execution->cancel();
87  if (slot_it->second.thread_ptr->joinable()) {
88  slot_it->second.thread_ptr->join();
89  }
90  }
91  boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
92  // fill concurrency slot with the new goal handle, execution, and working thread
93  concurrency_slots_[slot].goal_handle = goal_handle;
94  concurrency_slots_[slot].goal_handle.setAccepted();
95  concurrency_slots_[slot].execution = execution_ptr;
96  concurrency_slots_[slot].thread_ptr = threads_.create_thread(boost::bind(
98  boost::ref(concurrency_slots_[slot].goal_handle), execution_ptr));
99  }
100  }
101 
102  virtual void cancel(GoalHandle &goal_handle){
103  uint8_t slot = goal_handle.getGoal()->concurrency_slot;
104 
105  boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
106  typename std::map<uint8_t, ConcurrencySlot>::iterator slot_it = concurrency_slots_.find(slot);
107  if(slot_it != concurrency_slots_.end())
108  {
109  concurrency_slots_[slot].execution->cancel();
110  }
111  }
112 
113  virtual void runAndCleanUp(GoalHandle &goal_handle, typename Execution::Ptr execution_ptr){
114  uint8_t slot = goal_handle.getGoal()->concurrency_slot;
115 
116  if (execution_ptr->setup_fn_)
117  execution_ptr->setup_fn_();
118  run_(goal_handle, *execution_ptr);
119  ROS_DEBUG_STREAM_NAMED(name_, "Finished action \"" << name_ << "\" run method, waiting for execution thread to finish.");
120  execution_ptr->join();
121  ROS_DEBUG_STREAM_NAMED(name_, "Execution thread for action \"" << name_ << "\" stopped, cleaning up execution leftovers.");
122  boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
123  ROS_DEBUG_STREAM_NAMED(name_, "Exiting run method with goal status: "
124  << concurrency_slots_[slot].goal_handle.getGoalStatus().text
125  << " and code: " << concurrency_slots_[slot].goal_handle.getGoalStatus().status);
126  threads_.remove_thread(concurrency_slots_[slot].thread_ptr);
127  delete concurrency_slots_[slot].thread_ptr;
128  concurrency_slots_.erase(slot);
129  if (execution_ptr->cleanup_fn_)
130  execution_ptr->cleanup_fn_();
131  }
132 
133  virtual void reconfigureAll(
134  mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
135  {
136  boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
137 
138  typename std::map<uint8_t, ConcurrencySlot>::iterator iter;
139  for(iter = concurrency_slots_.begin(); iter != concurrency_slots_.end(); ++iter)
140  {
141  iter->second.execution->reconfigure(config);
142  }
143  }
144 
145  virtual void cancelAll()
146  {
147  ROS_INFO_STREAM_NAMED(name_, "Cancel all goals for \"" << name_ << "\".");
148  boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
149  typename std::map<uint8_t, ConcurrencySlot>::iterator iter;
150  for(iter = concurrency_slots_.begin(); iter != concurrency_slots_.end(); ++iter)
151  {
152  iter->second.execution->cancel();
153  }
154  threads_.join_all();
155  }
156 
157 protected:
158  const std::string &name_;
160 
161  RunMethod run_;
162  boost::thread_group threads_;
163  std::map<uint8_t, ConcurrencySlot> concurrency_slots_;
164 
165  boost::mutex slot_map_mtx_;
166 
167 };
168 
169 }
170 
171 #endif //MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_
const RobotInformation & robot_info_
#define ROS_DEBUG_STREAM_NAMED(name, args)
boost::shared_ptr< const Goal > getGoal() const
AbstractAction(const std::string &name, const RobotInformation &robot_info, const RunMethod run_method)
#define ROS_INFO_STREAM_NAMED(name, args)
boost::function< void(GoalHandle &goal_handle, Execution &execution)> RunMethod
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
boost::shared_ptr< AbstractAction > Ptr
virtual void cancel(GoalHandle &goal_handle)
virtual void reconfigureAll(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
actionlib::ActionServer< Action >::GoalHandle GoalHandle
virtual void start(GoalHandle &goal_handle, typename Execution::Ptr execution_ptr)
std::map< uint8_t, ConcurrencySlot > concurrency_slots_
virtual void runAndCleanUp(GoalHandle &goal_handle, typename Execution::Ptr execution_ptr)
actionlib_msgs::GoalStatus getGoalStatus() const


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:34