Class CPointsMap

Nested Relationships

Nested Types

Inheritance Relationships

Base Types

  • public mrpt::maps::CMetricMap

  • public mrpt::math::KDTreeCapable< CPointsMap >

  • public mrpt::viz::PLY_Importer

  • public mrpt::viz::PLY_Exporter

  • public mrpt::maps::NearestNeighborsCapable (Class NearestNeighborsCapable)

Derived Types

Class Documentation

class CPointsMap : public mrpt::maps::CMetricMap, public mrpt::math::KDTreeCapable<CPointsMap>, public mrpt::viz::PLY_Importer, public mrpt::viz::PLY_Exporter, public mrpt::maps::NearestNeighborsCapable

A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors. This is a virtual class, thus only a derived class can be instantiated by the user. The user most usually wants to use CSimplePointsMap.

This class implements generic version of mrpt::maps::CMetric::insertObservation() accepting these types of sensory data:

  • mrpt::obs::CObservation2DRangeScan: 2D range scans

  • mrpt::obs::CObservation3DRangeScan: 3D range scans (Kinect, etc…)

  • mrpt::obs::CObservationRange: IRs, Sonars, etc.

  • mrpt::obs::CObservationVelodyneScan

  • mrpt::obs::CObservationPointCloud

Loading and saving in the standard LAS LiDAR point cloud format is supported by installing libLAS and including the header <mrpt/maps/CPointsMaps_liblas.h> in your program. Since MRPT 1.5.0 there is no need to build MRPT against libLAS to use this feature. See LAS functions in mrpt_maps_liblas_grp.

See also

CMetricMap, CPoint, CSerializable

Subclassed by mrpt::maps::CGenericPointsMap, mrpt::maps::CSimplePointsMap

Register/unregister custom data fields

static constexpr const char *POINT_FIELD_INTENSITY = "intensity"
static constexpr const char *POINT_FIELD_RING_ID = "ring"
static constexpr const char *POINT_FIELD_TIMESTAMP = "t"
static constexpr const char *POINT_FIELD_COLOR_Ru8 = "color_r"

uint8_t RGB.r

static constexpr const char *POINT_FIELD_COLOR_Gu8 = "color_g"

uint8_t RGB.g

static constexpr const char *POINT_FIELD_COLOR_Bu8 = "color_b"

uint8_t RGB.b

static constexpr const char *POINT_FIELD_COLOR_Rf = "color_rf"

float RGB.r

static constexpr const char *POINT_FIELD_COLOR_Gf = "color_gf"

float RGB.g

static constexpr const char *POINT_FIELD_COLOR_Bf = "color_bf"

float RGB.b

inline virtual bool registerField_float(const std::string &fieldName)

Registers a new data channel of type float. If the map is not empty, the new channel is filled with default values (0) to match the current point count.

Returns:

true if the field could effectively be added to the underlying point map class.

inline virtual bool registerField_uint16([[maybe_unused]] const std::string &fieldName)

Registers a new data channel of type uint16_t. If the map is not empty, the new channel is filled with default values (0) to match the current point count.

Returns:

true if the field could effectively be added to the underlying point map class.

inline virtual bool registerField_uint8([[maybe_unused]] const std::string &fieldName)

Registers a new data channel of type uint8_t. If the map is not empty, the new channel is filled with default values (0) to match the current point count.

Returns:

true if the field could effectively be added to the underlying point map class.

inline virtual bool registerField_double([[maybe_unused]] const std::string &fieldName)

Registers a new data channel of type double. If the map is not empty, the new channel is filled with default values (0) to match the current point count.

Returns:

true if the field could effectively be added to the underlying point map class.

Pure virtual interfaces to be implemented by any class derived

from CPointsMap

virtual void reserve(size_t newLength) = 0

Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory. This is useful for situations where it is approximately known the final size of the map. This method is more efficient than constantly increasing the size of the buffers. Refer to the STL C++ library’s “reserve” methods.

virtual void resize(size_t newLength) = 0

Resizes all point buffers so they can hold the given number of points: newly created points are set to default values, and old contents are not changed.

virtual void setSize(size_t newLength) = 0

Resizes all point buffers so they can hold the given number of points, erasing all previous contents and leaving all points to default values.

inline void setPointFast(size_t index, float x, float y, float z)

Changes the coordinates of the given point (0-based index), without checking for out-of-bounds and without calling mark_as_modified(). Also, color, intensity, or other data is left unchanged.

See also

setPoint

inline void insertPointFast(float x, float y, float z)

Low-level method for insertPoint() without calling mark_as_modified(). Note that for derived classes having more per-point fields, you must ensure adding those fields after this to keep the length of all vectors consistent.

