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
OccupancyGridVisualization.hpp
Go to the documentation of this file.
1
/*
2
* PointCloudOccupancyGrid.hpp
3
*
4
* Created on: Nov 3, 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
19
class
OccupancyGridVisualization
:
public
VisualizationBase
20
{
21
public
:
22
28
OccupancyGridVisualization
(
ros::NodeHandle
& nodeHandle,
const
std::string& name);
29
33
virtual
~OccupancyGridVisualization
();
34
40
bool
readParameters
(
XmlRpc::XmlRpcValue
& config);
41
45
bool
initialize
();
46
52
bool
visualize
(
const
grid_map::GridMap
& map);
53
54
private
:
55
57
std::string
layer_
;
58
60
float
dataMin_
,
dataMax_
;
61
};
62
63
}
/* namespace */
grid_map_visualization::OccupancyGridVisualization::visualize
bool visualize(const grid_map::GridMap &map)
Definition:
OccupancyGridVisualization.cpp:54
grid_map_visualization::OccupancyGridVisualization::OccupancyGridVisualization
OccupancyGridVisualization(ros::NodeHandle &nodeHandle, const std::string &name)
Definition:
OccupancyGridVisualization.cpp:15
ros::NodeHandle
XmlRpc::XmlRpcValue
grid_map_visualization::VisualizationBase
Definition:
VisualizationBase.hpp:20
grid_map::GridMap
GridMap.hpp
grid_map_visualization
Definition:
GridMapVisualization.hpp:26
grid_map_visualization::OccupancyGridVisualization::dataMax_
float dataMax_
Definition:
OccupancyGridVisualization.hpp:60
grid_map_visualization::OccupancyGridVisualization::layer_
std::string layer_
Type that is transformed to the occupancy grid.
Definition:
OccupancyGridVisualization.hpp:57
grid_map_visualization::OccupancyGridVisualization::readParameters
bool readParameters(XmlRpc::XmlRpcValue &config)
Definition:
OccupancyGridVisualization.cpp:26
ros.h
grid_map_visualization::OccupancyGridVisualization::~OccupancyGridVisualization
virtual ~OccupancyGridVisualization()
Definition:
OccupancyGridVisualization.cpp:22
grid_map_visualization::OccupancyGridVisualization::initialize
bool initialize()
Definition:
OccupancyGridVisualization.cpp:48
grid_map_visualization::OccupancyGridVisualization::dataMin_
float dataMin_
Minimum and maximum value of the grid map data (used to normalize the cell data in [min...
Definition:
OccupancyGridVisualization.hpp:60
VisualizationBase.hpp
grid_map_visualization::OccupancyGridVisualization
Definition:
OccupancyGridVisualization.hpp:19
grid_map_visualization
Author(s): Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:23:56