Go to the documentation of this file.
34 #ifndef OCTOMAP_MAP_NODE_H
35 #define OCTOMAP_MAP_NODE_H
43 template <
class TREETYPE>
60 inline void setId(std::string newid) {
id = newid; }
74 bool readMap(std::string filename);
void updateMap(const Pointcloud &cloud, point3d sensor_origin)
Definition: MapNode.hxx:63
A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan.
Definition: Pointcloud.h:47
void setId(std::string newid)
Definition: MapNode.h:60
TREETYPE * node_map
Definition: MapNode.h:69
bool writeMap(std::string filename)
Definition: MapNode.hxx:97
pose6d origin
Definition: MapNode.h:70
This class represents a three-dimensional vector.
Definition: Vector3.h:50
pose6d getOrigin()
Definition: MapNode.h:62
bool readMap(std::string filename)
Definition: MapNode.hxx:88
MapNode()
Definition: MapNode.hxx:37
~MapNode()
Definition: MapNode.hxx:58
TREETYPE TreeType
Definition: MapNode.h:53
TREETYPE * getMap()
Definition: MapNode.h:55
Tables used by the Marching Cubes Algorithm The tables are from Paul Bourke's web page http://paulbou...
std::string id
Definition: MapNode.h:71
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
std::string getId()
Definition: MapNode.h:59
Pointcloud generatePointcloud()
Definition: MapNode.hxx:67
void clear()
Definition: MapNode.hxx:78