Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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
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
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_