class mrpt::maps::CColouredPointsMap

A map of 2D/3D points with individual colours (RGB).

For different color schemes, see CColouredPointsMap::colorScheme Colors are defined in the range [0,1].

See also:

mrpt::maps::CPointsMap, mrpt::maps::CMetricMap, mrpt::serialization::CSerializable

#include <mrpt/maps/CColouredPointsMap.h>

class CColouredPointsMap: public mrpt::maps::CPointsMap
{
public:
    // enums

    enum TColouringMethod;

    // structs

    struct TColourOptions;

    //
fields

    TColourOptions colorScheme;
    TInsertionOptions insertionOptions;
    TKDTreeSearchParams kdtree_search_params;

    // construction

    CColouredPointsMap();
    CColouredPointsMap(const CPointsMap& o);
    CColouredPointsMap(const CColouredPointsMap& o);

    //
methods

    virtual void reserve(size_t newLength);
    virtual void resize(size_t newLength);
    virtual void setSize(size_t newLength);
    virtual void insertPointFast(float x, float y, float z = 0);
    virtual void getPointAllFieldsFast(const size_t index, std::vector<float>& point_data) const;
    virtual void setPointAllFieldsFast(const size_t index, const std::vector<float>& point_data);
    virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan& rangeScan, const mrpt::poses::CPose3D* robotPose = nullptr);
    virtual void loadFromRangeScan(const mrpt::obs::CObservation3DRangeScan& rangeScan, const mrpt::poses::CPose3D* robotPose = nullptr);

    template <class POINTCLOUD>
    void setFromPCLPointCloudRGB(const POINTCLOUD& cloud);

    template <class POINTCLOUD>
    void getPCLPointCloudXYZRGB(POINTCLOUD& cloud) const;

    void setPointFast(size_t index, float x, float y, float z);
    bool load2D_from_text_file(const std::string& file);
    bool load3D_from_text_file(const std::string& file);
    bool load2Dor3D_from_text_file(const std::string& file, const bool is_3D);
    bool save2D_to_text_file(const std::string& file) const;
    bool save3D_to_text_file(const std::string& file) const;
    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const;
    void enableFilterByHeight(bool enable = true);
    bool isFilterByHeightEnabled() const;
    void setHeightFilterLevels(const double _z_min, const double _z_max);
    void getHeightFilterLevels(double& _z_min, double& _z_max) const;

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

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

    size_t kdtree_get_point_count() const;
    float kdtree_get_pt(const size_t idx, int dim) const;
    float kdtree_distance(const float* p1, const size_t idx_p2, size_t size) const;
    size_t kdTreeClosestPoint2D(float x0, float y0, float& out_x, float& out_y, float& out_dist_sqr) const;
    size_t kdTreeClosestPoint2D(float x0, float y0, float& out_dist_sqr) const;
    size_t kdTreeClosestPoint2D(const TPoint2D& p0, TPoint2D& pOut, float& outDistSqr) const;
    float kdTreeClosestPoint2DsqrError(float x0, float y0) const;

    void kdTreeTwoClosestPoint2D(
        float x0,
        float y0,
        float& out_x1,
        float& out_y1,
        float& out_x2,
        float& out_y2,
        float& out_dist_sqr1,
        float& out_dist_sqr2
        ) const;

    std::vector<size_t> kdTreeNClosestPoint2D(
        float x0,
        float y0,
        size_t knn,
        std::vector<float>& out_x,
        std::vector<float>& out_y,
        std::vector<float>& out_dist_sqr
        ) const;

    void kdTreeNClosestPoint2DIdx(
        float x0,
        float y0,
        size_t knn,
        std::vector<size_t>& out_idx,
        std::vector<float>& out_dist_sqr
        ) const;

    size_t kdTreeClosestPoint3D(
        float x0,
        float y0,
        float z0,
        float& out_x,
        float& out_y,
        float& out_z,
        float& out_dist_sqr
        ) const;

    size_t kdTreeClosestPoint3D(float x0, float y0, float z0, float& out_dist_sqr) const;
    size_t kdTreeClosestPoint3D(const TPoint3D& p0, TPoint3D& pOut, float& outDistSqr) const;

    void kdTreeNClosestPoint3D(
        float x0,
        float y0,
        float z0,
        size_t knn,
        std::vector<float>& out_x,
        std::vector<float>& out_y,
        std::vector<float>& out_z,
        std::vector<float>& out_dist_sqr
        ) const;

    void kdTreeNClosestPoint3DWithIdx(
        float x0,
        float y0,
        float z0,
        size_t knn,
        std::vector<float>& out_x,
        std::vector<float>& out_y,
        std::vector<float>& out_z,
        std::vector<size_t>& out_idx,
        std::vector<float>& out_dist_sqr
        ) const;

    size_t kdTreeRadiusSearch3D(
        const float x0,
        const float y0,
        const float z0,
        const float maxRadiusSqr,
        std::vector<std::pair<size_t, float>>& out_indices_dist
        ) const;

    size_t kdTreeRadiusSearch2D(
        const float x0,
        const float y0,
        const float maxRadiusSqr,
        std::vector<std::pair<size_t, float>>& out_indices_dist
        ) const;

    void kdTreeNClosestPoint3DIdx(
        float x0,
        float y0,
        float z0,
        size_t knn,
        std::vector<size_t>& out_idx,
        std::vector<float>& out_dist_sqr
        ) const;

    CColouredPointsMap& operator = (const CPointsMap& o);
    CColouredPointsMap& operator = (const CColouredPointsMap& o);
    bool save3D_and_colour_to_text_file(const std::string& file) const;
    void setPointRGB(size_t index, float x, float y, float z, float R, float G, float B);
    void insertPointRGB(float x, float y, float z, float R, float G, float B);
    void setPointColor(size_t index, float R, float G, float B);
    void setPointColor_fast(size_t index, float R, float G, float B);

    virtual void getPointRGB(
        size_t index,
        float& x,
        float& y,
        float& z,
        float& R,
        float& G,
        float& B
        ) const;

    void getPointColor(size_t index, float& R, float& G, float& B) const;
    void getPointColor_fast(size_t index, float& R, float& G, float& B) const;
    virtual bool hasColorPoints() const;
    virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const;
    bool colourFromObservation(const mrpt::obs::CObservationImage& obs, const mrpt::poses::CPose3D& robotPose);
    void resetPointsMinDist(float defValue = 2000.0f);
    virtual float squareDistanceToClosestCorrespondence(float x0, float y0) const;
    virtual void addFrom(const CPointsMap& anotherMap);
    void operator += (const CPointsMap& anotherMap);
    void insertAnotherMap(const CPointsMap* otherMap, const mrpt::poses::CPose3D& otherPose);
    size_t size() const;
    void getPoint(size_t index, float& x, float& y, float& z) const;
    void getPoint(size_t index, float& x, float& y) const;
    void getPoint(size_t index, double& x, double& y, double& z) const;
    void getPoint(size_t index, double& x, double& y) const;
    void getPoint(size_t index, mrpt::math::TPoint2D& p) const;
    void getPoint(size_t index, mrpt::math::TPoint3D& p) const;
    void getPointFast(size_t index, float& x, float& y, float& z) const;
    void setPoint(size_t index, float x, float y, float z);
    void setPoint(size_t index, const mrpt::math::TPoint2D& p);
    void setPoint(size_t index, const mrpt::math::TPoint3D& p);
    void setPoint(size_t index, float x, float y);

    virtual void setPointRGB(
        size_t index,
        float x,
        float y,
        float z,
        ] float R,
        ] float G,
        ] float B
        );

    virtual void setPointWeight(] size_t index, ] unsigned long w);
    virtual unsigned int getPointWeight(] size_t index) const;

    void getPointsBuffer(
        size_t& outPointsCount,
        const float*& xs,
        const float*& ys,
        const float*& zs
        ) const;

    const mrpt::aligned_std_vector<float>& getPointsBufferRef_x() const;
    const mrpt::aligned_std_vector<float>& getPointsBufferRef_y() const;
    const mrpt::aligned_std_vector<float>& getPointsBufferRef_z() const;

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

    template <class CONTAINER>
    void getAllPoints(CONTAINER& ps, size_t decimation = 1) const;

    void getAllPoints(std::vector<float>& xs, std::vector<float>& ys, size_t decimation = 1) const;
    void insertPoint(float x, float y, float z = 0);
    void insertPoint(const mrpt::math::TPoint3D& p);
    virtual void insertPointRGB(float x, float y, float z, ] float R, ] float G, ] float B);

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

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

    void setAllPoints(const std::vector<float>& X, const std::vector<float>& Y);
    void getPointAllFields(const size_t index, std::vector<float>& point_data) const;
    void setPointAllFields(const size_t index, const std::vector<float>& point_data);
    void clipOutOfRangeInZ(float zMin, float zMax);
    void clipOutOfRange(const mrpt::math::TPoint2D& point, float maxRange);
    void applyDeletionMask(const std::vector<bool>& mask);

    virtual void determineMatching2D(
        const mrpt::maps::CMetricMap* otherMap,
        const mrpt::poses::CPose2D& otherMapPose,
        mrpt::tfest::TMatchingPairList& correspondences,
        const TMatchingParams& params,
        TMatchingExtraResults& extraResults
        ) const;

    virtual void determineMatching3D(
        const mrpt::maps::CMetricMap* otherMap,
        const mrpt::poses::CPose3D& otherMapPose,
        mrpt::tfest::TMatchingPairList& correspondences,
        const TMatchingParams& params,
        TMatchingExtraResults& extraResults
        ) const;

    virtual float compute3DMatchingRatio(const mrpt::maps::CMetricMap* otherMap, const mrpt::poses::CPose3D& otherMapPose, const TMatchingRatioParams& params) const;

    void compute3DDistanceToMesh(
        const mrpt::maps::CMetricMap* otherMap2,
        const mrpt::poses::CPose3D& otherMapPose,
        float maxDistForCorrespondence,
        mrpt::tfest::TMatchingPairList& correspondences,
        float& correspondencesRatio
        );

    void loadFromVelodyneScan(const mrpt::obs::CObservationVelodyneScan& scan, const mrpt::poses::CPose3D* robotPose = nullptr);

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

    void changeCoordinatesReference(const mrpt::poses::CPose2D& b);
    void changeCoordinatesReference(const mrpt::poses::CPose3D& b);
    void changeCoordinatesReference(const CPointsMap& other, const mrpt::poses::CPose3D& b);
    virtual bool isEmpty() const;
    bool empty() const;
    float getLargestDistanceFromOrigin() const;
    float getLargestDistanceFromOriginNoRecompute(bool& output_is_valid) const;

    void boundingBox(
        float& min_x,
        float& max_x,
        float& min_y,
        float& max_y,
        float& min_z,
        float& max_z
        ) const;

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

    void extractPoints(
        const mrpt::math::TPoint3D& corner1,
        const mrpt::math::TPoint3D& corner2,
        CPointsMap* outMap,
        double R = 1,
        double G = 1,
        double B = 1
        );

    virtual double internal_computeObservationLikelihood(const mrpt::obs::CObservation& obs, const mrpt::poses::CPose3D& takenFrom);
    void mark_as_modified() const;
    const CPointsMap& derived() const;
    CPointsMap& derived();

    bool loadFromPlyFile(
        const std::string& filename,
        std::vector<std::string>* file_comments = nullptr,
        std::vector<std::string>* file_obj_info = nullptr
        );

    std::string getLoadPLYErrorString() const;

    bool saveToPlyFile(
        const std::string& filename,
        bool save_in_binary = false,
        const std::vector<std::string>& file_comments = std::vector<std::string>(),
        const std::vector<std::string>& file_obj_info = std::vector<std::string>()
        ) const;

    std::string getSavePLYErrorString() const;
};

