Go to the documentation of this file.
36 template <
class TREETYPE>
40 template <
class TREETYPE>
42 this->node_map = in_node_map;
43 this->origin = in_origin;
46 template <
class TREETYPE>
50 template <
class TREETYPE>
57 template <
class TREETYPE>
62 template <
class TREETYPE>
66 template <
class TREETYPE>
70 node_map->getOccupied(occs);
71 for(point3d_list::iterator it = occs.begin(); it != occs.end(); ++it){
77 template <
class TREETYPE>
83 origin =
pose6d(0.0,0.0,0.0,0.0,0.0,0.0);
87 template <
class TREETYPE>
92 node_map =
new TREETYPE(0.05);
93 return node_map->readBinary(filename);
96 template <
class TREETYPE>
98 return node_map->writeBinary(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 push_back(float x, float y, float z)
Definition: Pointcloud.h:61
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
bool readMap(std::string filename)
Definition: MapNode.hxx:88
MapNode()
Definition: MapNode.hxx:37
~MapNode()
Definition: MapNode.hxx:58
std::list< octomath::Vector3 > point3d_list
Definition: octomap_types.h:54
Tables used by the Marching Cubes Algorithm The tables are from Paul Bourke's web page http://paulbou...
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
Pointcloud generatePointcloud()
Definition: MapNode.hxx:67
void clear()
Definition: MapNode.hxx:78
octomath::Pose6D pose6d
Use our Pose6D (float precision) as pose6d in octomap.
Definition: octomap_types.h:51