base_local_planner::MapGridVisualizer Class Reference

#include <map_grid_visualizer.h>

List of all members.

Public Member Functions

void initialize (const std::string &name, const costmap_2d::Costmap2D *costmap, boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function)
 Initializes the MapGridVisualizer.
 MapGridVisualizer ()
 Default constructor.
void publishCostCloud ()
 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.
 ~MapGridVisualizer ()

Private Attributes

pcl::PointCloud< MapGridCostPointcost_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.
const costmap_2d::Costmap2D * costmap_p_
 The costmap to use to infer the size of the underlying map grid.
std::string frame_id_
 The frame to assign to the output PointCloud.
std::string name_
 The name to get parameters relative to.
ros::NodeHandle ns_nh_
pcl_ros::Publisher
< MapGridCostPoint
pub_
bool publish_cost_grid_pc_
 Whether or not to build and publsih a PointCloud.

Detailed Description

Definition at line 43 of file map_grid_visualizer.h.


Constructor & Destructor Documentation

base_local_planner::MapGridVisualizer::MapGridVisualizer (  ) 

Default constructor.

Definition at line 39 of file map_grid_visualizer.cpp.

base_local_planner::MapGridVisualizer::~MapGridVisualizer (  )  [inline]

Destructor for the visualizer

Definition at line 60 of file map_grid_visualizer.h.


Member Function Documentation

void base_local_planner::MapGridVisualizer::initialize ( const std::string &  name,
const costmap_2d::Costmap2D *  costmap,
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:
name The name to be appended to ~/ in order to get the proper namespace for parameters
costmap The costmap instance to use to get the size of the map to generate a point cloud for
cost_function The 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 42 of file map_grid_visualizer.cpp.

void base_local_planner::MapGridVisualizer::publishCostCloud (  ) 

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

Definition at line 74 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 70 of file map_grid_visualizer.h.

const costmap_2d::Costmap2D* base_local_planner::MapGridVisualizer::costmap_p_ [private]

The costmap to use to infer the size of the underlying map grid.

Definition at line 72 of file map_grid_visualizer.h.

The frame to assign to the output PointCloud.

Definition at line 69 of file map_grid_visualizer.h.

The name to get parameters relative to.

Definition at line 68 of file map_grid_visualizer.h.

Definition at line 73 of file map_grid_visualizer.h.

Definition at line 75 of file map_grid_visualizer.h.

Whether or not to build and publsih a PointCloud.

Definition at line 71 of file map_grid_visualizer.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko
autogenerated on Fri Jan 11 09:41:55 2013