Go to the documentation of this file.
   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);
 
  101 #include "octomap/MapCollection.hxx" 
  
MAPNODE * associate(const Pointcloud &scan)
bool isOccupied(const point3d &p) const
bool removeNode(const MAPNODE *n)
bool castRay(const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
static void splitPathAndFilename(std::string &filenamefullpath, std::string *path, std::string *filename)
std::vector< MAPNODE * >::iterator iterator
static bool readTagValue(std::string tag, std::ifstream &infile, std::string *value)
void addNode(MAPNODE *node)
This class represents a three-dimensional vector.
std::vector< Pointcloud * > segment(const Pointcloud &scan) const
std::vector< MAPNODE * > nodes
std::vector< MAPNODE * >::const_iterator const_iterator
const_iterator end() const
bool read(std::string filename)
static std::string combinePathAndFilename(std::string path, std::string filename)
double getOccupancy(const point3d &p)
void insertScan(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false)
bool write(std::string filename)
const_iterator begin() const
bool writePointcloud(std::string filename)
MAPNODE * queryNode(const point3d &p)
octomap
Author(s): Kai M. Wurm 
, Armin Hornung 
autogenerated on Mon Apr 21 2025 02:39:48