Inherited Members

public:
    // typedefs

    typedef KDTreeCapable<Derived, num_t, metric_t> self_t;

    // structs

    template <int _DIM = -1>
    struct TKDTreeDataHolder;

    struct TKDTreeSearchParams;
    struct TInsertionOptions;
    struct TLaserRange2DInsertContext;
    struct TLaserRange3DInsertContext;
    struct TLikelihoodOptions;
    struct TRenderOptions;

    //
methods

    virtual bool isEmpty() const = 0;
    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const = 0;
    virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const = 0;
    float kdTreeClosestPoint2DsqrError(const TPoint2D& p0) const;
    void kdTreeTwoClosestPoint2D(const TPoint2D& p0, TPoint2D& pOut1, TPoint2D& pOut2, float& outDistSqr1, float& outDistSqr2) const;

    std::vector<size_t> kdTreeNClosestPoint2D(
        const TPoint2D& p0,
        size_t N,
        std::vector<TPoint2D>& pOut,
        std::vector<float>& outDistSqr
        ) const;

    void kdTreeNClosestPoint2DIdx(
        const TPoint2D& p0,
        size_t N,
        std::vector<size_t>& outIdx,
        std::vector<float>& outDistSqr
        ) const;

    void kdTreeNClosestPoint3D(const TPoint3D& p0, size_t N, std::vector<TPoint3D>& pOut, std::vector<float>& outDistSqr) const;

    void kdTreeNClosestPoint3DIdx(
        const TPoint3D& p0,
        size_t N,
        std::vector<size_t>& outIdx,
        std::vector<float>& outDistSqr
        ) const;

    void kdTreeEnsureIndexBuilt3D();
    void kdTreeEnsureIndexBuilt2D();
    KDTreeCapable& operator = (const KDTreeCapable&);
    virtual void reserve(size_t newLength) = 0;
    virtual void resize(size_t newLength) = 0;
    virtual void setSize(size_t newLength) = 0;
    virtual void insertPointFast(float x, float y, float z = 0) = 0;
    virtual void getPointAllFieldsFast(const size_t index, std::vector<float>& point_data) const = 0;
    virtual void setPointAllFieldsFast(const size_t index, const std::vector<float>& point_data) = 0;
    CPointsMap& operator = (const CPointsMap& o);

    virtual void getPointRGB(
        size_t index,
        float& x,
        float& y,
        float& z,
        float& R,
        float& G,
        float& B
        ) const;

    virtual bool hasColorPoints() const;
    virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan& rangeScan, const mrpt::poses::CPose3D* robotPose = nullptr) = 0;
    virtual void loadFromRangeScan(const mrpt::obs::CObservation3DRangeScan& rangeScan, const mrpt::poses::CPose3D* robotPose = nullptr) = 0;
    virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const;

