Public Member Functions | Private Attributes | List of all members
base_local_planner::MapGridVisualizer Class Reference

#include <map_grid_visualizer.h>

Public Member Functions

void initialize (const std::string &name, std::string frame, boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function)
 Initializes the MapGridVisualizer. More...
 
 MapGridVisualizer ()
 Default constructor. More...
 
void publishCostCloud (const costmap_2d::Costmap2D *costmap_p_)
 Build and publish a PointCloud if the publish_cost_grid_pc parameter was true. Only include points for which the cost_function at (cx,cy) returns true. More...
 
 ~MapGridVisualizer ()
 

Private Attributes

pcl::PointCloud< MapGridCostPoint > * cost_cloud_
 
boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function_
 The function to be used to generate the cost components for the output PointCloud. More...
 
std::string name_
 The name to get parameters relative to. More...
 
ros::NodeHandle ns_nh_
 
pcl_ros::Publisher< MapGridCostPointpub_
 

Detailed Description

Definition at line 44 of file map_grid_visualizer.h.

Constructor & Destructor Documentation

base_local_planner::MapGridVisualizer::MapGridVisualizer ( )

Default constructor.

Definition at line 41 of file map_grid_visualizer.cpp.

base_local_planner::MapGridVisualizer::~MapGridVisualizer ( )
inline

Destructor for the visualizer

Definition at line 62 of file map_grid_visualizer.h.

Member Function Documentation

void base_local_planner::MapGridVisualizer::initialize ( const std::string &  name,
std::string  frame,
boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)>  cost_function 
)

Initializes the MapGridVisualizer.

Parameters
nameThe name to be appended to ~/ in order to get the proper namespace for parameters
costmapThe costmap instance to use to get the size of the map to generate a point cloud for
cost_functionThe function to use to compute the cost values to be inserted into each point in the output PointCloud as well as whether to include a given point or not

Definition at line 44 of file map_grid_visualizer.cpp.

void base_local_planner::MapGridVisualizer::publishCostCloud ( const costmap_2d::Costmap2D costmap_p_)

Build and publish a PointCloud if the publish_cost_grid_pc parameter was true. Only include points for which the cost_function at (cx,cy) returns true.

Definition at line 55 of file map_grid_visualizer.cpp.

Member Data Documentation

pcl::PointCloud<MapGridCostPoint>* base_local_planner::MapGridVisualizer::cost_cloud_
private

Definition at line 73 of file map_grid_visualizer.h.

boost::function<bool (int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> base_local_planner::MapGridVisualizer::cost_function_
private

The function to be used to generate the cost components for the output PointCloud.

Definition at line 71 of file map_grid_visualizer.h.

std::string base_local_planner::MapGridVisualizer::name_
private

The name to get parameters relative to.

Definition at line 70 of file map_grid_visualizer.h.

ros::NodeHandle base_local_planner::MapGridVisualizer::ns_nh_
private

Definition at line 72 of file map_grid_visualizer.h.

pcl_ros::Publisher<MapGridCostPoint> base_local_planner::MapGridVisualizer::pub_
private

Definition at line 74 of file map_grid_visualizer.h.


The documentation for this class was generated from the following files:


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:49