12 #include <octomap/ColorOcTree.h> 13 #include <octomap/octomap.h> 32 octomap::ColorOcTree, octomap::ColorOcTreeNode>;
47 CColouredOctoMap::TMapDefinition::TMapDefinition() =
default;
48 void CColouredOctoMap::TMapDefinition::loadFromConfigFile_map_specific(
54 sectionNamePrefix +
string(
"_creationOpts");
57 insertionOpts.loadFromConfigFile(
58 source, sectionNamePrefix +
string(
"_insertOpts"));
59 likelihoodOpts.loadFromConfigFile(
60 source, sectionNamePrefix +
string(
"_likelihoodOpts"));
63 void CColouredOctoMap::TMapDefinition::dumpToTextStream_map_specific(
64 std::ostream& out)
const 68 this->insertionOpts.dumpToTextStream(out);
69 this->likelihoodOpts.dumpToTextStream(out);
92 CColouredOctoMap::~CColouredOctoMap() =
default;
93 uint8_t CColouredOctoMap::serializeGetVersion()
const {
return 3; }
96 this->likelihoodOptions.writeToStream(out);
97 this->renderingOptions.writeToStream(out);
98 out << genericMapParams;
101 std::stringstream ss;
102 m_impl->m_octomap.writeBinaryConst(ss);
107 void CColouredOctoMap::serializeFrom(
117 "Deserialization of old versions of this class was " 118 "discontinued in MRPT 1.9.9 [no CMemoryChunk]");
123 this->likelihoodOptions.readFromStream(
in);
124 if (version >= 1) this->renderingOptions.readFromStream(
in);
125 if (version >= 2)
in >> genericMapParams;
134 std::stringstream ss;
137 m_impl->m_octomap.readBinary(ss);
149 bool CColouredOctoMap::internal_insertObservation(
152 octomap::point3d sensorPt;
153 octomap::Pointcloud scan;
157 robotPose3D = (*robotPose);
173 octomap::point3d(sensorPose.
x(), sensorPose.
y(), sensorPose.z());
176 const size_t nPts = scanPts->
size();
182 for (
size_t i = 0; i < nPts; i++)
185 scanPts->getPointFast(i, pt.
x, pt.
y, pt.
z);
192 scan.push_back(gx, gy, gz);
196 m_impl->m_octomap.insertPointCloud(
197 scan, sensorPt, insertionOptions.maxrange,
198 insertionOptions.pruning);
224 octomap::point3d(sensorPose.
x(), sensorPose.
y(), sensorPose.z());
226 const size_t sizeRangeScan = pts->size();
227 scan.reserve(sizeRangeScan);
229 for (
size_t i = 0; i < sizeRangeScan; i++)
235 if (pt.
x != 0 || pt.
y != 0 || pt.
z != 0)
236 scan.push_back(pt.
x, pt.
y, pt.
z);
240 octomap::KeySet free_cells, occupied_cells;
241 m_impl->m_octomap.computeUpdate(
242 scan, sensorPt, free_cells, occupied_cells,
243 insertionOptions.maxrange);
246 for (
const auto& free_cell : free_cells)
248 m_impl->m_octomap.updateNode(free_cell,
false,
false);
250 for (
const auto& occupied_cell : occupied_cells)
252 m_impl->m_octomap.updateNode(occupied_cell,
true,
false);
256 const float colF2B = 255.0f;
257 for (
size_t i = 0; i < sizeRangeScan; i++)
263 if (pt.
x != 0 || pt.
y != 0 || pt.
z != 0)
264 this->updateVoxelColour(
270 if (insertionOptions.pruning) m_impl->m_octomap.prune();
281 bool CColouredOctoMap::getPointColour(
285 octomap::OcTreeKey key;
286 if (m_impl->m_octomap.coordToKeyChecked(octomap::point3d(
x,
y,
z), key))
288 octomap::ColorOcTreeNode* node =
289 m_impl->m_octomap.search(key, 0 );
290 if (!node)
return false;
292 const octomap::ColorOcTreeNode::Color& col = node->getColor();
303 void CColouredOctoMap::updateVoxelColour(
304 const double x,
const double y,
const double z,
const uint8_t r,
307 switch (m_colour_method)
310 m_impl->m_octomap.integrateNodeColor(
x,
y,
z,
r,
g,
b);
313 m_impl->m_octomap.setNodeColor(
x,
y,
z,
r,
g,
b);
316 m_impl->m_octomap.averageNodeColor(
x,
y,
z,
r,
g,
b);
325 void CColouredOctoMap::getAsOctoMapVoxels(
331 octomap::ColorOcTree::tree_iterator it_end = m_impl->m_octomap.end_tree();
333 const unsigned char max_depth = 0;
335 const TColor general_color_u(
336 general_color.
R * 255, general_color.
G * 255, general_color.
B * 255,
337 general_color.
A * 255);
348 const size_t nLeafs = this->getNumLeafNodes();
352 double xmin, xmax, ymin, ymax, zmin,
zmax;
353 this->getMetricMin(xmin, ymin, zmin);
354 this->getMetricMax(xmax, ymax,
zmax);
356 for (octomap::ColorOcTree::tree_iterator it =
357 m_impl->m_octomap.begin_tree(max_depth);
360 const octomap::point3d vx_center = it.getCoordinate();
361 const double vx_length = it.getSize();
362 const double L = 0.5 * vx_length;
367 const double occ = it->getOccupancy();
368 if ((occ >= 0.5 && renderingOptions.generateOccupiedVoxels) ||
369 (occ < 0.5 && renderingOptions.generateFreeVoxels))
372 octomap::ColorOcTreeNode::Color node_color = it->getColor();
373 vx_color =
TColor(node_color.r, node_color.g, node_color.b);
375 const size_t vx_set = (m_impl->m_octomap.isNodeOccupied(*it))
382 TPoint3D(vx_center.x(), vx_center.y(), vx_center.z()),
383 vx_length, vx_color));
386 else if (renderingOptions.generateGridLines)
390 vx_center.x() - L, vx_center.y() - L, vx_center.z() - L);
392 vx_center.x() + L, vx_center.y() + L, vx_center.z() + L);
405 this->getMetricMin(bbmin.
x, bbmin.
y, bbmin.
z);
406 this->getMetricMax(bbmax.
x, bbmax.
y, bbmax.
z);
411 void CColouredOctoMap::insertRay(
412 const float end_x,
const float end_y,
const float end_z,
413 const float sensor_x,
const float sensor_y,
const float sensor_z)
415 m_impl->m_octomap.insertRay(
416 octomap::point3d(sensor_x, sensor_y, sensor_z),
417 octomap::point3d(end_x, end_y, end_z), insertionOptions.maxrange,
418 insertionOptions.pruning);
420 void CColouredOctoMap::updateVoxel(
421 const double x,
const double y,
const double z,
bool occupied)
423 m_impl->m_octomap.updateNode(
x,
y,
z, occupied);
425 bool CColouredOctoMap::isPointWithinOctoMap(
426 const float x,
const float y,
const float z)
const 428 octomap::OcTreeKey key;
429 return m_impl->m_octomap.coordToKeyChecked(octomap::point3d(
x,
y,
z), key);
432 double CColouredOctoMap::getResolution()
const 434 return m_impl->m_octomap.getResolution();
436 unsigned int CColouredOctoMap::getTreeDepth()
const 438 return m_impl->m_octomap.getTreeDepth();
441 size_t CColouredOctoMap::memoryUsage()
const 443 return m_impl->m_octomap.memoryUsage();
445 size_t CColouredOctoMap::memoryUsageNode()
const 447 return m_impl->m_octomap.memoryUsageNode();
449 size_t CColouredOctoMap::memoryFullGrid()
const 451 return m_impl->m_octomap.memoryFullGrid();
453 double CColouredOctoMap::volume() {
return m_impl->m_octomap.volume(); }
454 void CColouredOctoMap::getMetricSize(
double&
x,
double&
y,
double&
z)
456 return m_impl->m_octomap.getMetricSize(
x,
y,
z);
458 void CColouredOctoMap::getMetricSize(
double&
x,
double&
y,
double&
z)
const 460 return m_impl->m_octomap.getMetricSize(
x,
y,
z);
462 void CColouredOctoMap::getMetricMin(
double&
x,
double&
y,
double&
z)
464 return m_impl->m_octomap.getMetricMin(
x,
y,
z);
466 void CColouredOctoMap::getMetricMin(
double&
x,
double&
y,
double&
z)
const 468 return m_impl->m_octomap.getMetricMin(
x,
y,
z);
470 void CColouredOctoMap::getMetricMax(
double&
x,
double&
y,
double&
z)
472 return m_impl->m_octomap.getMetricMax(
x,
y,
z);
474 void CColouredOctoMap::getMetricMax(
double&
x,
double&
y,
double&
z)
const 476 return m_impl->m_octomap.getMetricMax(
x,
y,
z);
478 size_t CColouredOctoMap::calcNumNodes()
const 480 return m_impl->m_octomap.calcNumNodes();
482 size_t CColouredOctoMap::getNumLeafNodes()
const 484 return m_impl->m_octomap.getNumLeafNodes();
486 void CColouredOctoMap::setOccupancyThres(
double prob)
488 m_impl->m_octomap.setOccupancyThres(prob);
490 void CColouredOctoMap::setProbHit(
double prob)
492 m_impl->m_octomap.setProbHit(prob);
494 void CColouredOctoMap::setProbMiss(
double prob)
496 m_impl->m_octomap.setProbMiss(prob);
498 void CColouredOctoMap::setClampingThresMin(
double thresProb)
500 m_impl->m_octomap.setClampingThresMin(thresProb);
502 void CColouredOctoMap::setClampingThresMax(
double thresProb)
504 m_impl->m_octomap.setClampingThresMax(thresProb);
506 double CColouredOctoMap::getOccupancyThres()
const 508 return m_impl->m_octomap.getOccupancyThres();
510 float CColouredOctoMap::getOccupancyThresLog()
const 512 return m_impl->m_octomap.getOccupancyThresLog();
514 double CColouredOctoMap::getProbHit()
const 516 return m_impl->m_octomap.getProbHit();
518 float CColouredOctoMap::getProbHitLog()
const 520 return m_impl->m_octomap.getProbHitLog();
522 double CColouredOctoMap::getProbMiss()
const 524 return m_impl->m_octomap.getProbMiss();
526 float CColouredOctoMap::getProbMissLog()
const 528 return m_impl->m_octomap.getProbMissLog();
530 double CColouredOctoMap::getClampingThresMin()
const 532 return m_impl->m_octomap.getClampingThresMin();
534 float CColouredOctoMap::getClampingThresMinLog()
const 536 return m_impl->m_octomap.getClampingThresMinLog();
538 double CColouredOctoMap::getClampingThresMax()
const 540 return m_impl->m_octomap.getClampingThresMax();
542 float CColouredOctoMap::getClampingThresMaxLog()
const 544 return m_impl->m_octomap.getClampingThresMaxLog();
546 void CColouredOctoMap::internal_clear() { m_impl->m_octomap.clear(); }
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)
double x
X,Y,Z coordinates.
static Ptr Create(Args &&... args)
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixed< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixed< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixed< double, 3, 6 > *out_jacobian_df_dse3=nullptr, 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...
const mrpt::poses::CPose3D * robotPoseInTheWorld
(Default: nullptr) Read takeIntoAccountSensorPoseOnRobot
#define THROW_EXCEPTION(msg)
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
To be added to all CSerializable-classes implementation files.
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.
void clear()
Clears everything.
GLsizei GLsizei GLuint * obj
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
void push_back_GridCube(const TGridCube &c)
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
mrpt::maps::CColouredOctoMap::TInsertionOptions insertionOpts
meters)
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...
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.
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
double x() const
Common members of all points & poses classes.
GLsizei const GLchar ** string
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 LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
#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...
Virtual base class for "archives": classes abstracting I/O streams.
GLdouble GLdouble GLdouble r
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)
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
mrpt::img::TColorf getColor() const
Returns the object color property as a TColorf.
A RGB color - floats in the range [0,1].
The namespace for 3D scene representation and rendering.
GLsizei GLsizei GLchar * source
bool PROJ3D_USE_LUT
(Default:true) [Only used when range_is_depth=true] Whether to use a Look-up-table (LUT) to speed up ...
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.
size_t size() const
Returns the number of stored points in the map.
bool isCubeTransparencyEnabled() const
void clear()
Clear the contents of this container.
void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory...