Class KeyframePointCloudMap

Nested Relationships

Nested Types

Inheritance Relationships

Base Types

  • public mrpt::maps::CMetricMap

  • public mrpt::maps::NearestNeighborsCapable

  • public mp2p_icp::IcpPrepareCapable

  • public mp2p_icp::NearestPointWithCovCapable

  • public mp2p_icp::MetricMapMergeCapable

Class Documentation

class KeyframePointCloudMap : public mrpt::maps::CMetricMap, public mrpt::maps::NearestNeighborsCapable, public mp2p_icp::IcpPrepareCapable, public mp2p_icp::NearestPointWithCovCapable, public mp2p_icp::MetricMapMergeCapable

An efficient storage class for large point clouds built as keyframes, each having an associated local cloud.

The user of the class is responsible for processing raw observations into mrpt::obs::CObservationPointCloud observations, the only ones allowed as input to the insert*() methods, with points already transformed from the sensor frame to the vehicle (base_link) frame. This can be easily done with mp2p_icp::Generator, plus an optional filtering pipeline.

Each key-frame is responsible of keeping its own KD-tree for NN searches and keeping up-to-date covariances for each point local vicinity.

Basic API for construction and main parameters

using KeyFrameID = uint64_t

key-frame ID, index in the keyframes_ map.

KeyframePointCloudMap() = default

Constructor / default ctor.

~KeyframePointCloudMap()

Data access API

mrpt::math::TBoundingBoxf boundingBox() const override

Computes the bounding box of all the points, or (0,0 ,0,0, 0,0) if there are no points. Results are cached unless the map is somehow modified to avoid repeated calculations.

API of the NearestNeighborsCapable virtual interface

inline bool nn_has_indices_or_ids() const override
inline size_t nn_index_count() const override
bool nn_single_search(const mrpt::math::TPoint3Df &query, mrpt::math::TPoint3Df &result, float &out_dist_sqr, uint64_t &resultIndexOrID) const override
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

Public virtual methods implementation for IcpPrepareCapable

void icp_get_prepared_as_global(const mrpt::poses::CPose3D &icp_ref_point, const std::optional<mrpt::math::TBoundingBoxf> &local_map_roi = std::nullopt) const override

Prepare the map for ICP with a given point as reference.

void icp_cleanup() const override

Optionally, clean up after ICP is done.

Public virtual methods implementation for MetricMapMergeCapable

void merge_with(const MetricMapMergeCapable &source, const std::optional<mrpt::poses::CPose3D> &otherRelativePose = std::nullopt) override
void transform_map_left_multiply(const mrpt::poses::CPose3D &b) override

Public virtual methods implementation for NearestPointWithCovCapable

void nn_search_cov2cov(const NearestPointWithCovCapable &localMap, const mrpt::poses::CPose3D &localMapPose, const float max_search_distance, mp2p_icp::MatchedPointWithCovList &outPairings) const override
std::size_t point_count() const override

Public virtual methods implementation for CMetricMap

std::string asString() const override

Returns a short description of the map.

void getVisualizationInto(mrpt::opengl::CSetOfObjects &outObj) const override
bool isEmpty() const override

Returns true if the map is empty

void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override

This virtual method saves the map to a file “filNamePrefix”+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).

const mrpt::maps::CSimplePointsMap *getAsSimplePointsMap() const override

Returns a cached point cloud view of the entire map. Not efficient at all. Only for MOLA->ROS2 bridge.

Public Functions

KeyframePointCloudMap(const KeyframePointCloudMap&) = default
KeyframePointCloudMap &operator=(const KeyframePointCloudMap&) = default
KeyframePointCloudMap(KeyframePointCloudMap&&) = default
KeyframePointCloudMap &operator=(KeyframePointCloudMap&&) = default

Public Members

TInsertionOptions insertionOptions
TLikelihoodOptions likelihoodOptions
TRenderOptions renderOptions
TCreationOptions creationOptions
mola::KeyframePointCloudMap::TCreationOptions creationOptions
mola::KeyframePointCloudMap::TInsertionOptions insertionOpts
mola::KeyframePointCloudMap::TLikelihoodOptions likelihoodOpts
mola::KeyframePointCloudMap::TRenderOptions renderOpts

Protected Functions

void internal_clear() override
struct TCreationOptions : public mrpt::config::CLoadableOptions

Public Functions

TCreationOptions() = default
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
void dumpToTextStream(std::ostream &out) const override
void writeToStream(mrpt::serialization::CArchive &out) const
void readFromStream(mrpt::serialization::CArchive &in)

Public Members

uint32_t max_search_keyframes = 3

Maximum number of key-frames to search for NN.

uint32_t k_correspondences_for_cov = 20
struct TInsertionOptions : public mrpt::config::CLoadableOptions

Options for insertObservation()

Public Functions

TInsertionOptions() = default
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
void dumpToTextStream(std::ostream &out) const override
void writeToStream(mrpt::serialization::CArchive &out) const
void readFromStream(mrpt::serialization::CArchive &in)

Public Members

double remove_frames_farther_than = 0

If >0, remove old key-frames farther than this (meters)

struct TLikelihoodOptions : public mrpt::config::CLoadableOptions

Options used when evaluating “computeObservationLikelihood” in the derived classes.

See also

CObservation::computeObservationLikelihood

Public Functions

TLikelihoodOptions() = default
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
void dumpToTextStream(std::ostream &out) const override
void writeToStream(mrpt::serialization::CArchive &out) const
void readFromStream(mrpt::serialization::CArchive &in)
struct TRenderOptions : public mrpt::config::CLoadableOptions

Rendering options, used in getAs3DObject()

Public Functions

void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
void dumpToTextStream(std::ostream &out) const override
void writeToStream(mrpt::serialization::CArchive &out) const

Binary dump to stream - used in derived classes’ serialization

void readFromStream(mrpt::serialization::CArchive &in)

Binary dump to stream - used in derived classes’ serialization

Public Members

float point_size = 1.0f
mrpt::img::TColorf color = {.0f, .0f, 1.0f}

Color of points. Superseded by colormap if the latter is set.

mrpt::img::TColormap colormap = mrpt::img::cmHOT

Colormap for points (index is “z” coordinates)

uint8_t recolorizeByCoordinateIndex = 3

If colormap!=mrpt::img::cmNONE, use this coordinate as color index: 0=x 1=y 2=z 3=intensity