sbpl_lattice_planner.h
Go to the documentation of this file.
1 #ifndef SBPL_LATTICE_PLANNER_H
2 #define SBPL_LATTICE_PLANNER_H
3 
4 #include <iostream>
5 #include <vector>
6 
7 using namespace std;
8 
9 // ROS
10 #include <ros/ros.h>
11 #include <geometry_msgs/PoseStamped.h>
12 
13 // Costmap used for the map representation
15 
16 // sbpl headers
17 #include <sbpl/headers.h>
18 
19 // global representation
21 
23 
25 public:
26 
31 
32 
38  SBPLLatticePlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
39 
40 
46  virtual void initialize(std::string name,
47  costmap_2d::Costmap2DROS* costmap_ros);
48 
56  virtual bool makePlan(const geometry_msgs::PoseStamped& start,
57  const geometry_msgs::PoseStamped& goal,
58  std::vector<geometry_msgs::PoseStamped>& plan);
59 
60  virtual ~SBPLLatticePlanner(){};
61 
62 private:
63  unsigned char costMapCostToSBPLCost(unsigned char newcost);
64  void publishStats(int solution_cost, int solution_size,
65  const geometry_msgs::PoseStamped& start,
66  const geometry_msgs::PoseStamped& goal);
67 
68  unsigned char computeCircumscribedCost();
69 
71 
72  SBPLPlanner* planner_;
73  EnvironmentNAVXYTHETALAT* env_;
74 
75  std::string planner_type_;
77  double allocated_time_;
80  std::string environment_type_;
81  std::string cost_map_topic_;
84  std::string primitive_filename_;
87  unsigned char lethal_obstacle_;
89  unsigned char circumscribed_cost_;
90  unsigned char sbpl_cost_multiplier_;
91 
92  std::string name_;
94  std::vector<geometry_msgs::Point> footprint_;
95  unsigned int current_env_width_;
96  unsigned int current_env_height_;
97 
100 };
101 };
102 
103 #endif
104 
ROSCONSOLE_DECL void initialize()
std::vector< geometry_msgs::Point > footprint_


sbpl_lattice_planner
Author(s): Michael Phillips
autogenerated on Mon Jun 22 2020 03:18:17