Fields

TColourOptions colorScheme

The options employed when inserting laser scans in the map.

TInsertionOptions insertionOptions

The options used when inserting observations in the map.

TKDTreeSearchParams kdtree_search_params

Parameters to tune the ANN searches.

Methods

virtual void reserve(size_t newLength)

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)

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.

See also:

reserve, setPoint, setPointFast, setSize

virtual void setSize(size_t newLength)

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

See also:

reserve, setPoint, setPointFast, setSize

virtual void insertPointFast(float x, float y, float z = 0)

The virtual method for insertPoint() without calling mark_as_modified()

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

Get all the data fields for one point as a vector: [X Y Z R G B] Unlike getPointAllFields(), this method does not check for index out of bounds.

See also:

getPointAllFields, setPointAllFields, setPointAllFieldsFast

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

Set all the data fields for one point as a vector: [X Y Z R G B] Unlike setPointAllFields(), this method does not check for index out of bounds.

See also:

setPointAllFields, getPointAllFields, getPointAllFieldsFast

virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan& rangeScan, const mrpt::poses::CPose3D* robotPose = nullptr)

See CPointsMap::loadFromRangeScan()

virtual void loadFromRangeScan(const mrpt::obs::CObservation3DRangeScan& rangeScan, const mrpt::poses::CPose3D* robotPose = nullptr)