virtual void getPointAllFieldsFast(size_t index, std::vector<float> &point_data) const = 0

Get all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc… Unlike getPointAllFields(), this method does not check for index out of bounds

virtual void setPointAllFieldsFast(size_t index, const std::vector<float> &point_data) = 0

Set all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc… Unlike setPointAllFields(), this method does not check for index out of bounds

bool loadFromKittiVelodyneFile(const std::string &filename)

Loads from a Kitti dataset Velodyne scan binary file with an XYZI point cloud. The file can be gz compressed (only enabled if the filename ends in “.gz” to prevent spurious false autodetection of gzip files).

Returns:

true on success

bool saveToKittiVelodyneFile(const std::string &filename) const

Saves in a binary file compatible with the Kitti dataset, including XYZI fields.

Returns:

true on success

inline virtual void impl_copyFrom(const CPointsMap &obj) final

Virtual assignment operator, copies as much common data (XYZ, color,…) as possible from the source map into this one.

File input/output methods

inline bool load2D_from_text_file(const std::string &file)

Load from a text file. Each line should contain an “X Y” coordinate pair, separated by whitespaces. Returns false if any error occurred, true elsewere.

inline bool load2D_from_text_stream(std::istream &in, mrpt::optional_ref<std::string> outErrorMsg = std::nullopt)
inline bool load3D_from_text_file(const std::string &file)

Load from a text file. Each line should contain an “X Y Z” coordinate tuple, separated by whitespaces. Returns false if any error occurred, true elsewere.

inline bool load3D_from_text_stream(std::istream &in, mrpt::optional_ref<std::string> outErrorMsg = std::nullopt)
bool load2Dor3D_from_text_file(const std::string &file, bool is_3D)

2D or 3D generic implementation of load2D_from_text_file and load3D_from_text_file

bool load2Dor3D_from_text_stream(std::istream &in, mrpt::optional_ref<std::string> outErrorMsg, bool is_3D)
bool save2D_to_text_file(const std::string &file) const

Save to a text file. Each line will contain “X Y” point coordinates. Returns false if any error occurred, true elsewere.

bool save2D_to_text_stream(std::ostream &out) const
bool save3D_to_text_file(const std::string &file) const

Save to a text file. Each line will contain “X Y Z” point coordinates. Returns false if any error occurred, true elsewere.

bool save3D_to_text_stream(std::ostream &out) const
inline 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)

Generic, string-keyed field access virtual interface

inline virtual bool hasPointField(const std::string &fieldName) const

Returns true if the map has a data channel with the given name.

inline virtual std::vector<std::string> getPointFieldNames_float() const

Get list of all float channel names

inline virtual std::vector<std::string> getPointFieldNames_double() const

Get list of all double channel names

inline virtual std::vector<std::string> getPointFieldNames_uint16() const

Get list of all uint16_t channel names

inline virtual std::vector<std::string> getPointFieldNames_uint8() const

Get list of all uint8_t channel names

std::vector<std::string> getPointFieldNames_float_except_xyz() const

Get list of all float channel names, except x,y,z

inline virtual float getPointField_float(size_t index, const std::string &fieldName) const

Read the value of a float channel for a given point. Returns 0 if field does not exist.

Throws:

std::exception – on index out of bounds or if field exists but is not float.

inline virtual double getPointField_double([[maybe_unused]] size_t index, [[maybe_unused]] const std::string &fieldName) const

Read the value of a double channel for a given point. Returns 0 if field does not exist.

Throws:

std::exception – on index out of bounds or if field exists but is not double.

inline virtual uint16_t getPointField_uint16([[maybe_unused]] size_t index, [[maybe_unused]] const std::string &fieldName) const

Read the value of a uint16_t channel for a given point. Returns 0 if field does not exist.

Throws:

std::exception – on index out of bounds or if field exists but is not uint16_t.

inline virtual uint8_t getPointField_uint8([[maybe_unused]] size_t index, [[maybe_unused]] const std::string &fieldName) const

Read the value of a uint8_t channel for a given point. Returns 0 if field does not exist.

Throws:

std::exception – on index out of bounds or if field exists but is not uint16_t.

inline virtual void setPointField_float(size_t index, const std::string &fieldName, float value)

Sets the value of a float channel for a given point.

Throws:

std::exception – on index out of bounds or if field does not exist or is not float.

inline virtual void setPointField_double([[maybe_unused]] size_t index, [[maybe_unused]] const std::string &fieldName, [[maybe_unused]] double value)

Sets the value of a double channel for a given point.

Throws:

std::exception – on index out of bounds or if field does not exist or is not double.

