Program Listing for File NDT.h
↰ Return to documentation for file (include/mola_metric_maps/NDT.h
)
/* -------------------------------------------------------------------------
* A Modular Optimization framework for Localization and mApping (MOLA)
*
* Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
* Licensed under the GNU GPL v3 for non-commercial applications.
*
* This file is part of MOLA.
* MOLA is free software: you can redistribute it and/or modify it under the
* terms of the GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option) any later
* version.
*
* MOLA is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR
* A PARTICULAR PURPOSE. See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with
* MOLA. If not, see <https://www.gnu.org/licenses/>.
* ------------------------------------------------------------------------- */
#pragma once
#include <mola_metric_maps/index3d_t.h>
#include <mp2p_icp/NearestPlaneCapable.h>
#include <mp2p_icp/estimate_points_eigen.h> // PointCloudEigen
#include <mrpt/core/round.h>
#include <mrpt/img/TColor.h>
#include <mrpt/img/color_maps.h>
#include <mrpt/maps/CMetricMap.h>
#include <mrpt/maps/CSimplePointsMap.h>
#include <mrpt/maps/NearestNeighborsCapable.h>
#include <mrpt/math/TBoundingBox.h>
#include <mrpt/math/TPoint3D.h>
#include <tsl/robin_map.h>
#include <array>
#include <functional>
#include <optional>
//#define HASHED_VOXEL_POINT_CLOUD_WITH_CACHED_ACCESS
namespace mola
{
class NDT : public mrpt::maps::CMetricMap,
public mrpt::maps::NearestNeighborsCapable,
public mp2p_icp::NearestPlaneCapable
{
DEFINE_SERIALIZABLE(NDT, mola)
public:
using global_index3d_t = index3d_t<int32_t>;
constexpr static size_t MAX_POINTS_PER_VOXEL = 16;
constexpr static std::size_t GLOBAL_ID_SUBVOXEL_BITCOUNT = 5;
static_assert(MAX_POINTS_PER_VOXEL <= (1 << GLOBAL_ID_SUBVOXEL_BITCOUNT));
inline global_index3d_t coordToGlobalIdx(const mrpt::math::TPoint3Df& pt) const
{
return global_index3d_t(
static_cast<int32_t>(pt.x * voxel_size_inv_), //
static_cast<int32_t>(pt.y * voxel_size_inv_), //
static_cast<int32_t>(pt.z * voxel_size_inv_));
}
inline mrpt::math::TPoint3Df globalIdxToCoord(const global_index3d_t idx) const
{
return {
idx.cx * voxel_size_, //
idx.cy * voxel_size_, //
idx.cz * voxel_size_};
}
using global_plain_index_t = uint64_t;
static inline global_plain_index_t g2plain(const global_index3d_t& g, int subVoxelIndex = 0)
{
constexpr uint64_t SUBVOXEL_MASK = ((1 << GLOBAL_ID_SUBVOXEL_BITCOUNT) - 1);
constexpr auto OFF = GLOBAL_ID_SUBVOXEL_BITCOUNT;
constexpr int FBITS = 20; // (64 - OFF)/3, rounded if needed
constexpr uint64_t FMASK = (1 << FBITS) - 1;
return (static_cast<uint64_t>(subVoxelIndex) & SUBVOXEL_MASK) |
(static_cast<uint64_t>(g.cx & FMASK) << (OFF + FBITS * 0)) |
(static_cast<uint64_t>(g.cy & FMASK) << (OFF + FBITS * 1)) |
(static_cast<uint64_t>(g.cz & FMASK) << (OFF + FBITS * 2));
}
NDT(float voxel_size = 5.00f);
~NDT();
void setVoxelProperties(float voxel_size);
struct point_vector_t
{
std::array<float, MAX_POINTS_PER_VOXEL> xs, ys, zs;
};
bool ndt_is_plane(const mp2p_icp::PointCloudEigen& ndt) const;
struct VoxelData
{
public:
VoxelData() = default;
struct PointSpan
{
PointSpan(const point_vector_t& points, uint32_t n) : points_(points), n_(n) {}
size_t size() const { return n_; }
bool empty() const { return n_ == 0; }
mrpt::math::TPoint3Df operator[](int i) const
{
return {points_.xs[i], points_.ys[i], points_.zs[i]};
}
private:
const point_vector_t& points_;
const uint32_t n_;
};
auto points() const -> PointSpan { return PointSpan(points_, nPoints_); }
void insertPoint(const mrpt::math::TPoint3Df& p, const mrpt::math::TPoint3Df& sensorPose)
{
if (nPoints_ < MAX_POINTS_PER_VOXEL)
{
points_.xs[nPoints_] = p.x;
points_.ys[nPoints_] = p.y;
points_.zs[nPoints_] = p.z;
nPoints_++;
ndt_.reset();
}
was_seen_from_ = sensorPose;
}
const std::optional<mp2p_icp::PointCloudEigen>& ndt() const;
bool has_ndt() const { return ndt_.has_value(); }
// for serialization, do not use in normal use:
size_t size() const { return nPoints_; }
const auto& was_seen_from() const { return was_seen_from_; }
private:
mutable std::optional<mp2p_icp::PointCloudEigen> ndt_;
point_vector_t points_;
std::optional<mrpt::math::TPoint3Df> was_seen_from_;
uint32_t nPoints_ = 0;
};
using grids_map_t = tsl::robin_map<global_index3d_t, VoxelData, index3d_hash<int32_t>>;
// clear(): available in base class
inline VoxelData* voxelByGlobalIdxs(const global_index3d_t& idx, bool createIfNew)
{
// 1) Insert into decimation voxel map:
VoxelData* voxel = nullptr;
#if defined(HASHED_VOXEL_POINT_CLOUD_WITH_CACHED_ACCESS)
for (int i = 0; i < CachedData::NUM_CACHED_IDXS; i++)
{
if (cached_.lastAccessVoxel[i] && cached_.lastAccessIdx[i] == idx)
{
// Cache hit:
#ifdef USE_DEBUG_PROFILER
mrpt::system::CTimeLoggerEntry tle(profiler, "insertPoint.cache_hit");
#endif
voxel = cached_.lastAccessVoxel[i];
break;
}
}
if (!voxel)
{
#endif
#ifdef USE_DEBUG_PROFILER
mrpt::system::CTimeLoggerEntry tle(profiler, "insertPoint.cache_misss");
#endif
auto it = voxels_.find(idx);
if (it == voxels_.end())
{
if (!createIfNew)
return nullptr;
else
voxel = &voxels_[idx]; // Create it
}
else
{
// Use the found grid
voxel = &it.value();
}
#if defined(HASHED_VOXEL_POINT_CLOUD_WITH_CACHED_ACCESS)
// Add to cache:
cached_.lastAccessIdx[cached_.lastAccessNextWrite] = idx;
cached_.lastAccessVoxel[cached_.lastAccessNextWrite] = voxel;
cached_.lastAccessNextWrite++;
cached_.lastAccessNextWrite &= CachedData::NUM_CACHED_IDX_MASK;
}
#endif
return voxel;
}
const VoxelData* voxelByGlobalIdxs(const global_index3d_t& idx //
/*, bool createIfNew this must be false for const! */) const
{ // reuse the non-const method:
return const_cast<NDT*>(this)->voxelByGlobalIdxs(idx, false);
}
VoxelData* voxelByCoords(const mrpt::math::TPoint3Df& pt, bool createIfNew)
{
return voxelByGlobalIdxs(coordToGlobalIdx(pt), createIfNew);
}
const VoxelData* voxelByCoords(const mrpt::math::TPoint3Df& pt) const
{
return const_cast<NDT*>(this)->voxelByCoords(pt, false);
}
void insertPoint(const mrpt::math::TPoint3Df& pt, const mrpt::math::TPoint3Df& sensorPose);
const grids_map_t& voxels() const { return voxels_; }
mrpt::math::TBoundingBoxf boundingBox() const override;
void visitAllPoints(const std::function<void(const mrpt::math::TPoint3Df&)>& f) const;
void visitAllVoxels(
const std::function<void(const global_index3d_t&, const VoxelData&)>& f) const;
bool saveToTextFile(const std::string& file) const;
[[nodiscard]] bool nn_has_indices_or_ids() const override;
[[nodiscard]] size_t nn_index_count() const override;
[[nodiscard]] bool nn_single_search(
const mrpt::math::TPoint3Df& query, mrpt::math::TPoint3Df& result, float& out_dist_sqr,
uint64_t& resultIndexOrID) const override;
[[nodiscard]] bool nn_single_search(
const mrpt::math::TPoint2Df& query, mrpt::math::TPoint2Df& result, float& out_dist_sqr,
uint64_t& resultIndexOrID) const override;
void nn_multiple_search(
const mrpt::math::TPoint3Df& query, const size_t N,
std::vector<mrpt::math::TPoint3Df>& results, std::vector<float>& out_dists_sqr,
std::vector<uint64_t>& resultIndicesOrIDs) const override;
void nn_multiple_search(
const mrpt::math::TPoint2Df& query, const size_t N,
std::vector<mrpt::math::TPoint2Df>& results, std::vector<float>& out_dists_sqr,
std::vector<uint64_t>& resultIndicesOrIDs) const override;
void nn_radius_search(
const mrpt::math::TPoint3Df& query, const float search_radius_sqr,
std::vector<mrpt::math::TPoint3Df>& results, std::vector<float>& out_dists_sqr,
std::vector<uint64_t>& resultIndicesOrIDs, size_t maxPoints) const override;
void nn_radius_search(
const mrpt::math::TPoint2Df& query, const float search_radius_sqr,
std::vector<mrpt::math::TPoint2Df>& results, std::vector<float>& out_dists_sqr,
std::vector<uint64_t>& resultIndicesOrIDs, size_t maxPoints) const override;
template <size_t MAX_KNN>
void nn_multiple_search_impl(
const mrpt::math::TPoint3Df& query, const size_t N,
std::vector<mrpt::math::TPoint3Df>& results, std::vector<float>& out_dists_sqr,
std::vector<uint64_t>& resultIndicesOrIDs) const;
NearestPlaneResult nn_search_pt2pl(
const mrpt::math::TPoint3Df& point, const float max_search_distance) const override;
std::string asString() const override;
void getVisualizationInto(mrpt::opengl::CSetOfObjects& outObj) const override;
bool isEmpty() const override;
void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const override;
const mrpt::maps::CSimplePointsMap* getAsSimplePointsMap() const override;
struct TInsertionOptions : public mrpt::config::CLoadableOptions
{
TInsertionOptions() = default;
void loadFromConfigFile(
const mrpt::config::CConfigFileBase& source,
const std::string& section) override; // See base docs
void dumpToTextStream(std::ostream& out) const override; // See base docs
void writeToStream(mrpt::serialization::CArchive& out) const;
void readFromStream(mrpt::serialization::CArchive& in);
uint32_t max_points_per_voxel = 0;
double remove_voxels_farther_than = .0;
float min_distance_between_points = .0f;
double max_eigen_ratio_for_planes = 0.01;
};
TInsertionOptions insertionOptions;
struct TLikelihoodOptions : public mrpt::config::CLoadableOptions
{
TLikelihoodOptions() = default;
void loadFromConfigFile(
const mrpt::config::CConfigFileBase& source,
const std::string& section) override; // See base docs
void dumpToTextStream(std::ostream& out) const override; // See base docs
void writeToStream(mrpt::serialization::CArchive& out) const;
void readFromStream(mrpt::serialization::CArchive& in);
double sigma_dist = 0.5;
double max_corr_distance = 1.0;
uint32_t decimation = 10;
};
TLikelihoodOptions likelihoodOptions;
struct TRenderOptions : public mrpt::config::CLoadableOptions
{
void loadFromConfigFile(
const mrpt::config::CConfigFileBase& source,
const std::string& section) override; // See base docs
void dumpToTextStream(std::ostream& out) const override; // See base docs
void writeToStream(mrpt::serialization::CArchive& out) const;
void readFromStream(mrpt::serialization::CArchive& in);
bool points_visible = false;
float point_size = 1.0f;
mrpt::img::TColorf points_color{.0f, .0f, 1.0f};
bool planes_visible = true;
mrpt::img::TColorf planes_color{1.0f, .0f, 1.0f};
bool normals_visible = true;
mrpt::img::TColorf normals_color{1.0f, 0.0f, 0.0f};
mrpt::img::TColormap points_colormap = mrpt::img::cmHOT;
mrpt::img::TColormap planes_colormap = mrpt::img::cmHOT;
uint8_t recolorizeByCoordinateIndex = 2;
};
TRenderOptions renderOptions;
public:
// Interface for use within a mrpt::maps::CMultiMetricMap:
MAP_DEFINITION_START(NDT)
float voxel_size = 1.00f;
mola::NDT::TInsertionOptions insertionOpts;
mola::NDT::TLikelihoodOptions likelihoodOpts;
mola::NDT::TRenderOptions renderOpts;
MAP_DEFINITION_END(NDT)
private:
float voxel_size_ = 1.00f;
// Calculated from the above, in setVoxelProperties()
float voxel_size_inv_ = 1.0f / voxel_size_;
float voxel_size_sqr_ = voxel_size_ * voxel_size_;
mrpt::math::TPoint3Df voxelDiagonal_;
grids_map_t voxels_;
struct CachedData
{
CachedData() = default;
void reset() { *this = CachedData(); }
mutable std::optional<mrpt::math::TBoundingBoxf> boundingBox_;
#if defined(HASHED_VOXEL_POINT_CLOUD_WITH_CACHED_ACCESS)
// 2 bits seems to be the optimum for typical cases:
constexpr static int CBITS = 2;
constexpr static int NUM_CACHED_IDXS = 1 << CBITS;
constexpr static int NUM_CACHED_IDX_MASK = NUM_CACHED_IDXS - 1;
int lastAccessNextWrite = 0;
global_index3d_t lastAccessIdx[NUM_CACHED_IDXS];
VoxelData* lastAccessVoxel[NUM_CACHED_IDXS] = {nullptr};
#endif
};
CachedData cached_;
protected:
// See docs in base CMetricMap class:
void internal_clear() override;
private:
// See docs in base CMetricMap class:
bool internal_insertObservation(
const mrpt::obs::CObservation& obs,
const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt) override;
// See docs in base class
double internal_computeObservationLikelihood(
const mrpt::obs::CObservation& obs, const mrpt::poses::CPose3D& takenFrom) const override;
double internal_computeObservationLikelihoodPointCloud3D(
const mrpt::poses::CPose3D& pc_in_map, const float* xs, const float* ys, const float* zs,
const std::size_t num_pts) const;
void internal_insertPointCloud3D(
const mrpt::poses::CPose3D& pc_in_map, const float* xs, const float* ys, const float* zs,
const std::size_t num_pts);
// See docs in base class
bool internal_canComputeObservationLikelihood(const mrpt::obs::CObservation& obs) const override;
mutable mrpt::maps::CSimplePointsMap::Ptr cachedPoints_;
};
} // namespace mola