See CPointsMap::loadFromRangeScan()

template <class POINTCLOUD>
void setFromPCLPointCloudRGB(const POINTCLOUD& cloud)

Loads a PCL point cloud (WITH RGB information) into this MRPT class (for clouds without RGB data, see CPointsMap::setFromPCLPointCloud()).

Usage example:

pcl::PointCloud<pcl::PointXYZRGB> cloud;
mrpt::maps::CColouredPointsMap       pc;

pc.setFromPCLPointCloudRGB(cloud);

See also:

CPointsMap::setFromPCLPointCloud()

template <class POINTCLOUD>
void getPCLPointCloudXYZRGB(POINTCLOUD& cloud) const

Like CPointsMap::getPCLPointCloud() but for PointCloud<PointXYZRGB>

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

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 occured, true elsewere.

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 occured, true elsewere.

bool load2Dor3D_from_text_file(const std::string& file, const bool is_3D)

2D or 3D generic implementation of load2D_from_text_file and load3D_from_text_file

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 occured, true elsewere.

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 occured, true elsewere.

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

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)

void enableFilterByHeight(bool enable = true)

Enable/disable the filter-by-height functionality.

Default upon construction is disabled.

See also:

setHeightFilterLevels

bool isFilterByHeightEnabled() const

Return whether filter-by-height is enabled.

See also:

enableFilterByHeight

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).

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

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

See also:

enableFilterByHeight, setHeightFilterLevels

template <class POINTCLOUD>
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>
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()

size_t kdtree_get_point_count() const

Must return the number of data points.

float kdtree_get_pt(const size_t idx, int dim) const

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