inline virtual void setPointField_uint16([[maybe_unused]] size_t index, [[maybe_unused]] const std::string &fieldName, [[maybe_unused]] uint16_t value)

Sets the value of a uint16_t channel for a given point.

Throws:

std::exception – on index out of bounds or if field does not exist or is not uint16_t.

inline virtual void setPointField_uint8([[maybe_unused]] size_t index, [[maybe_unused]] const std::string &fieldName, [[maybe_unused]] uint8_t value)

Sets the value of a uint8_t channel for a given point.

Throws:

std::exception – on index out of bounds or if field does not exist or is not uint8_t.

inline virtual void insertPointField_float([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] float value)

Appends a value to a float channel (for use after insertPointFast())

inline virtual void insertPointField_double([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] double value)

Appends a value to a double channel (for use after insertPointFast())

inline virtual void insertPointField_uint16([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] uint16_t value)

Appends a value to a uint16_t channel (for use after insertPointFast())

inline virtual void insertPointField_uint8([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] uint8_t value)

Appends a value to a uint8_t channel (for use after insertPointFast())

inline virtual void reserveField_float([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] size_t n)
inline virtual void reserveField_double([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] size_t n)
inline virtual void reserveField_uint16([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] size_t n)
inline virtual void reserveField_uint8([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] size_t n)
inline virtual void resizeField_float([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] size_t n)
inline virtual void resizeField_double([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] size_t n)
inline virtual void resizeField_uint16([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] size_t n)
inline virtual void resizeField_uint8([[maybe_unused]] const std::string &fieldName, [[maybe_unused]] size_t n)
inline virtual auto getPointsBufferRef_float_field(const std::string &fieldName) const -> const mrpt::aligned_std_vector<float>*
inline virtual auto getPointsBufferRef_double_field([[maybe_unused]] const std::string &fieldName) const -> const mrpt::aligned_std_vector<double>*
inline virtual auto getPointsBufferRef_uint16_field([[maybe_unused]] const std::string &fieldName) const -> const mrpt::aligned_std_vector<uint16_t>*
inline virtual auto getPointsBufferRef_uint8_field([[maybe_unused]] const std::string &fieldName) const -> const mrpt::aligned_std_vector<uint8_t>*
inline virtual auto getPointsBufferRef_float_field(const std::string &fieldName) -> mrpt::aligned_std_vector<float>*
inline virtual auto getPointsBufferRef_double_field([[maybe_unused]] const std::string &fieldName) -> mrpt::aligned_std_vector<double>*
inline virtual auto getPointsBufferRef_uint16_field([[maybe_unused]] const std::string &fieldName) -> mrpt::aligned_std_vector<uint16_t>*
inline virtual auto getPointsBufferRef_uint8_field([[maybe_unused]] const std::string &fieldName) -> mrpt::aligned_std_vector<uint8_t>*

Filter-by-height stuff

inline void enableFilterByHeight(bool enable = true)

Enable/disable the filter-by-height functionality

Note

Default upon construction is disabled.

inline bool isFilterByHeightEnabled() const

Return whether filter-by-height is enabled

inline void setHeightFilterLevels(const double _z_min, const double _z_max)

Set the min/max Z levels for points to be actually inserted in the map (only if enableFilterByHeight() was called before).

inline void getHeightFilterLevels(double &_z_min, double &_z_max) const

Get the min/max Z levels for points to be actually inserted in the map

PCL library support

template<class POINTCLOUD>
inline void getPCLPointCloud(POINTCLOUD &cloud) const

Use to convert this MRPT point cloud object into a PCL point cloud object (PointCloud<PointXYZ>). Usage example:

mrpt::maps::CPointsCloud       pc;
pcl::PointCloud<pcl::PointXYZ> cloud;

pc.getPCLPointCloud(cloud);

See also

setFromPCLPointCloud, CColouredPointsMap::getPCLPointCloudXYZRGB (for color data)

template<class POINTCLOUD>
inline void setFromPCLPointCloud(const POINTCLOUD &cloud)

Loads a PCL point cloud into this MRPT class (note: this method ignores potential RGB information, see CColouredPointsMap::setFromPCLPointCloudRGB() ). Usage example:

pcl::PointCloud<pcl::PointXYZ> cloud;
mrpt::maps::CPointsCloud       pc;

pc.setFromPCLPointCloud(cloud);

See also

getPCLPointCloud, CColouredPointsMap::setFromPCLPointCloudRGB()

Methods that MUST be implemented by children classes of

KDTreeCapable

inline size_t kdtree_get_point_count() const

Must return the number of data points.

inline float kdtree_get_pt(size_t idx, int dim) const

