Go to the documentation of this file.
51 std::ofstream binary_outfile( filename.c_str(), std::ios_base::binary);
53 if (!binary_outfile.is_open()){
61 std::ofstream binary_outfile( filename.c_str(), std::ios_base::binary);
63 if (!binary_outfile.is_open()){
68 binary_outfile.close();
81 s <<
binaryFileHeader <<
"\n# (feel free to add / change comments, but leave the first line as it is!)\n#\n";
83 s <<
"size "<< this->
size() << std::endl;
85 s <<
"data" << std::endl;
105 s.read((
char*)&tree_type,
sizeof(tree_type));
110 s.read((
char*)&res,
sizeof(res));
127 std::ifstream binary_infile( filename.c_str(), std::ios_base::binary);
128 if (!binary_infile.is_open()){
143 std::istream::pos_type streampos = s.tellg();
144 std::getline(s, line);
173 OCTOMAP_ERROR(
"Tree size mismatch: # read nodes (%zu) != # expected nodes (%d)\n",this->
size(), size);
void setProbMiss(double prob)
sets the probability for a "miss" (will be converted to logodds) - sensor model
bool writeBinaryConst(const std::string &filename) const
virtual std::ostream & writeBinaryData(std::ostream &s) const =0
Writes the actual data, implemented in OccupancyOcTreeBase::writeBinaryData()
#define OCTOMAP_WARNING_STR(args)
static const std::string binaryFileHeader
void setOccupancyThres(double prob)
sets the threshold for occupancy (sensor model)
AbstractOccupancyOcTree()
bool readBinary(std::istream &s)
#define OCTOMAP_DEBUG(...)
virtual std::istream & readBinaryData(std::istream &s)=0
Reads the actual data, implemented in OccupancyOcTreeBase::readBinaryData()
#define OCTOMAP_DEBUG_STR(args)
bool readBinaryLegacyHeader(std::istream &s, unsigned int &size, double &res)
Try to read the old binary format for conversion, will be removed in the future.
virtual double getResolution() const =0
void setClampingThresMin(double thresProb)
sets the minimum threshold for occupancy clamping (sensor model)
#define OCTOMAP_ERROR(...)
static bool readHeader(std::istream &s, std::string &id, unsigned &size, double &res)
void setClampingThresMax(double thresProb)
sets the maximum threshold for occupancy clamping (sensor model)
virtual std::string getTreeType() const =0
returns actual class name as string for identification
void setProbHit(double prob)
sets the probability for a "hit" (will be converted to logodds) - sensor model
#define OCTOMAP_ERROR_STR(args)
virtual size_t size() const =0
virtual void toMaxLikelihood()=0
virtual void setResolution(double res)=0
bool writeBinary(const std::string &filename)
octomap
Author(s): Kai M. Wurm
, Armin Hornung
autogenerated on Tue Dec 12 2023 03:39:40