1 #ifndef SBPL_LATTICE_PLANNER_H 2 #define SBPL_LATTICE_PLANNER_H 11 #include <geometry_msgs/PoseStamped.h> 17 #include <sbpl/headers.h> 56 virtual bool makePlan(
const geometry_msgs::PoseStamped& start,
57 const geometry_msgs::PoseStamped& goal,
58 std::vector<geometry_msgs::PoseStamped>& plan);
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);
68 unsigned char computeCircumscribedCost();
73 EnvironmentNAVXYTHETALAT*
env_;
EnvironmentNAVXYTHETALAT * env_
unsigned int current_env_width_
unsigned char circumscribed_cost_
std::string cost_map_topic_
ROSCONSOLE_DECL void initialize()
ros::Publisher stats_publisher_
std::string primitive_filename_
unsigned int current_env_height_
std::string environment_type_
std::string planner_type_
unsigned char lethal_obstacle_
unsigned char inscribed_inflated_obstacle_
costmap_2d::Costmap2DROS * costmap_ros_
virtual ~SBPLLatticePlanner()
std::vector< geometry_msgs::Point > footprint_
unsigned char sbpl_cost_multiplier_