float kdtree_distance(const float* p1, const 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:

size_t kdTreeClosestPoint2D(
    float x0,
    float y0,
    float& out_x,
    float& out_y,
    float& out_dist_sqr
    ) const

KD Tree-based search for the closest point (only ONE) to some given 2D coordinates.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 3D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

out_x

The X coordinate of the found closest correspondence.

out_y

The Y coordinate of the found closest correspondence.

out_dist_sqr

The square distance between the query and the returned point.

Returns:

The index of the closest point in the map array.

See also:

kdTreeClosestPoint3D, kdTreeTwoClosestPoint2D

size_t kdTreeClosestPoint2D(float x0, float y0, float& out_dist_sqr) const

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

size_t kdTreeClosestPoint2D(
    const TPoint2D& p0,
    TPoint2D& pOut,
    float& outDistSqr
    ) const

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

float kdTreeClosestPoint2DsqrError(float x0, float y0) const

Like kdTreeClosestPoint2D, but just return the square error from some point to its closest neighbor.

void kdTreeTwoClosestPoint2D(
    float x0,
    float y0,
    float& out_x1,
    float& out_y1,
    float& out_x2,
    float& out_y2,
    float& out_dist_sqr1,
    float& out_dist_sqr2
    ) const

KD Tree-based search for the TWO closest point to some given 2D coordinates.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 3D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

out_x1

The X coordinate of the first correspondence.

out_y1

The Y coordinate of the first correspondence.

out_x2

The X coordinate of the second correspondence.

out_y2

The Y coordinate of the second correspondence.

out_dist_sqr1

The square distance between the query and the first returned point.

out_dist_sqr2

The square distance between the query and the second returned point.

See also:

kdTreeClosestPoint2D

std::vector<size_t> kdTreeNClosestPoint2D(
    float x0,
    float y0,
    size_t knn,
    std::vector<float>& out_x,
    std::vector<float>& out_y,
    std::vector<float>& out_dist_sqr
    ) const

KD Tree-based search for the N closest point to some given 2D coordinates.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 3D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

N

The number of closest points to search.

out_x

The vector containing the X coordinates of the correspondences.

out_y

The vector containing the Y coordinates of the correspondences.

out_dist_sqr

The vector containing the square distance between the query and the returned points.

Returns:

The list of indices

See also:

kdTreeClosestPoint2D

kdTreeTwoClosestPoint2D

void kdTreeNClosestPoint2DIdx(
    float x0,
    float y0,
    size_t knn,
    std::vector<size_t>& out_idx,
    std::vector<float>& out_dist_sqr
    ) const

KD Tree-based search for the N closest point to some given 2D coordinates and returns their indexes.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 3D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

N

The number of closest points to search.

out_idx

The indexes of the found closest correspondence.

out_dist_sqr

The square distance between the query and the returned point.

See also:

kdTreeClosestPoint2D

size_t kdTreeClosestPoint3D(
    float x0,
    float y0,
    float z0,
    float& out_x,
    float& out_y,
    float& out_z,
    float& out_dist_sqr
    ) const

KD Tree-based search for the closest point (only ONE) to some given 3D coordinates.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 2D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

z0

The Z coordinate of the query.

out_x

The X coordinate of the found closest correspondence.

out_y

The Y coordinate of the found closest correspondence.

out_z

The Z coordinate of the found closest correspondence.

out_dist_sqr

The square distance between the query and the returned point.

Returns:

The index of the closest point in the map array.

See also:

kdTreeClosestPoint2D

size_t kdTreeClosestPoint3D(float x0, float y0, float z0, float& out_dist_sqr) const

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

size_t kdTreeClosestPoint3D(
    const TPoint3D& p0,
    TPoint3D& pOut,
    float& outDistSqr
    ) const

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

void kdTreeNClosestPoint3D(
    float x0,
    float y0,
    float z0,
    size_t knn,
    std::vector<float>& out_x,
    std::vector<float>& out_y,
    std::vector<float>& out_z,
    std::vector<float>& out_dist_sqr
    ) const

KD Tree-based search for the N closest points to some given 3D coordinates.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 2D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

z0

The Z coordinate of the query.

N

The number of closest points to search.

out_x

The vector containing the X coordinates of the correspondences.

out_y

The vector containing the Y coordinates of the correspondences.

out_z

The vector containing the Z coordinates of the correspondences.

out_dist_sqr

The vector containing the square distance between the query and the returned points.

See also:

kdTreeNClosestPoint2D

void kdTreeNClosestPoint3DWithIdx(
    float x0,
    float y0,
    float z0,
    size_t knn,
    std::vector<float>& out_x,
    std::vector<float>& out_y,
    std::vector<float>& out_z,
    std::vector<size_t>& out_idx,
    std::vector<float>& out_dist_sqr
    ) const

KD Tree-based search for the N closest points to some given 3D coordinates.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 2D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

z0

The Z coordinate of the query.

N

The number of closest points to search.

out_x

The vector containing the X coordinates of the correspondences.

out_y

The vector containing the Y coordinates of the correspondences.

out_z

The vector containing the Z coordinates of the correspondences.

out_idx

The vector containing the indexes of the correspondences.

out_dist_sqr

The vector containing the square distance between the query and the returned points.

See also:

kdTreeNClosestPoint2D

size_t kdTreeRadiusSearch3D(
    const float x0,
    const float y0,
    const float z0,
    const float maxRadiusSqr,
    std::vector<std::pair<size_t, float>>& out_indices_dist
    ) const

KD Tree-based search for all the points within a given radius of some 3D point.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 2D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

z0

The Z coordinate of the query.

maxRadiusSqr

The square of the desired search radius.

out_indices_dist

The output list, with pairs of indeces/squared distances for the found correspondences.

Returns:

Number of found points.

See also:

kdTreeRadiusSearch2D, kdTreeNClosestPoint3DIdx

size_t kdTreeRadiusSearch2D(
    const float x0,
    const float y0,
    const float maxRadiusSqr,
    std::vector<std::pair<size_t, float>>& out_indices_dist
    ) const

KD Tree-based search for all the points within a given radius of some 2D point.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 3D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

maxRadiusSqr

The square of the desired search radius.

out_indices_dist

The output list, with pairs of indeces/squared distances for the found correspondences.

Returns:

Number of found points.

See also:

kdTreeRadiusSearch3D, kdTreeNClosestPoint2DIdx

void kdTreeNClosestPoint3DIdx(
    float x0,
    float y0,
    float z0,
    size_t knn,
    std::vector<size_t>& out_idx,
    std::vector<float>& out_dist_sqr
    ) const

KD Tree-based search for the N closest point to some given 3D coordinates and returns their indexes.

This method automatically build the “m_kdtree_data” structure when:

  • It is called for the first time

  • The map has changed

  • The KD-tree was build for 2D.

Parameters:

x0

The X coordinate of the query.

y0

The Y coordinate of the query.

z0

The Z coordinate of the query.

N

The number of closest points to search.

out_idx

The indexes of the found closest correspondence.

out_dist_sqr

The square distance between the query and the returned point.

See also:

kdTreeClosestPoint2D, kdTreeRadiusSearch3D

bool save3D_and_colour_to_text_file(const std::string& file) const

Save to a text file.

In each line contains X Y Z (meters) R G B (range [0,1]) for each point in the map. Returns false if any error occured, true elsewere.

void setPointRGB(
    size_t index,
    float x,
    float y,
    float z,
    float R,
    float G,
    float B
    )

Changes a given point from map.

First index is 0.

Parameters:

Throws

std::exception on index out of bound.

void insertPointRGB(float x, float y, float z, float R, float G, float B)

Adds a new point given its coordinates and color (colors range is [0,1])

void setPointColor(size_t index, float R, float G, float B)

Changes just the color of a given point from the map.

First index is 0.

Parameters:

Throws

std::exception on index out of bound.

void setPointColor_fast(size_t index, float R, float G, float B)

Like setPointColor but without checking for out-of-index erors.

virtual void getPointRGB(
    size_t index,
    float& x,
    float& y,
    float& z,
    float& R,
    float& G,
    float& B
    ) const

Retrieves a point and its color (colors range is [0,1])

void getPointColor(size_t index, float& R, float& G, float& B) const

Retrieves a point color (colors range is [0,1])

void getPointColor_fast(size_t index, float& R, float& G, float& B) const

Like getPointColor but without checking for out-of-index erors.

virtual bool hasColorPoints() const

Returns true if the point map has a color field for each point.

virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const

Override of the default 3D scene builder to account for the individual points’ color.

bool colourFromObservation(const mrpt::obs::CObservationImage& obs, const mrpt::poses::CPose3D& robotPose)

Colour a set of points from a CObservationImage and the global pose of the robot.

void resetPointsMinDist(float defValue = 2000.0f)

Reset the minimum-observed-distance buffer for all the points to a predefined value.

virtual float squareDistanceToClosestCorrespondence(float x0, float y0) const

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

virtual void addFrom(const CPointsMap& anotherMap)

Adds all the points from anotherMap to this map, without fusing.

This operation can be also invoked via the “+=” operator, for example:

mrpt::maps::CSimplePointsMap m1, m2;
...
m1.addFrom( m2 );  // Add all points of m2 to m1
m1 += m2;          // Exactly the same than above

The method in CPointsMap is generic but derived classes may redefine this virtual method to another one more optimized.

void operator += (const CPointsMap& anotherMap)

This operator is synonymous with addFrom.

See also:

addFrom

void insertAnotherMap(const CPointsMap* otherMap, const mrpt::poses::CPose3D& otherPose)

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

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

See also:

fuseWith, addFrom

size_t size() const

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

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

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.

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.

Parameters:

Throws

std::exception on index out of bound.

See also:

setPoint, getPointFast

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.

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.

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.

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.

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.

Parameters:

Throws

std::exception on index out of bound.

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.

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.

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.

virtual void setPointRGB(
    size_t index,
    float x,
    float y,
    float z,
    ] float R,
    ] float G,
    ] float B
    )

