Main Page
Namespaces
Classes
Files
File List
File Members
include
grid_map_visualization
visualizations
FlatPointCloudVisualization.hpp
Go to the documentation of this file.
1
/*
2
* FlatPointCloudVisualization.hpp
3
*
4
* Created on: Mar 9, 2016
5
* Author: Péter Fankhauser
6
* Institute: ETH Zurich, ANYbotics
7
*/
8
9
#pragma once
10
11
#include <
grid_map_visualization/visualizations/VisualizationBase.hpp
>
12
#include <
grid_map_core/GridMap.hpp
>
13
14
// ROS
15
#include <
ros/ros.h
>
16
17
namespace
grid_map_visualization
{
18
22
class
FlatPointCloudVisualization
:
public
VisualizationBase
23
{
24
public
:
25
31
FlatPointCloudVisualization
(
ros::NodeHandle
& nodeHandle,
const
std::string& name);
32
36
virtual
~FlatPointCloudVisualization
();
37
43
bool
readParameters
(
XmlRpc::XmlRpcValue
& config);
44
48
bool
initialize
();
49
55
bool
visualize
(
const
grid_map::GridMap
& map);
56
57
private
:
59
std::string
layer_
;
60
62
double
height_
;
63
};
64
65
}
/* namespace */
grid_map_visualization::FlatPointCloudVisualization::readParameters
bool readParameters(XmlRpc::XmlRpcValue &config)
Definition:
FlatPointCloudVisualization.cpp:26
ros::NodeHandle
XmlRpc::XmlRpcValue
grid_map_visualization::FlatPointCloudVisualization::~FlatPointCloudVisualization
virtual ~FlatPointCloudVisualization()
Definition:
FlatPointCloudVisualization.cpp:22
grid_map_visualization::VisualizationBase
Definition:
VisualizationBase.hpp:20
grid_map::GridMap
GridMap.hpp
grid_map_visualization
Definition:
GridMapVisualization.hpp:26
grid_map_visualization::FlatPointCloudVisualization::FlatPointCloudVisualization
FlatPointCloudVisualization(ros::NodeHandle &nodeHandle, const std::string &name)
Definition:
FlatPointCloudVisualization.cpp:16
grid_map_visualization::FlatPointCloudVisualization::layer_
std::string layer_
Type that is transformed to points.
Definition:
FlatPointCloudVisualization.hpp:59
grid_map_visualization::FlatPointCloudVisualization
Definition:
FlatPointCloudVisualization.hpp:22
ros.h
grid_map_visualization::FlatPointCloudVisualization::height_
double height_
Height of the z-coordinate at which the flat point cloud is visualized.
Definition:
FlatPointCloudVisualization.hpp:62
grid_map_visualization::FlatPointCloudVisualization::initialize
bool initialize()
Definition:
FlatPointCloudVisualization.cpp:38
VisualizationBase.hpp
grid_map_visualization::FlatPointCloudVisualization::visualize
bool visualize(const grid_map::GridMap &map)
Definition:
FlatPointCloudVisualization.cpp:44
grid_map_visualization
Author(s): Péter Fankhauser
autogenerated on Tue Jun 1 2021 02:13:51