OccupancyGridVisualization.cpp
Go to the documentation of this file.
1 /*
2  * OccupancyGridVisualization.cpp
3  *
4  * Created on: Nov 3, 2014
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
11 #include <nav_msgs/OccupancyGrid.h>
12 
13 namespace grid_map_visualization {
14 
16 : VisualizationBase(nodeHandle, name),
17  dataMin_(0.0),
18  dataMax_(1.0)
19 {
20 }
21 
23 {
24 }
25 
27 {
29 
30  if (!getParam("layer", layer_)) {
31  ROS_ERROR("OccupancyGridVisualization with name '%s' did not find a 'layer' parameter.", name_.c_str());
32  return false;
33  }
34 
35  if (!getParam("data_min", dataMin_)) {
36  ROS_ERROR("OccupancyGridVisualization with name '%s' did not find a 'data_min' parameter.", name_.c_str());
37  return false;
38  }
39 
40  if (!getParam("data_max", dataMax_)) {
41  ROS_ERROR("OccupancyGridVisualization with name '%s' did not find a 'data_max' parameter.", name_.c_str());
42  return false;
43  }
44 
45  return true;
46 }
47 
49 {
50  publisher_ = nodeHandle_.advertise<nav_msgs::OccupancyGrid>(name_, 1, true);
51  return true;
52 }
53 
55 {
56  if (!isActive()) return true;
57  if (!map.exists(layer_)) {
58  ROS_WARN_STREAM("OccupancyGridVisualization::visualize: No grid map layer with name '" << layer_ << "' found.");
59  return false;
60  }
61  nav_msgs::OccupancyGrid occupancyGrid;
63  publisher_.publish(occupancyGrid);
64  return true;
65 }
66 
67 } /* namespace */
OccupancyGridVisualization(ros::NodeHandle &nodeHandle, const std::string &name)
void publish(const boost::shared_ptr< M > &message) const
static void toOccupancyGrid(const grid_map::GridMap &gridMap, const std::string &layer, float dataMin, float dataMax, nav_msgs::OccupancyGrid &occupancyGrid)
bool exists(const std::string &layer) const
bool getParam(const std::string &name, std::string &value)
std::string layer_
Type that is transformed to the occupancy grid.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
ros::NodeHandle & nodeHandle_
ROS nodehandle.
std::string name_
Name of the visualization.
float dataMin_
Minimum and maximum value of the grid map data (used to normalize the cell data in [min...
ros::Publisher publisher_
ROS publisher of the occupancy grid.
virtual bool readParameters(XmlRpc::XmlRpcValue &config)
#define ROS_ERROR(...)


grid_map_visualization
Author(s): Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:32