overload (RGB data is ignored in classes without color information)

virtual void setPointWeight(] size_t index, ] unsigned long w)

Sets the point weight, which is ignored in all classes but those which actually store that field (Note: No checks are done for out-of-bounds index).

See also:

getPointWeight

virtual unsigned int getPointWeight(] size_t index) const

Gets the point weight, which is ignored in all classes (defaults to 1) but in those which actually store that field (Note: No checks are done for out-of-bounds index).

See also:

setPointWeight

void getPointsBuffer(
    size_t& outPointsCount,
    const float*& xs,
    const float*& ys,
    const float*& zs
    ) const

Provides a direct access to points buffer, or nullptr if there is no points in the map.

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

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

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>
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.

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).

See also:

getPointsBufferRef_x, getPointsBufferRef_y, getPointsBufferRef_z

template <class CONTAINER>
void getAllPoints(
    CONTAINER& ps,
    size_t decimation = 1
    ) const

Gets all points as a STL-like container.

Parameters:

CONTAINER

Any STL-like container of mrpt::math::TPoint3D, mrpt::math::TPoint3Df or anything having members x, y, z. Note that this method is not efficient for large point clouds. Fastest methods are getPointsBuffer() or getPointsBufferRef_x(), getPointsBufferRef_y(), getPointsBufferRef_z()

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

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.

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.