Returns the dim’th component of the idx’th point in the class:

inline float kdtree_distance(const float *p1, size_t idx_p2, size_t size) const

Returns the distance between the vector “p1[0:size-1]” and the data point with index “idx_p2” stored in the class:

template<typename BBOX>
inline bool kdtree_get_bbox(BBOX &bb) const

API of the NearestNeighborsCapable virtual interface

virtual void nn_prepare_for_2d_queries() const override

Must be called before calls to nn_*_search() to ensure the required data structures are ready for queries (e.g. KD-trees). Useful in multithreading applications.

virtual void nn_prepare_for_3d_queries() const override

Must be called before calls to nn_*_search() to ensure the required data structures are ready for queries (e.g. KD-trees). Useful in multithreading applications.

inline virtual bool nn_has_indices_or_ids() const override

Returns true if the rest of nn_* methods will populate the output indices values with 0-based contiguous indices. Returns false if indices are actually sparse ID numbers without any expectation of they be contiguous or start near zero.

inline virtual size_t nn_index_count() const override

If nn_has_indices_or_ids() returns true, this must return the number of “points” (or whatever entity) the indices correspond to. Otherwise, the return value should be ignored.

virtual bool nn_single_search(const mrpt::math::TPoint3Df &query, mrpt::math::TPoint3Df &result, float &out_dist_sqr, uint64_t &resultIndexOrID) const override

Search for the closest 3D point to a given one.

Parameters:
  • query[in] The query input point.

  • result[out] The found closest point.

  • out_dist_sqr[out] The square Euclidean distance between the query and the returned point.

  • resultIndexOrID[out] The index or ID of the result point in the map.

Returns:

True if successful, false if no point was found.

virtual bool nn_single_search(const mrpt::math::TPoint2Df &query, mrpt::math::TPoint2Df &result, float &out_dist_sqr, uint64_t &resultIndexOrID) const override
virtual void nn_multiple_search(const mrpt::math::TPoint3Df &query, size_t N, std::vector<mrpt::math::TPoint3Df> &results, std::vector<float> &out_dists_sqr, std::vector<uint64_t> &resultIndicesOrIDs) const override

Search for the N closest 3D points to a given one.

Parameters:
  • query[in] The query input point.

  • results[out] The found closest points.

  • out_dists_sqr[out] The square Euclidean distances between the query and the returned point.

  • resultIndicesOrIDs[out] The indices or IDs of the result points.

