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
00040
00041 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_
00042 #define MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_
00043
00044 #include <map>
00045 #include <stdint.h>
00046 #include <string>
00047 #include <vector>
00048
00049 #include <geometry_msgs/PoseStamped.h>
00050 #include <tf/transform_listener.h>
00051
00052 #include <mbf_abstract_core/abstract_planner.h>
00053 #include <mbf_utility/types.h>
00054
00055 #include <mbf_utility/navigation_utility.h>
00056
00057 #include "mbf_abstract_nav/abstract_execution_base.h"
00058
00059 namespace mbf_abstract_nav
00060 {
00061
00076 class AbstractPlannerExecution : public AbstractExecutionBase
00077 {
00078 public:
00079
00081 typedef boost::shared_ptr<AbstractPlannerExecution > Ptr;
00082
00087 AbstractPlannerExecution(const std::string name,
00088 const mbf_abstract_core::AbstractPlanner::Ptr planner_ptr,
00089 const MoveBaseFlexConfig &config,
00090 boost::function<void()> setup_fn,
00091 boost::function<void()> cleanup_fn);
00092
00096 virtual ~AbstractPlannerExecution();
00097
00103 std::vector<geometry_msgs::PoseStamped> getPlan();
00104
00109 ros::Time getLastValidPlanTime();
00110
00115 bool isPatienceExceeded();
00116
00120 enum PlanningState
00121 {
00122 INITIALIZED,
00123 STARTED,
00124 PLANNING,
00125 FOUND_PLAN,
00126 MAX_RETRIES,
00127 PAT_EXCEEDED,
00128 NO_PLAN_FOUND,
00129 CANCELED,
00130 STOPPED,
00131 INTERNAL_ERROR
00132 };
00133
00138 PlanningState getState();
00139
00143 double getFrequency() { return frequency_; };
00144
00149 double getCost();
00150
00156 virtual bool cancel();
00157
00163 void setNewGoal(const geometry_msgs::PoseStamped &goal, double tolerance);
00164
00169 void setNewStart(const geometry_msgs::PoseStamped &start);
00170
00177 void setNewStartAndGoal(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal,
00178 double tolerance);
00179
00187 bool start(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal,
00188 double tolerance);
00189
00195 void reconfigure(const MoveBaseFlexConfig &config);
00196
00197 protected:
00198
00200 mbf_abstract_core::AbstractPlanner::Ptr planner_;
00201
00203 std::string plugin_name_;
00204
00208 virtual void run();
00209
00210 private:
00211
00223 virtual uint32_t makePlan(
00224 const geometry_msgs::PoseStamped &start,
00225 const geometry_msgs::PoseStamped &goal,
00226 double tolerance,
00227 std::vector<geometry_msgs::PoseStamped> &plan,
00228 double &cost,
00229 std::string &message);
00230
00235 void setState(PlanningState state);
00236
00238 boost::mutex state_mtx_;
00239
00241 boost::mutex plan_mtx_;
00242
00244 boost::mutex goal_start_mtx_;
00245
00247 boost::mutex planning_mtx_;
00248
00250 bool has_new_goal_;
00251
00253 bool has_new_start_;
00254
00256 ros::Time last_call_start_time_;
00257
00259 ros::Time last_valid_plan_time_;
00260
00262 std::vector<geometry_msgs::PoseStamped> plan_;
00263
00265 double cost_;
00266
00268 geometry_msgs::PoseStamped start_;
00269
00271 geometry_msgs::PoseStamped goal_;
00272
00274 double tolerance_;
00275
00277 double frequency_;
00278
00280 ros::Duration patience_;
00281
00283 int max_retries_;
00284
00286 bool planning_;
00287
00289 std::string robot_frame_;
00290
00292 std::string global_frame_;
00293
00295 const TFPtr tf_listener_ptr_;
00296
00298 PlanningState state_;
00299
00301 boost::mutex configuration_mutex_;
00302
00303 };
00304
00305 }
00306
00307 #endif