virtual void insertPointRGB(
    float x,
    float y,
    float z,
    ] float R,
    ] float G,
    ] float B
    )

overload (RGB data is ignored in classes without color information)

template <typename VECTOR>
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).

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

void getPointAllFields(const 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…

See also:

getPointAllFieldsFast, setPointAllFields, setPointAllFieldsFast

void setPointAllFields(const 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

See also:

setPointAllFields, getPointAllFields, getPointAllFieldsFast

void clipOutOfRangeInZ(float zMin, float zMax)

Delete points out of the given “z” axis range have been removed.

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

Delete points which are more far than “maxRange” away from the given “point”.

void applyDeletionMask(const std::vector<bool>& mask)

Remove from the map the points marked in a bool’s array as “true”.

Parameters:

std::exception

If mask size is not equal to points count.

virtual void determineMatching2D(
    const mrpt::maps::CMetricMap* otherMap,
    const mrpt::poses::CPose2D& otherMapPose,
    mrpt::tfest::TMatchingPairList& correspondences,
    const TMatchingParams& params,
    TMatchingExtraResults& extraResults
    ) const

Computes the matching between this and another 2D point map, which includes finding:

  • The set of points pairs in each map

  • The mean squared distance between corresponding pairs.

The algorithm is:

  • For each point in “otherMap”:

    • Transform the point according to otherMapPose

    • Search with a KD-TREE the closest correspondences in “this” map.

    • Add to the set of candidate matchings, if it passes all the thresholds in params.

This method is the most time critical one into ICP-like algorithms.

Parameters:

otherMap

[IN] The other map to compute the matching with.

otherMapPose

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

params

[IN] Parameters for the determination of pairings.

correspondences

[OUT] The detected matchings pairs.

extraResults

[OUT] Other results.

See also:

compute3DMatchingRatio

virtual void determineMatching3D(
    const mrpt::maps::CMetricMap* otherMap,
    const mrpt::poses::CPose3D& otherMapPose,
    mrpt::tfest::TMatchingPairList& correspondences,
    const TMatchingParams& params,
    TMatchingExtraResults& extraResults
    ) const

Computes the matchings between this and another 3D points map - method used in 3D-ICP.

This method finds the set of point pairs in each map.

The method is the most time critical one into ICP-like algorithms.

The algorithm is:

  • For each point in “otherMap”:

    • Transform the point according to otherMapPose

    • Search with a KD-TREE the closest correspondences in “this” map.

    • Add to the set of candidate matchings, if it passes all the thresholds in params.

Parameters:

otherMap

[IN] The other map to compute the matching with.

otherMapPose

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

params

[IN] Parameters for the determination of pairings.

correspondences

[OUT] The detected matchings pairs.

extraResults

[OUT] Other results.

See also:

compute3DMatchingRatio

virtual float compute3DMatchingRatio(
    const mrpt::maps::CMetricMap* otherMap,
    const mrpt::poses::CPose3D& otherMapPose,
    const TMatchingRatioParams& params
    ) const

Computes the ratio in [0,1] of correspondences between “this” and the “otherMap” map, whose 6D pose relative to “this” is “otherMapPose” In the case of a multi-metric map, this returns the average between the maps.

This method always return 0 for grid maps.

Parameters:

otherMap

[IN] The other map to compute the matching with.

otherMapPose

[IN] The 6D pose of the other map as seen from “this”.

params

[IN] Matching parameters

Returns:

The matching ratio [0,1]

See also:

determineMatching2D

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).

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.

See also:

determineMatching3D

void loadFromVelodyneScan(const mrpt::obs::CObservationVelodyneScan& scan, const mrpt::poses::CPose3D* robotPose = nullptr)

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).