virtual void nn_multiple_search(const mrpt::math::TPoint2Df &query, size_t N, std::vector<mrpt::math::TPoint2Df> &results, std::vector<float> &out_dists_sqr, std::vector<uint64_t> &resultIndicesOrIDs) const override
virtual void nn_radius_search(const mrpt::math::TPoint3Df &query, 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

Radius search for closest 3D points to a given one.

Parameters:
  • query[in] The query input point.

  • search_radius_sqr[in] The search radius, squared.

  • results[out] The found closest points.

  • out_dists_sqr[out] The square Euclidean distances between the query and the returned point.

  • resultIndicesOrIDs[out] The indices or IDs of the result points.

  • maxPoints[in] If !=0, the maximum number of neigbors to return.

virtual void nn_radius_search(const mrpt::math::TPoint2Df &query, 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

PLY Import virtual methods to implement in base classes

inline void PLY_import_set_face_count([[maybe_unused]] size_t N) override

In a base class, reserve memory to prepare subsequent calls to PLY_import_set_face

virtual void PLY_import_set_vertex(size_t idx, const mrpt::math::TPoint3Df &pt, const mrpt::img::TColorf *pt_color = nullptr) override

In a base class, will be called after PLY_import_set_vertex_count() once for each loaded point.

Parameters:

pt_color – Will be nullptr if the loaded file does not provide color info.

inline void PLY_import_set_vertex_timestamp([[maybe_unused]] size_t idx, [[maybe_unused]] const double unixTimestamp) override

PLY Export virtual methods to implement in base classes

virtual size_t PLY_export_get_vertex_count() const override
inline virtual size_t PLY_export_get_face_count() const override
virtual void PLY_export_get_vertex(size_t idx, mrpt::math::TPoint3Df &pt, bool &pt_has_color, mrpt::img::TColorf &pt_color) const override

Public Functions

CPointsMap()

Ctor

~CPointsMap() = default
inline CPointsMap &operator=(const CPointsMap &o)
CPointsMap(const CPointsMap &o) = delete

Don’t define this one as we cannot call the virtual method impl_copyFrom() during copy ctors. Redefine in derived classes as needed instead.

CPointsMap(CPointsMap &&o) = delete
CPointsMap &operator=(CPointsMap &&o) = delete
float squareDistanceToClosestCorrespondence(float x0, float y0) const override

Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.

inline float squareDistanceToClosestCorrespondenceT(const mrpt::math::TPoint2D &p0) const
void insertAnotherMap(const CPointsMap *otherMap, const mrpt::poses::CPose3D &otherPose, bool filterOutPointsAtZero = false, bool autoRegisterAllSourceFields = true)

Insert the contents of another map into this one with some geometric transformation, without fusing close points.

See also

fuseWith, addFrom

Parameters:
  • otherMap – The other map whose points are to be inserted into this one.

  • otherPose – The pose of the other map in the coordinates of THIS map

  • filterOutPointsAtZero – If true, points at (0,0,0) (in the frame of reference of otherMap) will be assumed to be invalid and will not be copied.

  • autoRegisterAllSourceFields – If true (default) all source map fields will be registered and copied. If false, only those fields already existing in the target (this) map will be copied.

inline void operator+=(const CPointsMap &anotherMap)

Inserts another map into this one.

inline size_t size() const

Save the point cloud as a PCL PCD file, in either ASCII or binary format

Note

This method requires user code to include PCL before MRPT headers.

Note

This method requires user code to include PCL before MRPT headers.

Returns:

false on any error Load the point cloud from a PCL PCD file.

Returns:

false on any error Returns the number of stored points in the map.

void getPoint(size_t index, float &x, float &y, float &z) const

Access to a given point from map, as a 2D point. First index is 0.

Throws:

Throws – std::exception on index out of bound.

void getPoint(size_t index, float &x, float &y) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

void getPoint(size_t index, double &x, double &y, double &z) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

void getPoint(size_t index, double &x, double &y) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void getPoint(size_t index, mrpt::math::TPoint2D &p) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void getPoint(size_t index, mrpt::math::TPoint3D &p) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void getPoint(size_t index, mrpt::math::TPoint3Df &p) const
inline void getPointFast(size_t index, float &x, float &y, float &z) const

Just like getPoint() but without checking out-of-bound index and without returning the point weight, just XYZ.

bool hasColor_u8() const

Returns true if the point map has a color field for each point (uint8_t), named “color_{r,g,b}”

bool hasColor_f() const

Returns true if the point map has a color field for each point (float), named “color_{rf,gf,bf}”

inline void setPoint(size_t index, float x, float y, float z)

Changes a given point from map, with Z defaulting to 0 if not provided.

Throws:

Throws – std::exception on index out of bound.

inline void setPoint(size_t index, const mrpt::math::TPoint2D &p)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void setPoint(size_t index, const mrpt::math::TPoint3D &p)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void setPoint(size_t index, float x, float y)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline const mrpt::aligned_std_vector<float> &getPointsBufferRef_x() const

Provides a direct access to a read-only reference of the internal point buffer.

See also

getAllPoints

inline const mrpt::aligned_std_vector<float> &getPointsBufferRef_y() const

Provides a direct access to a read-only reference of the internal point buffer.

See also

getAllPoints

inline const mrpt::aligned_std_vector<float> &getPointsBufferRef_z() const

Provides a direct access to a read-only reference of the internal point buffer.

See also

getAllPoints

template<class VECTOR>
inline void getAllPoints(VECTOR &xs, VECTOR &ys, VECTOR &zs, size_t decimation = 1) const

Returns a copy of the 2D/3D points as a std::vector of float coordinates. If decimation is greater than 1, only 1 point out of that number will be saved in the output, effectively performing a subsampling of the points.

Template Parameters:

VECTOR – can be std::vector<float or double> or any row/column Eigen::Array or Eigen::Matrix (this includes mrpt::math::CVectorFloat and mrpt::math::CVectorDouble).

void getAllPoints(std::vector<float> &xs, std::vector<float> &ys, size_t decimation = 1) const

Returns a copy of the 2D/3D points as a std::vector of float coordinates. If decimation is greater than 1, only 1 point out of that number will be saved in the output, effectively performing a subsampling of the points.

See also

setAllPoints

inline void getAllPoints(std::vector<mrpt::math::TPoint2D> &ps, size_t decimation = 1) const
inline void insertPoint(float x, float y, float z = 0)

Provides a way to insert (append) individual points into the map: the missing fields of child classes (color, weight, etc) are left to their default values

inline void insertPoint(const mrpt::math::TPoint3D &p)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline bool registerPointFieldsFrom(const mrpt::maps::CPointsMap &source)

Must be called before insertPointFrom() to make sure we have the required fields.

Returns:

true if ALL fields could be added, false if some would be missing because the underlying point cloud class cannot hold them.

InsertCtx prepareForInsertPointsFrom(const CPointsMap &source)

Prepare efficient data structures for repeated insertion from another point map with insertPointFrom()

inline void insertPointFrom(size_t sourcePointIndex, const InsertCtx &ctx)

Generic method to copy all applicable point properties from one map to another, e.g. timestamp, intensity, etc.

Note

Before calling this in a loop, make sure of calling registerPointFieldsFrom()

template<typename VECTOR>
inline void setAllPointsTemplate(const VECTOR &X, const VECTOR &Y, const VECTOR &Z = VECTOR())

Set all the points at once from vectors with X,Y and Z coordinates (if Z is not provided, it will be set to all zeros).

Template Parameters:

VECTOR – can be mrpt::math::CVectorFloat or std::vector<float> or any other column or row Eigen::Matrix.

void setAllPoints(const std::vector<float> &X, const std::vector<float> &Y, const std::vector<float> &Z)

Set all the points at once from vectors with X,Y and Z coordinates.

See also

getAllPoints

void setAllPoints(const std::vector<float> &X, const std::vector<float> &Y)

Set all the points at once from vectors with X and Y coordinates (Z=0).

See also

getAllPoints

inline void getPointAllFields(size_t index, std::vector<float> &point_data) const

Get all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc…

inline void setPointAllFields(size_t index, const std::vector<float> &point_data)

Set all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc… Unlike setPointAllFields(), this method does not check for index out of bounds

void clipOutOfRangeInZ(float zMin, float zMax, mrpt::maps::CPointsMap &result) const

Stores into a new cloud all the points except those out of the given “z” azis range.

void clipOutOfRange(const mrpt::math::TPoint2D &point, float maxRange, mrpt::maps::CPointsMap &result) const

Stores into a new cloud all the points except those farther than “maxRange” away from the given “point”.

void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const override
void determineMatching3D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const override
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) const override
void compute3DDistanceToMesh(const mrpt::maps::CMetricMap *otherMap2, const mrpt::poses::CPose3D &otherMapPose, float maxDistForCorrespondence, mrpt::tfest::TMatchingPairList &correspondences, float &correspondencesRatio)

Computes the matchings between this and another 3D points map. This method matches each point in the other map with the centroid of the 3 closest points in 3D from this map (if the distance is below a defined threshold).

See also

determineMatching3D

Parameters:
  • otherMap – [IN] The other map to compute the matching with.

  • otherMapPose – [IN] The pose of the other map as seen from “this”.

  • maxDistForCorrespondence – [IN] Maximum 2D linear distance between two points to be matched.

  • correspondences – [OUT] The detected matchings pairs.

  • correspondencesRatio – [OUT] The ratio [0,1] of points in otherMap with at least one correspondence.

virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const std::optional<const mrpt::poses::CPose3D> &robotPose) = 0

