12 #include <octomap/octomap.h> 13 #include <octomap/ColorOcTree.h> 59 insertionOpts.loadFromConfigFile(
source, sectionNamePrefix+
string(
"_insertOpts") );
60 likelihoodOpts.loadFromConfigFile(
source, sectionNamePrefix+
string(
"_likelihoodOpts") );
67 this->insertionOpts.dumpToTextStream(out);
68 this->likelihoodOpts.dumpToTextStream(out);
88 m_colour_method(INTEGRATE)
90 m_octomap.ptr.reset(
new octomap::ColorOcTree(resolution));
96 CColouredOctoMap::~CColouredOctoMap()
111 this->likelihoodOptions.writeToStream(out);
112 this->renderingOptions.writeToStream(out);
113 out << genericMapParams;
117 const_cast<octomap::ColorOcTree*
>(&
PIMPL_GET_REF(ColorOcTree,m_octomap))->writeBinary(tmpFil);
139 if (
version>=1) this->renderingOptions.readFromStream(
in);
147 if (chunk.getTotalBytesCount())
150 if (!chunk.saveBufferToFile( tmpFil ) )
THROW_EXCEPTION(
"Error saving temporary file");
167 octomap::point3d sensorPt;
168 octomap::Pointcloud scan;
172 robotPose3D = (*robotPose);
186 sensorPt = octomap::point3d(sensorPose.
x(),sensorPose.
y(),sensorPose.z());
189 const size_t nPts = scanPts->
size();
195 for (
size_t i=0;i<nPts;i++)
198 scanPts->getPointFast(i,pt.
x,pt.
y,pt.
z);
205 scan.push_back(gx,gy,gz);
209 PIMPL_GET_REF(ColorOcTree, m_octomap).insertPointCloud(scan, sensorPt, insertionOptions.maxrange, insertionOptions.pruning);
231 sensorPt = octomap::point3d(sensorPose.
x(),sensorPose.
y(),sensorPose.z());
233 const size_t sizeRangeScan = pts->size();
234 scan.reserve(sizeRangeScan);
236 for (
size_t i=0;i<sizeRangeScan;i++)
241 if (pt.
x!=0 || pt.
y!=0 || pt.
z!=0)
242 scan.push_back(pt.
x,pt.
y,pt.
z);
246 octomap::KeySet free_cells, occupied_cells;
247 PIMPL_GET_REF(ColorOcTree, m_octomap).computeUpdate(scan, sensorPt, free_cells, occupied_cells, insertionOptions.maxrange);
251 PIMPL_GET_REF(ColorOcTree, m_octomap).updateNode(*it,
false,
false);
254 PIMPL_GET_REF(ColorOcTree, m_octomap).updateNode(*it,
true,
false);
258 const float colF2B = 255.0f;
259 for (
size_t i=0;i<sizeRangeScan;i++)
264 if (pt.
x!=0 || pt.
y!=0 || pt.
z!=0)
269 if (insertionOptions.pruning)
PIMPL_GET_REF(ColorOcTree, m_octomap).prune();
281 octomap::OcTreeKey key;
282 if (
PIMPL_GET_REF(ColorOcTree, m_octomap).coordToKeyChecked(octomap::point3d(
x,
y,
z), key))
284 octomap::ColorOcTreeNode *node =
PIMPL_GET_REF(ColorOcTree, m_octomap).search(key,0 );
285 if (!node)
return false;
287 const octomap::ColorOcTreeNode::Color &col = node->getColor();
299 switch (m_colour_method) {
321 octomap::ColorOcTree::tree_iterator it_end =
PIMPL_GET_REF(ColorOcTree, m_octomap).end_tree();
323 const unsigned char max_depth = 0;
325 const TColor general_color_u(general_color.
R*255,general_color.
G*255,general_color.
B*255,general_color.
A*255);
335 const size_t nLeafs = this->getNumLeafNodes();
339 double xmin, xmax, ymin, ymax, zmin,
zmax;
340 this->getMetricMin(xmin, ymin, zmin);
341 this->getMetricMax(xmax, ymax,
zmax);
343 for(octomap::ColorOcTree::tree_iterator it =
PIMPL_GET_REF(ColorOcTree, m_octomap).begin_tree(max_depth);it!=it_end; ++it)
345 const octomap::point3d vx_center = it.getCoordinate();
346 const double vx_length = it.getSize();
347 const double L = 0.5*vx_length;
352 const double occ = it->getOccupancy();
353 if ( (occ>=0.5 && renderingOptions.generateOccupiedVoxels) ||
354 (occ<0.5 && renderingOptions.generateFreeVoxels) )
357 octomap::ColorOcTreeNode::Color node_color = it->getColor();
358 vx_color =
TColor(node_color.r, node_color.g, node_color.b);
365 else if (renderingOptions.generateGridLines)
381 this->getMetricMin(bbmin.
x,bbmin.
y,bbmin.
z);
382 this->getMetricMax(bbmax.
x,bbmax.
y,bbmax.
z);
387 void CColouredOctoMap::insertRay(
const float end_x,
const float end_y,
const float end_z,
const float sensor_x,
const float sensor_y,
const float sensor_z)
389 PIMPL_GET_REF(ColorOcTree, m_octomap).insertRay(octomap::point3d(sensor_x, sensor_y, sensor_z), octomap::point3d(end_x, end_y, end_z), insertionOptions.maxrange, insertionOptions.pruning);
391 void CColouredOctoMap::updateVoxel(
const double x,
const double y,
const double z,
bool occupied)
395 bool CColouredOctoMap::isPointWithinOctoMap(
const float x,
const float y,
const float z)
const 397 octomap::OcTreeKey key;
401 double CColouredOctoMap::getResolution()
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getResolution(); }
402 unsigned int CColouredOctoMap::getTreeDepth()
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getTreeDepth(); }
404 size_t CColouredOctoMap::memoryUsage()
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).memoryUsage(); }
405 size_t CColouredOctoMap::memoryUsageNode()
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).memoryUsageNode(); }
406 size_t CColouredOctoMap::memoryFullGrid()
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).memoryFullGrid(); }
407 double CColouredOctoMap::volume() {
return PIMPL_GET_REF(ColorOcTree, m_octomap).volume(); }
408 void CColouredOctoMap::getMetricSize(
double&
x,
double&
y,
double&
z) {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getMetricSize(
x,
y,
z); }
409 void CColouredOctoMap::getMetricSize(
double&
x,
double&
y,
double&
z)
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getMetricSize(
x,
y,
z); }
410 void CColouredOctoMap::getMetricMin(
double&
x,
double&
y,
double&
z) {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getMetricMin(
x,
y,
z); }
411 void CColouredOctoMap::getMetricMin(
double&
x,
double&
y,
double&
z)
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getMetricMin(
x,
y,
z); }
412 void CColouredOctoMap::getMetricMax(
double&
x,
double&
y,
double&
z) {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getMetricMax(
x,
y,
z); }
413 void CColouredOctoMap::getMetricMax(
double&
x,
double&
y,
double&
z)
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getMetricMax(
x,
y,
z); }
414 size_t CColouredOctoMap::calcNumNodes()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).calcNumNodes(); }
415 size_t CColouredOctoMap::getNumLeafNodes()
const {
return PIMPL_GET_CONSTREF(ColorOcTree, m_octomap).getNumLeafNodes(); }
416 void CColouredOctoMap::setOccupancyThres(
double prob) {
PIMPL_GET_REF(ColorOcTree, m_octomap).setOccupancyThres(prob) ; }
417 void CColouredOctoMap::setProbHit(
double prob) {
PIMPL_GET_REF(ColorOcTree, m_octomap).setProbHit(prob); }
418 void CColouredOctoMap::setProbMiss(
double prob) {
PIMPL_GET_REF(ColorOcTree, m_octomap).setProbMiss(prob); }
419 void CColouredOctoMap::setClampingThresMin(
double thresProb) {
PIMPL_GET_REF(ColorOcTree, m_octomap).setClampingThresMin(thresProb); }
420 void CColouredOctoMap::setClampingThresMax(
double thresProb) {
PIMPL_GET_REF(ColorOcTree, m_octomap).setClampingThresMax(thresProb); }
421 double CColouredOctoMap::getOccupancyThres()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getOccupancyThres(); }
422 float CColouredOctoMap::getOccupancyThresLog()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getOccupancyThresLog(); }
423 double CColouredOctoMap::getProbHit()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getProbHit(); }
424 float CColouredOctoMap::getProbHitLog()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getProbHitLog(); }
425 double CColouredOctoMap::getProbMiss()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getProbMiss(); }
426 float CColouredOctoMap::getProbMissLog()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getProbMissLog(); }
427 double CColouredOctoMap::getClampingThresMin()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getClampingThresMin(); }
428 float CColouredOctoMap::getClampingThresMinLog()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getClampingThresMinLog(); }
429 double CColouredOctoMap::getClampingThresMax()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getClampingThresMax(); }
430 float CColouredOctoMap::getClampingThresMaxLog()
const {
return PIMPL_GET_REF(ColorOcTree, m_octomap).getClampingThresMaxLog(); }
431 void CColouredOctoMap::internal_clear() {
PIMPL_GET_REF(ColorOcTree, m_octomap).clear(); }
double x() const
Common members of all points & poses classes.
void showVoxels(unsigned int voxel_set, bool show)
Shows/hides the voxels (voxel_set is a 0-based index for the set of voxels to modify, e.g.
Virtual base for specifying the kind and parameters of one map (normally, to be inserted into mrpt::m...
void reserveVoxels(const size_t set_index, const size_t nVoxels)
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
const mrpt::poses::CPose3D * robotPoseInTheWorld
(Default: NULL) Read takeIntoAccountSensorPoseOnRobot
#define THROW_EXCEPTION(msg)
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
void setBoundingBox(const mrpt::math::TPoint3D &bb_min, const mrpt::math::TPoint3D &bb_max)
Manually changes the bounding box (normally the user doesn't need to call this)
void reserveGridCubes(const size_t nCubes)
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
mrpt::maps::CColouredOctoMap::TLikelihoodOptions likelihoodOpts
Probabilistic observation likelihood options.
double z
X,Y,Z coordinates.
void clear()
Clears everything.
IMPLEMENTS_SERIALIZABLE(CLogFileRecord_FullEval, CHolonomicLogFileRecord, mrpt::nav) IMPLEMENTS_SERIALIZABLE(CHolonomicFullEval
GLsizei GLsizei GLuint * obj
void clear()
Clear the contents of this container.
This class allows loading and storing values and vectors of different types from a configuration text...
void readFromStream(mrpt::utils::CStream &in, int version)
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
void push_back_GridCube(const TGridCube &c)
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
This base provides a set of functions for maths stuff.
std::string BASE_IMPEXP getTempFileName()
Returns the name of a proposed temporary file name.
mrpt::maps::CColouredOctoMap::TInsertionOptions insertionOpts
Observations insertion options.
Lightweight 3D point (float version).
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
#define PIMPL_GET_CONSTREF(_TYPE, _VAR_NAME)
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
void project3DPointsFromDepthImageInto(mrpt::obs::CObservation3DRangeScan &src_obs, POINTMAP &dest_pointcloud, const mrpt::obs::T3DPointsProjectionParams &projectParams, const mrpt::obs::TRangeImageFilterParams &filterParams)
This namespace contains representation of robot actions and observations.
PIMPL_IMPLEMENT(octomap::ColorOcTree)
A memory buffer (implements CStream) which can be itself serialized.
GLsizei const GLchar ** string
#define PIMPL_GET_REF(_TYPE, _VAR_NAME)
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
The info of each grid block.
void push_back_Voxel(const size_t set_index, const TVoxel &v)
#define MRPT_LOAD_CONFIG_VAR(variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
The info of each of the voxels.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define MAP_DEFINITION_REGISTER(_CLASSNAME_STRINGS, _CLASSNAME_WITH_NS)
Registers one map class into TMetricMapInitializer factory.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
GLdouble GLdouble GLdouble r
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
Declares a virtual base class for all metric maps storage classes.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Declares a class that represents any robot's observation.
void resizeVoxelSets(const size_t nVoxelSets)
#define IS_CLASS(ptrObj, class_name)
Evaluates to true if the given pointer to an object (derived from mrpt::utils::CSerializable) is of t...
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
The namespace for 3D scene representation and rendering.
GLsizei GLsizei GLchar * source
A RGB color - floats in the range [0,1].
bool BASE_IMPEXP deleteFile(const std::string &fileName)
Deletes a single file.
bool PROJ3D_USE_LUT
(Default:true) [Only used when range_is_depth=true] Whether to use a Look-up-table (LUT) to speed up ...
virtual void load() const MRPT_OVERRIDE
Makes sure all images and other fields which may be externally stored are loaded in memory...
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
double resolution
The finest resolution of the octomap (default: 0.10 meters)
bool loadBufferFromFile(const std::string &file_name)
Loads the entire buffer from a file *.
size_t size() const
Returns the number of stored points in the map.
bool isCubeTransparencyEnabled() const
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
static CPointCloudColouredPtr Create()
mrpt::utils::TColorf getColor() const
Returns the object color property as a TColorf.
const POINTSMAP * buildAuxPointsMap(const void *options=NULL) const
Returns a cached points map representing this laser scan, building it upon the first call...