39 void CColouredOctoMap::TMapDefinition::loadFromConfigFile_map_specific(
45 sectionNamePrefix +
string(
"_creationOpts");
48 insertionOpts.loadFromConfigFile(
49 source, sectionNamePrefix +
string(
"_insertOpts"));
50 likelihoodOpts.loadFromConfigFile(
51 source, sectionNamePrefix +
string(
"_likelihoodOpts"));
54 void CColouredOctoMap::TMapDefinition::dumpToTextStream_map_specific(
59 this->insertionOpts.dumpToTextStream(out);
60 this->likelihoodOpts.dumpToTextStream(out);
81 :
COctoMapBase<octomap::ColorOcTree, octomap::ColorOcTreeNode>(resolution),
82 m_colour_method(INTEGRATE)
89 CColouredOctoMap::~CColouredOctoMap() {}
95 void CColouredOctoMap::writeToStream(
103 this->renderingOptions.writeToStream(out);
104 out << genericMapParams;
108 const_cast<octomap::ColorOcTree*
>(&m_octomap)->writeBinary(tmpFil);
129 if (version >= 1) this->renderingOptions.readFromStream(
in);
130 if (version >= 2)
in >> genericMapParams;
137 if (chunk.getTotalBytesCount())
140 if (!chunk.saveBufferToFile(tmpFil))
142 m_octomap.readBinary(tmpFil);
155 bool CColouredOctoMap::internal_insertObservation(
158 octomap::point3d sensorPt;
159 octomap::Pointcloud scan;
163 robotPose3D = (*robotPose);
180 octomap::point3d(sensorPose.
x(), sensorPose.
y(), sensorPose.z());
184 const size_t nPts = scanPts->
size();
190 for (
size_t i = 0; i < nPts; i++)
193 scanPts->getPointFast(i, pt.
x, pt.
y, pt.
z);
200 scan.push_back(gx, gy, gz);
204 m_octomap.insertPointCloud(
205 scan, sensorPt, insertionOptions.maxrange,
206 insertionOptions.pruning);
222 mrpt::make_aligned_shared<mrpt::opengl::CPointCloudColoured>();
225 proj_params.robotPoseInTheWorld = robotPose;
233 octomap::point3d(sensorPose.
x(), sensorPose.
y(), sensorPose.z());
235 const size_t sizeRangeScan = pts->size();
236 scan.reserve(sizeRangeScan);
238 for (
size_t i = 0; i < sizeRangeScan; i++)
244 if (pt.
x != 0 || pt.
y != 0 || pt.
z != 0)
245 scan.push_back(pt.
x, pt.
y, pt.
z);
249 octomap::KeySet free_cells, occupied_cells;
250 m_octomap.computeUpdate(
251 scan, sensorPt, free_cells, occupied_cells,
252 insertionOptions.maxrange);
256 it != free_cells.end(); ++it)
258 m_octomap.updateNode(*it,
false,
false);
261 it != occupied_cells.end(); ++it)
263 m_octomap.updateNode(*it,
true,
false);
267 const float colF2B = 255.0f;
268 for (
size_t i = 0; i < sizeRangeScan; i++)
274 if (pt.
x != 0 || pt.
y != 0 || pt.
z != 0)
275 this->updateVoxelColour(
281 if (insertionOptions.pruning) m_octomap.prune();
292 bool CColouredOctoMap::getPointColour(
296 octomap::OcTreeKey key;
297 if (m_octomap.coordToKeyChecked(octomap::point3d(
x,
y,
z), key))
299 octomap::ColorOcTreeNode* node = m_octomap.search(key, 0 );
300 if (!node)
return false;
302 const octomap::ColorOcTreeNode::Color& col = node->getColor();
313 void CColouredOctoMap::updateVoxelColour(
314 const double x,
const double y,
const double z,
const uint8_t r,
317 switch (m_colour_method)
320 m_octomap.integrateNodeColor(
x,
y,
z,
r,
g,
b);
323 m_octomap.setNodeColor(
x,
y,
z,
r,
g,
b);
326 m_octomap.averageNodeColor(
x,
y,
z,
r,
g,
b);
335 void CColouredOctoMap::getAsOctoMapVoxels(
341 octomap::ColorOcTree::tree_iterator it_end = m_octomap.end_tree();
343 const unsigned char max_depth = 0;
345 const TColor general_color_u(
346 general_color.
R * 255, general_color.
G * 255, general_color.
B * 255,
347 general_color.
A * 255);
358 const size_t nLeafs = this->getNumLeafNodes();
362 double xmin, xmax, ymin, ymax, zmin,
zmax;
363 this->getMetricMin(xmin, ymin, zmin);
364 this->getMetricMax(xmax, ymax,
zmax);
366 for (octomap::ColorOcTree::tree_iterator it =
367 m_octomap.begin_tree(max_depth);
370 const octomap::point3d vx_center = it.getCoordinate();
371 const double vx_length = it.getSize();
372 const double L = 0.5 * vx_length;
377 const double occ = it->getOccupancy();
378 if ((occ >= 0.5 && renderingOptions.generateOccupiedVoxels) ||
379 (occ < 0.5 && renderingOptions.generateFreeVoxels))
382 octomap::ColorOcTreeNode::Color node_color = it->getColor();
383 vx_color =
TColor(node_color.r, node_color.g, node_color.b);
385 const size_t vx_set = (m_octomap.isNodeOccupied(*it))
392 TPoint3D(vx_center.x(), vx_center.y(), vx_center.z()),
393 vx_length, vx_color));
396 else if (renderingOptions.generateGridLines)
400 vx_center.x() - L, vx_center.y() - L, vx_center.z() - L);
402 vx_center.x() + L, vx_center.y() + L, vx_center.z() + L);
415 this->getMetricMin(bbmin.
x, bbmin.
y, bbmin.
z);
416 this->getMetricMax(bbmax.
x, bbmax.
y, bbmax.
z);
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 POINTSMAP * buildAuxPointsMap(const void *options=nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call...
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
#define THROW_EXCEPTION(msg)
virtual void writeToStream(mrpt::utils::CStream &out, int *getVersion) const =0
Introduces a pure virtual method responsible for writing to a CStream.
#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.
void clear()
Clears everything.
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...
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)
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 getTempFileName()
Returns the name of a proposed temporary file name.
void readFromStream(mrpt::utils::CStream &in, int version) override
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
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 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.
double x
X,Y,Z coordinates.
A memory buffer (implements CStream) which can be itself serialized.
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)
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)
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixedNumeric< 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...
#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 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 ...
#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...
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
std::shared_ptr< CPointCloudColoured > Ptr
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
virtual void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory...
mrpt::utils::TColorf getColor() const
Returns the object color property as a TColorf.