Transform the range scan into a set of cartessian coordinated points. The options in “insertionOptions” are considered in this method.

Only ranges marked as “valid=true” in the observation will be inserted

See also

CObservation2DRangeScan, CObservation3DRangeScan

Note

Each derived class may enrich points in different ways (color, weight, etc..), so please refer to the description of the specific implementation of mrpt::maps::CPointsMap you are using.

Note

The actual generic implementation of this file lives in <src>/CPointsMap_crtp_common.h, but specific instantiations are generated at each derived class.

Parameters:
  • rangeScan – The scan to be inserted into this map

  • robotPose – Default to (0,0,0|0deg,0deg,0deg). Changes the frame of reference for the point cloud (i.e. the vehicle/robot pose in world coordinates).

virtual void loadFromRangeScan(const mrpt::obs::CObservation3DRangeScan &rangeScan, const std::optional<const mrpt::poses::CPose3D> &robotPose) = 0

Overload of loadFromRangeScan() for 3D range scans (for example, Kinect observations).

Note

Each derived class may enrich points in different ways (color, weight, etc..), so please refer to the description of the specific implementation of mrpt::maps::CPointsMap you are using.

Note

The actual generic implementation of this file lives in <src>/CPointsMap_crtp_common.h, but specific instantiations are generated at each derived class.

Parameters:
  • rangeScan – The scan to be inserted into this map

  • robotPose – Default to (0,0,0|0deg,0deg,0deg). Changes the frame of reference for the point cloud (i.e. the vehicle/robot pose in world coordinates).

void loadFromVelodyneScan(const mrpt::obs::CObservationVelodyneScan &scan, const std::optional<const mrpt::poses::CPose3D> &robotPose = std::nullopt)

Like loadFromRangeScan() for Velodyne 3D scans. Points are translated and rotated according to the sensorPose field in the observation and, if provided, to the robotPose parameter.