See also:

loadFromRangeScan

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.

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.

See also:

loadFromRangeScan, addFrom

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).

virtual bool isEmpty() const

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

bool empty() const

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

float getLargestDistanceFromOrigin() const

This method returns the largest distance from the origin to any of the points, such as a sphere centered at the origin with this radius cover ALL the points in the map (the results are buffered, such as, if the map is not modified, the second call will be much faster than the first one).

float getLargestDistanceFromOriginNoRecompute(bool& output_is_valid) const

Like getLargestDistanceFromOrigin() but returns in output_is_valid = false if the distance was not already computed, skipping its computation then, unlike getLargestDistanceFromOrigin()

void boundingBox(
    float& min_x,
    float& max_x,
    float& min_y,
    float& max_y,
    float& min_z,
    float& max_z
    ) const

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,
    const double radius,
    const double zmin,
    const 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::TPoint3D& corner1,
    const mrpt::math::TPoint3D& corner2,
    CPointsMap* outMap,
    double R = 1,
    double G = 1,
    double B = 1
    )

Extracts the points in the map within the area defined by two corners.

The points are coloured according the R,G,B input data.

virtual double internal_computeObservationLikelihood(
    const mrpt::obs::CObservation& obs,
    const mrpt::poses::CPose3D& takenFrom
    )

Internal method called by computeObservationLikelihood()

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.

const CPointsMap& derived() const

CRTP helper method.

CPointsMap& derived()

CRTP helper method.

bool loadFromPlyFile(
    const std::string& filename,
    std::vector<std::string>* file_comments = nullptr,
    std::vector<std::string>* file_obj_info = nullptr
    )

Loads from a PLY file.

Parameters:

filename

The filename to open. It can be either in binary or text format.

file_comments

If provided (!=nullptr) the list of comment strings stored in the file will be returned.

file_obj_info

If provided (!=nullptr) the list of “object info” strings stored in the file will be returned.

Returns:

false on any error in the file format or reading it. To obtain more details on the error you can call getLoadPLYErrorString()

std::string getLoadPLYErrorString() const

Return a description of the error if loadFromPlyFile() returned false, or an empty string if the file was loaded without problems.

bool saveToPlyFile(
    const std::string& filename,
    bool save_in_binary = false,
    const std::vector<std::string>& file_comments = std::vector<std::string>(),
    const std::vector<std::string>& file_obj_info = std::vector<std::string>()
    ) const

Saves to a PLY file.

Parameters:

filename

The filename to be saved.

file_comments

If provided (!=nullptr) the list of comment strings stored in the file will be returned.

file_obj_info

If provided (!=nullptr) the list of “object info” strings stored in the file will be returned.

Returns:

false on any error writing the file. To obtain more details on the error you can call getSavePLYErrorString()

std::string getSavePLYErrorString() const

Return a description of the error if loadFromPlyFile() returned false, or an empty string if the file was loaded without problems.