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 setId(std::string newid)
Definition: MapNode.h:60
std::string id
Definition: MapNode.h:71
TREETYPE TreeType
Definition: MapNode.h:53
pose6d origin
Definition: MapNode.h:70
void clear()
Definition: MapNode.hxx:78
bool readMap(std::string filename)
Definition: MapNode.hxx:88
TREETYPE * getMap()
Definition: MapNode.h:55
TREETYPE * node_map
Definition: MapNode.h:69
~MapNode()
Definition: MapNode.hxx:58
pose6d getOrigin()
Definition: MapNode.h:62
Pointcloud generatePointcloud()
Definition: MapNode.hxx:67
void updateMap(const Pointcloud &cloud, point3d sensor_origin)
Definition: MapNode.hxx:63
bool writeMap(std::string filename)
Definition: MapNode.hxx:97
std::string getId()
Definition: MapNode.h:59
MapNode()
Definition: MapNode.hxx:37
A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan.
Definition: Pointcloud.h:47
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
This class represents a three-dimensional vector.
Definition: Vector3.h:50
Namespace the OctoMap library and visualization tools.