sbpl_lattice_planner.h
Go to the documentation of this file.
00001 #ifndef SBPL_LATTICE_PLANNER_H
00002 #define SBPL_LATTICE_PLANNER_H
00003 
00004 #include <iostream>
00005 #include <vector>
00006 
00007 using namespace std;
00008 
00010 #include <ros/ros.h>
00011 
00012 // Costmap used for the map representation
00013 #include <costmap_2d/costmap_2d_ros.h>
00014 
00015 // sbpl headers
00016 #include <sbpl/headers.h>
00017 
00018 //global representation
00019 #include <nav_core/base_global_planner.h>
00020 
00021 namespace sbpl_lattice_planner{
00022 
00023 class SBPLLatticePlanner : public nav_core::BaseGlobalPlanner{
00024 public:
00025   
00029   SBPLLatticePlanner();
00030 
00031   
00037   SBPLLatticePlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00038 
00039 
00045   virtual void initialize(std::string name, 
00046                           costmap_2d::Costmap2DROS* costmap_ros);
00047   
00055   virtual bool makePlan(const geometry_msgs::PoseStamped& start, 
00056                         const geometry_msgs::PoseStamped& goal, 
00057                         std::vector<geometry_msgs::PoseStamped>& plan);
00058 
00059   virtual ~SBPLLatticePlanner(){};
00060 
00061 private:
00062   unsigned char costMapCostToSBPLCost(unsigned char newcost);
00063   void publishStats(int solution_cost, int solution_size, 
00064                     const geometry_msgs::PoseStamped& start, 
00065                     const geometry_msgs::PoseStamped& goal);
00066 
00067   bool initialized_;
00068 
00069   SBPLPlanner* planner_;
00070   EnvironmentNAVXYTHETALAT* env_;
00071   
00072   std::string planner_type_; 
00074   double allocated_time_; 
00075   double initial_epsilon_; 
00077   std::string environment_type_; 
00078   std::string cost_map_topic_; 
00080   bool forward_search_; 
00081   std::string primitive_filename_; 
00082   int force_scratch_limit_; 
00084   unsigned char lethal_obstacle_;
00085   unsigned char inscribed_inflated_obstacle_;
00086   unsigned char sbpl_cost_multiplier_;
00087 
00088 
00089   costmap_2d::Costmap2DROS* costmap_ros_; 
00090   costmap_2d::Costmap2D cost_map_;        
00092   ros::Publisher plan_pub_;
00093   ros::Publisher stats_publisher_;
00094   
00095   std::vector<geometry_msgs::Point> footprint_;
00096 
00097 };
00098 };
00099 
00100 #endif
00101 


sbpl_lattice_planner
Author(s): Michael Phillips
autogenerated on Mon Oct 6 2014 02:48:57