Main Page
+
Namespaces
Namespace List
+
Namespace Members
All
Functions
Typedefs
+
Classes
Class List
Class Hierarchy
+
Class Members
+
All
a
c
d
f
g
h
i
l
m
n
o
p
r
s
t
u
v
~
+
Functions
c
f
g
i
m
o
p
r
u
v
~
+
Variables
a
c
d
f
h
i
l
m
n
p
s
t
u
v
+
Files
File List
+
File Members
All
Functions
include
grid_map_visualization
visualizations
PointCloudVisualization.hpp
Go to the documentation of this file.
1
/*
2
* PointCloudVisualization.hpp
3
*
4
* Created on: Sep 11, 2014
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
PointCloudVisualization
:
public
VisualizationBase
23
{
24
public
:
25
31
PointCloudVisualization
(
ros::NodeHandle
& nodeHandle,
const
std::string& name);
32
36
virtual
~PointCloudVisualization
();
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
};
61
62
}
/* namespace */
ros::NodeHandle
XmlRpc::XmlRpcValue
grid_map_visualization::VisualizationBase
Definition:
VisualizationBase.hpp:20
grid_map_visualization::PointCloudVisualization::~PointCloudVisualization
virtual ~PointCloudVisualization()
Definition:
PointCloudVisualization.cpp:21
grid_map_visualization::PointCloudVisualization::readParameters
bool readParameters(XmlRpc::XmlRpcValue &config)
Definition:
PointCloudVisualization.cpp:25
grid_map::GridMap
GridMap.hpp
grid_map_visualization
Definition:
GridMapVisualization.hpp:26
grid_map_visualization::PointCloudVisualization
Definition:
PointCloudVisualization.hpp:22
ros.h
grid_map_visualization::PointCloudVisualization::visualize
bool visualize(const grid_map::GridMap &map)
Definition:
PointCloudVisualization.cpp:41
grid_map_visualization::PointCloudVisualization::layer_
std::string layer_
Type that is transformed to points.
Definition:
PointCloudVisualization.hpp:59
grid_map_visualization::PointCloudVisualization::initialize
bool initialize()
Definition:
PointCloudVisualization.cpp:35
VisualizationBase.hpp
grid_map_visualization::PointCloudVisualization::PointCloudVisualization
PointCloudVisualization(ros::NodeHandle &nodeHandle, const std::string &name)
Definition:
PointCloudVisualization.cpp:16
grid_map_visualization
Author(s): Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:23:56