39 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_ 40 #define MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_ 43 #include <mbf_abstract_nav/MoveBaseFlexConfig.h> 48 template <
typename Action,
typename Execution>
54 typedef boost::function<void (GoalHandle &goal_handle, Execution &execution)>
RunMethod;
63 const std::string& name,
65 const RunMethod run_method
69 GoalHandle &goal_handle,
70 typename Execution::Ptr execution_ptr
73 uint8_t slot = goal_handle.
getGoal()->concurrency_slot;
75 if(goal_handle.
getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
81 typename std::map<uint8_t, ConcurrencySlot>::iterator slot_it =
86 slot_it->second.execution->cancel();
87 if (slot_it->second.thread_ptr->joinable()) {
88 slot_it->second.thread_ptr->join();
102 virtual void cancel(GoalHandle &goal_handle){
103 uint8_t slot = goal_handle.
getGoal()->concurrency_slot;
106 typename std::map<uint8_t, ConcurrencySlot>::iterator slot_it =
concurrency_slots_.find(slot);
113 virtual void runAndCleanUp(GoalHandle &goal_handle,
typename Execution::Ptr execution_ptr){
114 uint8_t slot = goal_handle.
getGoal()->concurrency_slot;
116 if (execution_ptr->setup_fn_)
117 execution_ptr->setup_fn_();
118 run_(goal_handle, *execution_ptr);
120 execution_ptr->join();
129 if (execution_ptr->cleanup_fn_)
130 execution_ptr->cleanup_fn_();
134 mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
138 typename std::map<uint8_t, ConcurrencySlot>::iterator iter;
141 iter->second.execution->reconfigure(config);
149 typename std::map<uint8_t, ConcurrencySlot>::iterator iter;
152 iter->second.execution->cancel();
171 #endif //MBF_ABSTRACT_NAV__ABSTRACT_ACTION_H_ const RobotInformation & robot_info_
#define ROS_DEBUG_STREAM_NAMED(name, args)
boost::mutex slot_map_mtx_
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)
const std::string & name_
boost::thread_group threads_
virtual void reconfigureAll(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
actionlib::ActionServer< Action >::GoalHandle GoalHandle
boost::thread * thread_ptr
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