hector_exploration_planner.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2012, Mark Sollweck, Stefan Kohlbrecher, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Simulation, Systems Optimization and Robotics
00013 //       group, TU Darmstadt nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef HECTOR_EXPLORATION_PLANNER_H___
00030 #define HECTOR_EXPLORATION_PLANNER_H___
00031 
00032 #include <ros/ros.h>
00033 #include <costmap_2d/costmap_2d.h>
00034 #include <costmap_2d/costmap_2d_ros.h>
00035 #include <geometry_msgs/PoseStamped.h>
00036 
00037 #include <dynamic_reconfigure/server.h>
00038 
00039 #include <hector_exploration_planner/exploration_transform_vis.h>
00040 
00041 #include <boost/shared_array.hpp>
00042 
00043 namespace hector_exploration_planner{
00044 
00045 class ExplorationPlannerConfig;
00046 
00047 class HectorExplorationPlanner {
00048 public:
00049   HectorExplorationPlanner();
00050   ~HectorExplorationPlanner();
00051   HectorExplorationPlanner(std::string name,costmap_2d::Costmap2DROS *costmap_ros);
00052   void initialize(std::string name,costmap_2d::Costmap2DROS *costmap_ros);
00053 
00054   void dynRecParamCallback(hector_exploration_planner::ExplorationPlannerConfig &config, uint32_t level);
00055 
00063   bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &original_goal, std::vector<geometry_msgs::PoseStamped> &plan);
00064 
00070   bool doExploration(const geometry_msgs::PoseStamped &start,std::vector<geometry_msgs::PoseStamped> &plan);
00071 
00078   bool doInnerExploration(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan);
00079 
00080   bool getObservationPose(const geometry_msgs::PoseStamped& observation_pose, const double desired_distance, geometry_msgs::PoseStamped& new_observation_pose);
00081 
00082   bool doAlternativeExploration(const geometry_msgs::PoseStamped &start,std::vector<geometry_msgs::PoseStamped> &plan, std::vector<geometry_msgs::PoseStamped> &oldplan);
00083   bool findFrontiers(std::vector<geometry_msgs::PoseStamped> &frontiers, std::vector<geometry_msgs::PoseStamped> &noFrontiers);
00084   bool findFrontiersCloseToPath(std::vector<geometry_msgs::PoseStamped> &frontiers);
00085   bool findFrontiers(std::vector<geometry_msgs::PoseStamped> &frontiers);
00086   bool findInnerFrontier(std::vector<geometry_msgs::PoseStamped> &innerFrontier);
00087   
00088   float angleDifferenceWall(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal);
00089   bool exploreWalls(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &goals);
00090 
00091 private:
00092 
00093   enum LastMode{
00094     FRONTIER_EXPLORE,
00095     INNER_EXPLORE
00096   } last_mode_;
00097 
00101   void setupMapData();
00102   void deleteMapData();
00103   bool buildobstacle_trans_array_(bool use_inflated_obstacles);
00104   bool buildexploration_trans_array_(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> goals,bool useAnglePenalty, bool use_cell_danger = true);
00105   bool getTrajectory(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> goals, std::vector<geometry_msgs::PoseStamped> &plan);
00106   bool recoveryMakePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal,std::vector<geometry_msgs::PoseStamped> &plan);
00107   unsigned int cellDanger(int point);
00108   unsigned int angleDanger(float angle);
00109 
00110   void saveMaps(std::string path);
00111   void resetMaps();
00112   void clearFrontiers();
00113   bool isValid(int point);
00114   bool isFree(int point);
00115   bool isFreeFrontiers(int point);
00116   bool isFrontier(int point);
00117   float angleDifference(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal);
00118   float getDistanceWeight(const geometry_msgs::PoseStamped &point1, const geometry_msgs::PoseStamped &point2);
00119   double getYawToUnknown(int point);
00120   bool isFrontierReached(int point);
00121   bool isSameFrontier(int frontier_point1,int frontier_point2);
00122 
00123   void getStraightPoints(int point, int points[]);
00124   void getDiagonalPoints(int point, int points[]);
00125   void getAdjacentPoints(int point, int points[]);
00126   int left(int point);
00127   int upleft(int point);
00128   int up(int point);
00129   int upright(int point);
00130   int right(int point);
00131   int downright(int point);
00132   int down(int point);
00133   int downleft(int point);
00134 
00135   ros::Publisher observation_pose_pub_;
00136   ros::Publisher goal_pose_pub_;
00137 
00138   ros::Publisher visualization_pub_;
00139   ros::ServiceClient path_service_client_;
00140   costmap_2d::Costmap2DROS* costmap_ros_;
00141   costmap_2d::Costmap2D* costmap_;
00142 
00143   const unsigned char* occupancy_grid_array_;
00144   boost::shared_array<unsigned int> exploration_trans_array_;
00145   boost::shared_array<unsigned int> obstacle_trans_array_;
00146   boost::shared_array<int> frontier_map_array_;
00147   boost::shared_array<bool> is_goal_array_;
00148 
00149   bool initialized_;
00150   int previous_goal_;
00151 
00152   std::string name;
00153   unsigned int map_width_;
00154   unsigned int map_height_;
00155   unsigned int num_map_cells_;
00156 
00157   // Parameters
00158   bool p_plan_in_unknown_;
00159   bool p_explore_close_to_path_;
00160   bool p_use_inflated_obs_;
00161   int p_goal_angle_penalty_;
00162   int p_min_obstacle_dist_;
00163   int p_min_frontier_size_;
00164   double p_alpha_;
00165   double p_dist_for_goal_reached_;
00166   double p_same_frontier_dist_;
00167   double p_obstacle_cutoff_dist_;
00168   double p_cos_of_allowed_observation_pose_angle_;
00169   double p_close_to_path_target_distance_;
00170 
00171   boost::shared_ptr<dynamic_reconfigure::Server<hector_exploration_planner::ExplorationPlannerConfig> > dyn_rec_server_;
00172 
00173   boost::shared_ptr<ExplorationTransformVis> vis_;
00174   boost::shared_ptr<ExplorationTransformVis> close_path_vis_;
00175   boost::shared_ptr<ExplorationTransformVis> inner_vis_;
00176   boost::shared_ptr<ExplorationTransformVis> obstacle_vis_;
00177 
00178 };
00179 }
00180 
00181 #endif
00182 
00183 


hector_exploration_planner
Author(s): Mark Sollweck, Stefan Kohlbrecher, Florian Berz
autogenerated on Fri Aug 28 2015 11:01:32