Parameters:
  • scan – The Raw LIDAR data to be inserted into this map. It MUST contain point cloud data, generated by calling to mrpt::obs::CObservationVelodyneScan::generatePointCloud() prior to insertion in this map.

  • robotPose – Default to (0,0,0|0deg,0deg,0deg). Changes the frame of reference for the point cloud (i.e. the vehicle/robot pose in world coordinates).

void fuseWith(CPointsMap *anotherMap, float minDistForFuse = 0.02f, std::vector<bool> *notFusedPoints = nullptr)

Insert the contents of another map into this one, fusing the previous content with the new one. This means that points very close to existing ones will be “fused”, rather than “added”. This prevents the unbounded increase in size of these class of maps. NOTICE that “otherMap” is neither translated nor rotated here, so if this is desired it must done before calling this method.

See also

loadFromRangeScan, addFrom

Parameters:
  • otherMap – The other map whose points are to be inserted into this one.

  • minDistForFuse – Minimum distance (in meters) between two points, each one in a map, to be considered the same one and be fused rather than added.

  • notFusedPoints – If a pointer is supplied, this list will contain at output a list with a “bool” value per point in “this” map. This will be false/true according to that point having been fused or not.

void changeCoordinatesReference(const mrpt::poses::CPose2D &b)

Replace each point \( p_i \) by \( p'_i = b \oplus p_i \) (pose compounding operator).

void changeCoordinatesReference(const mrpt::poses::CPose3D &b)

Replace each point \( p_i \) by \( p'_i = b \oplus p_i \) (pose compounding operator).

void changeCoordinatesReference(const CPointsMap &other, const mrpt::poses::CPose3D &b)

Copy all the points from “other” map to “this”, replacing each point \( p_i \) by \( p'_i = b \oplus p_i \) (pose compounding operator).

bool isEmpty() const override

Returns true if the map is empty/no observation has been inserted.

inline bool empty() const

STL-like method to check whether the map is empty:

void getVisualizationInto(mrpt::viz::CSetOfObjects &outObj) const override

Returns a 3D object representing the map. The color of the points is controlled by renderOptions

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.

void extractCylinder(const mrpt::math::TPoint2D &center, double radius, double zmin, double zmax, CPointsMap &outMap)

Extracts the points in the map within a cylinder in 3D defined the provided radius and zmin/zmax values.

void extractPoints(const mrpt::math::TBoundingBoxf &bbox, CPointsMap &outMap)

Extracts the points in the map within the area defined by two corners. The points are coloured according the R,G,B input data.

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, std::size_t num_pts) const
inline void mark_as_modified() const

Users normally don’t need to call this. Called by this class or children classes, set m_largestDistanceFromOriginIsUpdated=false, invalidates the kd-tree cache, and such.

std::string asString() const override

Returns a short description of the map.

Public Members

TInsertionOptions insertionOptions

The options used when inserting observations in the map

TLikelihoodOptions likelihoodOptions
TRenderOptions renderOptions

Protected Functions

bool internal_insertObservation(const mrpt::obs::CObservation &obs, const std::optional<const mrpt::poses::CPose3D> &robotPose) override

This is a common version of CMetricMap::insertObservation() for point maps (actually, CMetricMap::internal_insertObservation), so derived classes don’t need to worry implementing that method unless something special is really necessary. See mrpt::maps::CPointsMap for the enumeration of types of observations which are accepted.

Protected Attributes

mrpt::aligned_std_vector<float> m_x

The point coordinates

mrpt::aligned_std_vector<float> m_y
mrpt::aligned_std_vector<float> m_z
mrpt::obs::CSinCosLookUpTableFor2DScans m_scans_sincos_cache

Cache of sin/cos values for the latest 2D scan geometries.

mutable bool m_boundingBoxIsUpdated = false
mutable mrpt::math::TBoundingBoxf m_boundingBox
double m_heightfilter_z_min = {-10}

The minimum and maximum height for a certain laser scan to be inserted into this map

double m_heightfilter_z_max = {10}
bool m_heightfilter_enabled = {false}

Whether or not (default=not) filter the input points by height

See also

m_heightfilter_z_min, m_heightfilter_z_max

Friends

friend struct detail::loadFromRangeImpl
friend struct detail::pointmap_traits
struct InsertCtx

Insert context for insertPointFrom().

Public Members

const mrpt::aligned_std_vector<float> *xs_src = nullptr
const mrpt::aligned_std_vector<float> *ys_src = nullptr
const mrpt::aligned_std_vector<float> *zs_src = nullptr
std::vector<FloatFieldMapping> float_fields
std::vector<DoubleFieldMapping> double_fields
std::vector<UInt16FieldMapping> uint16_fields
std::vector<UInt8FieldMapping> uint8_fields
struct DoubleFieldMapping

Public Members

const mrpt::aligned_std_vector<double> *src_buf = nullptr
mrpt::aligned_std_vector<double> *dst_buf = nullptr
struct FloatFieldMapping

Public Members

const mrpt::aligned_std_vector<float> *src_buf = nullptr
mrpt::aligned_std_vector<float> *dst_buf = nullptr
struct UInt16FieldMapping

Public Members

const mrpt::aligned_std_vector<uint16_t> *src_buf = nullptr
mrpt::aligned_std_vector<uint16_t> *dst_buf = nullptr
struct UInt8FieldMapping

Public Members

const mrpt::aligned_std_vector<uint8_t> *src_buf = nullptr
mrpt::aligned_std_vector<uint8_t> *dst_buf = nullptr
struct TInsertionOptions : public mrpt::config::CLoadableOptions

With this struct options are provided to the observation insertion process.

See also

CObservation::insertIntoPointsMap

Public Functions

TInsertionOptions()

Initialization of default parameters

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 - for usage in derived classes’ serialization

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

Binary dump to stream - for usage in derived classes’ serialization

Public Members

float minDistBetweenLaserPoints = {0.02f}

The minimum distance between points (in 3D): If two points are too close, one of them is not inserted into the map. Default is 0.02 meters.

bool addToExistingPointsMap = {true}

Applicable to “loadFromRangeScan” only! If set to false, the points from the scan are loaded, clearing all previous content. Default is false.

bool also_interpolate = {false}

If set to true, far points (<1m) are interpolated with samples at “minDistSqrBetweenLaserPoints” intervals (Default is false).

bool fuseWithExisting = {false}

If set to true (default=false), inserted points are “fused” with previously existent ones. This shrink the size of the points map, but its slower.

bool isPlanarMap = {false}

If set to true, only HORIZONTAL (in the XY plane) measurements will be inserted in the map (Default value is false, thus 3D maps are generated).

float horizontalTolerance

The tolerance in rads in pitch & roll for a laser scan to be considered horizontal, considered only when isPlanarMap=true (default=0).

float maxDistForInterpolatePoints = {2.0f}

The maximum distance between two points to interpolate between them (ONLY when also_interpolate=true)

bool insertInvalidPoints = {false}

Points with x,y,z coordinates set to zero will also be inserted

struct TLaserRange2DInsertContext

Helper struct used for internal_loadFromRangeScan2D_prepareOneRange()

Public Functions

inline explicit TLaserRange2DInsertContext(const mrpt::obs::CObservation2DRangeScan &_rangeScan)

Public Members

mrpt::math::CMatrixDouble44 HM

Homog matrix of the local sensor pose within the robot

const mrpt::obs::CObservation2DRangeScan &rangeScan
std::vector<float> fVars

Extra variables to be used as desired by the derived class.

std::vector<unsigned int> uVars
std::vector<uint8_t> bVars
struct TLaserRange3DInsertContext

Helper struct used for internal_loadFromRangeScan3D_prepareOneRange()

Public Functions

inline explicit TLaserRange3DInsertContext(const mrpt::obs::CObservation3DRangeScan &_rangeScan)

Public Members

mrpt::math::CMatrixDouble44 HM

Homog matrix of the local sensor pose within the robot

const mrpt::obs::CObservation3DRangeScan &rangeScan
float scan_x = 0

In internal_loadFromRangeScan3D_prepareOneRange, these are the local coordinates of the scan points being inserted right now.

float scan_y = 0
float scan_z = 0
std::vector<float> fVars

Extra variables to be used as desired by the derived class.

std::vector<unsigned int> uVars
std::vector<uint8_t> bVars
struct TLikelihoodOptions : public mrpt::config::CLoadableOptions

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

See also

CObservation::computeObservationLikelihood

Public Functions

TLikelihoodOptions()

Initialization of default parameters

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 - for usage in derived classes’ serialization

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

Binary dump to stream - for usage in derived classes’ serialization

Public Members

double sigma_dist = {0.0025}

Sigma squared (variance, in meters) of the exponential used to model the likelihood (default= 0.5^2 meters)

double max_corr_distance = {1.0}

Maximum distance in meters to consider for the numerator divided by “sigma_dist”, so that each point has a minimum (but very small) likelihood to avoid underflows (default=1.0 meters)

uint32_t decimation = {10}

Speed up the likelihood computation by considering only one out of N rays (default=10)

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::cmNONE}

Colormap for points (index is “z” coordinates)