abstract_action.h
Go to the documentation of this file.
00001 /*
00002  *  Copyright 2018, Sebastian Pütz
00003  *
00004  *  Redistribution and use in source and binary forms, with or without
00005  *  modification, are permitted provided that the following conditions
00006  *  are met:
00007  *
00008  *  1. Redistributions of source code must retain the above copyright
00009  *     notice, this list of conditions and the following disclaimer.
00010  *
00011  *  2. Redistributions in binary form must reproduce the above
00012  *     copyright notice, this list of conditions and the following
00013  *     disclaimer in the documentation and/or other materials provided
00014  *     with the distribution.
00015  *
00016  *  3. Neither the name of the copyright holder nor the names of its
00017  *     contributors may be used to endorse or promote products derived
00018  *     from this software without specific prior written permission.
00019  *
00020  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  *  POSSIBILITY OF SUCH DAMAGE.
00032  *
00033  *  abstract_action.h
00034  *
00035  *  author: Sebastian Pütz <spuetz@uni-osnabrueck.de>
00036  *
00037  */
00038 
00039 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_
00040 #define MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_
00041 
00042 #include <actionlib/server/action_server.h>
00043 #include <mbf_abstract_nav/MoveBaseFlexConfig.h>
00044 #include "mbf_abstract_nav/robot_information.h"
00045 
00046 namespace mbf_abstract_nav{
00047 
00048 template <typename Action, typename Execution>
00049 class AbstractAction
00050 {
00051  public:
00052   typedef boost::shared_ptr<AbstractAction> Ptr;
00053   typedef typename actionlib::ActionServer<Action>::GoalHandle GoalHandle;
00054   typedef boost::function<void (GoalHandle &goal_handle, Execution &execution)> RunMethod;
00055   typedef struct{
00056     typename Execution::Ptr execution;
00057     boost::thread* thread_ptr;
00058     GoalHandle goal_handle;
00059   } ConcurrencySlot;
00060 
00061 
00062   AbstractAction(
00063       const std::string& name,
00064       const RobotInformation &robot_info,
00065       const RunMethod run_method
00066   ) : name_(name), robot_info_(robot_info), run_(run_method){}
00067 
00068   virtual void start(
00069       GoalHandle &goal_handle,
00070       typename Execution::Ptr execution_ptr
00071   )
00072   {
00073     uint8_t slot = goal_handle.getGoal()->concurrency_slot;
00074 
00075     if(goal_handle.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
00076     {
00077       goal_handle.setCanceled();
00078     }
00079     else {
00080       slot_map_mtx_.lock();
00081       typename std::map<uint8_t, ConcurrencySlot>::iterator slot_it =
00082           concurrency_slots_.find(slot);
00083       slot_map_mtx_.unlock();
00084       if (slot_it != concurrency_slots_.end()) {
00085         // if there is a plugin running on the same slot, cancel it
00086         slot_it->second.execution->cancel();
00087         if (slot_it->second.thread_ptr->joinable()) {
00088           slot_it->second.thread_ptr->join();
00089         }
00090       }
00091       boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
00092       // fill concurrency slot with the new goal handle, execution, and working thread
00093       concurrency_slots_[slot].goal_handle = goal_handle;
00094       concurrency_slots_[slot].goal_handle.setAccepted();
00095       concurrency_slots_[slot].execution = execution_ptr;
00096       concurrency_slots_[slot].thread_ptr = threads_.create_thread(boost::bind(
00097           &AbstractAction::runAndCleanUp, this,
00098           boost::ref(concurrency_slots_[slot].goal_handle), execution_ptr));
00099     }
00100   }
00101 
00102   virtual void cancel(GoalHandle &goal_handle){
00103     uint8_t slot = goal_handle.getGoal()->concurrency_slot;
00104 
00105     boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
00106     typename std::map<uint8_t, ConcurrencySlot>::iterator slot_it = concurrency_slots_.find(slot);
00107     if(slot_it != concurrency_slots_.end())
00108     {
00109       concurrency_slots_[slot].execution->cancel();
00110     }
00111   }
00112 
00113   virtual void runAndCleanUp(GoalHandle &goal_handle, typename Execution::Ptr execution_ptr){
00114     uint8_t slot = goal_handle.getGoal()->concurrency_slot;
00115 
00116     if (execution_ptr->setup_fn_)
00117       execution_ptr->setup_fn_();
00118     run_(goal_handle, *execution_ptr);
00119     ROS_DEBUG_STREAM_NAMED(name_, "Finished action \"" << name_ << "\" run method, waiting for execution thread to finish.");
00120     execution_ptr->join();
00121     ROS_DEBUG_STREAM_NAMED(name_, "Execution thread for action \"" << name_ << "\" stopped, cleaning up execution leftovers.");
00122     boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
00123     ROS_DEBUG_STREAM_NAMED(name_, "Exiting run method with goal status: "
00124                            << concurrency_slots_[slot].goal_handle.getGoalStatus().text
00125                            << " and code: " << concurrency_slots_[slot].goal_handle.getGoalStatus().status);
00126     threads_.remove_thread(concurrency_slots_[slot].thread_ptr);
00127     delete concurrency_slots_[slot].thread_ptr;
00128     concurrency_slots_.erase(slot);
00129     if (execution_ptr->cleanup_fn_)
00130       execution_ptr->cleanup_fn_();
00131   }
00132 
00133   virtual void reconfigureAll(
00134       mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
00135   {
00136     boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
00137 
00138     typename std::map<uint8_t, ConcurrencySlot>::iterator iter;
00139     for(iter = concurrency_slots_.begin(); iter != concurrency_slots_.end(); ++iter)
00140     {
00141       iter->second.execution->reconfigure(config);
00142     }
00143   }
00144 
00145   virtual void cancelAll()
00146   {
00147     ROS_INFO_STREAM_NAMED(name_, "Cancel all goals for \"" << name_ << "\".");
00148     boost::lock_guard<boost::mutex> guard(slot_map_mtx_);
00149     typename std::map<uint8_t, ConcurrencySlot>::iterator iter;
00150     for(iter = concurrency_slots_.begin(); iter != concurrency_slots_.end(); ++iter)
00151     {
00152       iter->second.execution->cancel();
00153     }
00154     threads_.join_all();
00155   }
00156 
00157 protected:
00158   const std::string &name_;
00159   const RobotInformation &robot_info_;
00160 
00161   RunMethod run_;
00162   boost::thread_group threads_;
00163   std::map<uint8_t, ConcurrencySlot> concurrency_slots_;
00164 
00165   boost::mutex slot_map_mtx_;
00166 
00167 };
00168 
00169 }
00170 
00171 #endif //MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Mon Jun 17 2019 20:11:35