FlatPointCloudVisualization.cpp
Go to the documentation of this file.
1 /*
2  * FlatPointCloudVisualization.cpp
3  *
4  * Created on: Mar 9, 2016
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
11 
12 #include <sensor_msgs/PointCloud2.h>
13 
14 namespace grid_map_visualization {
15 
17  : VisualizationBase(nodeHandle, name),
18  height_(0.0)
19 {
20 }
21 
23 {
24 }
25 
27 {
29 
30  height_ = 0.0;
31  if (!getParam("height", height_)) {
32  ROS_INFO("FlatPointCloudVisualization with name '%s' did not find a 'height' parameter. Using default.", name_.c_str());
33  }
34 
35  return true;
36 }
37 
39 {
40  publisher_ = nodeHandle_.advertise<sensor_msgs::PointCloud2>(name_, 1, true);
41  return true;
42 }
43 
45 {
46  if (!isActive()) return true;
47  sensor_msgs::PointCloud2 pointCloud;
48 
49  grid_map::GridMap mapCopy(map);
50  mapCopy.add("flat", height_);
51  grid_map::GridMapRosConverter::toPointCloud(mapCopy, "flat", pointCloud);
52 
53  publisher_.publish(pointCloud);
54  return true;
55 }
56 
57 } /* namespace */
void publish(const boost::shared_ptr< M > &message) const
static void toPointCloud(const grid_map::GridMap &gridMap, const std::string &pointLayer, sensor_msgs::PointCloud2 &pointCloud)
bool getParam(const std::string &name, std::string &value)
#define ROS_INFO(...)
FlatPointCloudVisualization(ros::NodeHandle &nodeHandle, const std::string &name)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double height_
Height of the z-coordinate at which the flat point cloud is visualized.
void add(const std::string &layer, const double value=NAN)
ros::NodeHandle & nodeHandle_
ROS nodehandle.
std::string name_
Name of the visualization.
ros::Publisher publisher_
ROS publisher of the occupancy grid.
virtual bool readParameters(XmlRpc::XmlRpcValue &config)


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