34#ifndef OCTOMAP_MAP_COLLECTION_H
35#define OCTOMAP_MAP_COLLECTION_H
44 template <
class MAPNODE>
57 bool isOccupied(
float x,
float y,
float z)
const;
62 bool ignoreUnknownCells=
false,
double maxRange=-1.0)
const;
65 bool write(std::string filename);
69 double maxrange=-1.,
bool pruning=
true,
bool lazy_eval =
false);
73 typedef typename std::vector<MAPNODE*>::iterator
iterator;
83 bool read(std::string filename);
90 static void splitPathAndFilename(std::string &filenamefullpath, std::string* path, std::string *filename);
92 static bool readTagValue(std::string tag, std::ifstream &infile, std::string* value);
Definition: MapCollection.h:45
std::vector< MAPNODE * >::iterator iterator
Definition: MapCollection.h:73
static void splitPathAndFilename(std::string &filenamefullpath, std::string *path, std::string *filename)
Definition: MapCollection.hxx:284
static bool readTagValue(std::string tag, std::ifstream &infile, std::string *value)
Definition: MapCollection.hxx:315
void addNode(MAPNODE *node)
Definition: MapCollection.hxx:125
const_iterator begin() const
Definition: MapCollection.h:77
iterator end()
Definition: MapCollection.h:76
MapCollection()
Definition: MapCollection.hxx:41
bool writePointcloud(std::string filename)
Definition: MapCollection.hxx:218
const_iterator end() const
Definition: MapCollection.h:78
void insertScan(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false)
Definition: MapCollection.hxx:255
double getOccupancy(const point3d &p)
Definition: MapCollection.hxx:171
MAPNODE * queryNode(const point3d &p)
Definition: MapCollection.hxx:142
bool castRay(const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
Definition: MapCollection.hxx:189
bool isOccupied(const point3d &p) const
Definition: MapCollection.hxx:153
MAPNODE * associate(const Pointcloud &scan)
Definition: MapCollection.hxx:278
bool read(std::string filename)
Definition: MapCollection.hxx:64
~MapCollection()
Definition: MapCollection.hxx:50
iterator begin()
Definition: MapCollection.h:75
std::vector< MAPNODE * >::const_iterator const_iterator
Definition: MapCollection.h:74
bool write(std::string filename)
Definition: MapCollection.hxx:230
std::vector< MAPNODE * > nodes
Definition: MapCollection.h:96
std::vector< Pointcloud * > segment(const Pointcloud &scan) const
Definition: MapCollection.hxx:270
size_t size() const
Definition: MapCollection.h:79
void clear()
Definition: MapCollection.hxx:55
bool removeNode(const MAPNODE *n)
Definition: MapCollection.hxx:136
static std::string combinePathAndFilename(std::string path, std::string filename)
Definition: MapCollection.hxx:301
A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan.
Definition: Pointcloud.h:47
This class represents a three-dimensional vector.
Definition: Vector3.h:50
Namespace the OctoMap library and visualization tools.