36 template <
class Derived>
38 template <
class Derived>
88 std::vector<unsigned int>
uVars;
131 virtual void reserve(
size_t newLength) = 0;
138 virtual void resize(
size_t newLength) = 0;
145 virtual void setSize(
size_t newLength) = 0;
167 const size_t index, std::vector<float>& point_data)
const = 0;
176 const size_t index,
const std::vector<float>& point_data) = 0;
182 const CPointsMap& anotherMap,
const size_t nPreviousPoints) = 0;
192 float x0,
float y0)
const override;
198 static_cast<float>(p0.
x), static_cast<float>(p0.
y));
213 std::ostream& out)
const override;
273 std::ostream& out)
const override;
303 std::ostream& out)
const override;
397 const std::string& filename,
bool save_as_binary)
const;
408 inline size_t size()
const {
return m_x.size(); }
419 unsigned long getPoint(
size_t index,
double&
x,
double&
y,
double&
z)
const;
440 size_t index,
float&
x,
float&
y,
float&
z,
float&
R,
float&
G,
485 size_t index,
float x,
float y,
float z,
float R,
float G,
float B)
514 size_t& outPointsCount,
const float*& xs,
const float*& ys,
515 const float*& zs)
const;
535 template <
class VECTOR>
537 VECTOR& xs, VECTOR& ys, VECTOR& zs,
size_t decimation = 1)
const 541 const size_t Nout =
m_x.size() / decimation;
545 size_t idx_in, idx_out;
546 for (idx_in = 0, idx_out = 0; idx_out < Nout;
547 idx_in += decimation, ++idx_out)
549 xs[idx_out] =
m_x[idx_in];
550 ys[idx_out] =
m_y[idx_in];
551 zs[idx_out] =
m_z[idx_in];
563 template <
class CONTAINER>
566 std::vector<float> dmy1, dmy2, dmy3;
568 ps.resize(dmy1.size());
569 for (
size_t i = 0; i < dmy1.size(); i++)
584 std::vector<float>& xs, std::vector<float>& ys,
585 size_t decimation = 1)
const;
588 std::vector<mrpt::math::TPoint2D>& ps,
size_t decimation = 1)
const 590 std::vector<float> dmy1, dmy2;
592 ps.resize(dmy1.size());
593 for (
size_t i = 0; i < dmy1.size(); i++)
595 ps[i].x =
static_cast<double>(dmy1[i]);
596 ps[i].y =
static_cast<double>(dmy2[i]);
616 float x,
float y,
float z,
float R,
float G,
float B)
629 template <
typename VECTOR>
631 const VECTOR& X,
const VECTOR& Y,
const VECTOR& Z = VECTOR())
633 const size_t N = X.size();
635 ASSERT_(Z.size() == 0 || Z.size() == X.size());
637 const bool z_valid = !Z.empty();
639 for (
size_t i = 0; i < N; i++)
644 for (
size_t i = 0; i < N; i++)
654 const std::vector<float>& X,
const std::vector<float>& Y,
655 const std::vector<float>& Z)
663 const std::vector<float>& X,
const std::vector<float>& Y)
673 const size_t index, std::vector<float>& point_data)
const 686 const size_t index,
const std::vector<float>& point_data)
747 float maxDistForCorrespondence,
749 float& correspondencesRatio);
830 CPointsMap* anotherMap,
float minDistForFuse = 0.02f,
831 std::vector<bool>* notFusedPoints =
nullptr);
851 virtual bool isEmpty()
const override;
897 float& min_x,
float& max_x,
float& min_y,
float& max_y,
float& min_z,
903 float dmy1, dmy2, dmy3, dmy4, dmy5, dmy6;
926 const double&
R = 1,
const double&
G = 1,
const double& B = 1);
980 template <
class POINTCLOUD>
983 const size_t nThis = this->
size();
987 cloud.is_dense =
false;
988 cloud.points.resize(cloud.width * cloud.height);
989 for (
size_t i = 0; i < nThis; ++i)
991 cloud.points[i].x =
m_x[i];
992 cloud.points[i].y =
m_y[i];
993 cloud.points[i].z =
m_z[i];
1009 template <
class POINTCLOUD>
1012 const size_t N = cloud.points.size();
1015 for (
size_t i = 0; i < N; ++i)
1017 cloud.points[i].x, cloud.points[i].y, cloud.points[i].z);
1044 const float* p1,
const size_t idx_p2,
size_t size)
const 1048 const float d0 = p1[0] -
m_x[idx_p2];
1049 const float d1 = p1[1] -
m_y[idx_p2];
1050 return d0 * d0 + d1 * d1;
1054 const float d0 = p1[0] -
m_x[idx_p2];
1055 const float d1 = p1[1] -
m_y[idx_p2];
1056 const float d2 = p1[2] -
m_z[idx_p2];
1057 return d0 * d0 + d1 * d1 + d2 * d2;
1067 template <
typename BBOX>
1072 bb[0].low, bb[0].high, bb[1].low, bb[1].high, min_z, max_z);
1164 template <
class Derived>
1166 template <
class Derived>
1188 static const int HAS_RGB = 0;
1190 static const int HAS_RGBf = 0;
1192 static const int HAS_RGBu8 = 0;
1196 : m_obj(*const_cast<
mrpt::maps::CPointsMap*>(&
obj))
1208 template <
typename T>
void clear()
Erase all the contents of the map.
virtual void copyFrom(const CPointsMap &obj)=0
Virtual assignment operator, copies as much common data (XYZ, color,...) as possible from the source ...
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - used in derived classes' serialization.
TLikelihoodOptions()
Initilization of default parameters.
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - for usage in derived classes' serialization.
void setFromPCLPointCloud(const POINTCLOUD &cloud)
Loads a PCL point cloud into this MRPT class (note: this method ignores potential RGB information...
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 for CMetricMap::compute3DMatchingRatio()
bool save2D_to_text_file(const std::string &file) const
Save to a text file.
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).
bool isPlanarMap
If set to true, only HORIZONTAL (in the XY plane) measurements will be inserted in the map (Default v...
bool empty() const
STL-like method to check whether the map is empty:
mrpt::img::TColormap colormap
Colormap for points (index is "z" coordinates)
virtual void addFrom(const CPointsMap &anotherMap)
Adds all the points from anotherMap to this map, without fusing.
TColormap
Different colormaps for use in mrpt::img::colormap()
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...
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose=nullptr)=0
Transform the range scan into a set of cartessian coordinated points.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
bool internal_insertObservation(const mrpt::obs::CObservation *obs, 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 necesary.
bool m_heightfilter_enabled
Whether or not (default=not) filter the input points by height.
void operator+=(const CPointsMap &anotherMap)
This operator is synonymous with addFrom.
size_t PLY_export_get_face_count() const override
In a base class, return the number of faces.
void changeCoordinatesReference(const mrpt::poses::CPose2D &b)
Replace each point by (pose compounding operator).
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
const mrpt::obs::CObservation2DRangeScan & rangeScan
const mrpt::obs::CObservation3DRangeScan & rangeScan
#define ASSERT_BELOW_(__A, __B)
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).
virtual void setPointAllFieldsFast(const 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 ...
void resize(const size_t N)
Set number of points (to uninitialized values)
#define DECLARE_MEXPLUS_FROM(complete_type)
This must be inserted if a custom conversion method for MEX API is implemented in the class...
virtual double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
virtual mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() override
size_t size() const
Get number of points.
void base_copyFrom(const CPointsMap &obj)
Helper method for ::copyFrom()
const mrpt::aligned_std_vector< float > & getPointsBufferRef_y() const
Provides a direct access to a read-only reference of the internal point buffer.
virtual void setPointFast(size_t index, float x, float y, float z)=0
Changes the coordinates of the given point (0-based index), without checking for out-of-bounds and wi...
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
void loadFromVelodyneScan(const mrpt::obs::CObservationVelodyneScan &scan, const mrpt::poses::CPose3D *robotPose=nullptr)
Like loadFromRangeScan() for Velodyne 3D scans.
void getAllPoints(std::vector< mrpt::math::TPoint2D > &ps, size_t decimation=1) const
size_t kdtree_get_point_count() const
Must return the number of data points.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
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...
void getAllPoints(CONTAINER &ps, size_t decimation=1) const
Gets all points as a STL-like container.
virtual void getPointAllFieldsFast(const 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 ...
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 st...
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.
TInsertionOptions()
Initilization of default parameters.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
bool m_boundingBoxIsUpdated
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
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 ...
virtual void PLY_import_set_vertex(const 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...
GLsizei GLsizei GLuint * obj
float squareDistanceToClosestCorrespondenceT(const mrpt::math::TPoint2D &p0) const
size_t PLY_export_get_vertex_count() const override
In a base class, return the number of vertices.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
bool save3D_to_text_file(const std::string &file) const
Save to a text file.
virtual void getPoint(size_t index, float &x, float &y, float &z, float &R, float &G, float &B) const
Access to a given point from map, and its colors, if the map defines them (othersise, R=G=B=1.0).
GLubyte GLubyte GLubyte GLubyte w
Rendering options, used in getAs3DObject()
float maxDistForInterpolatePoints
The maximum distance between two points to interpolate between them (ONLY when also_interpolate=true)...
virtual void PLY_import_set_face_count(const size_t N) override
In a base class, reserve memory to prepare subsequent calls to PLY_import_set_face.
#define DEFINE_VIRTUAL_SERIALIZABLE(class_name)
This declaration must be inserted in virtual CSerializable classes definition:
bool kdtree_get_bbox(BBOX &bb) const
unsigned long getPoint(size_t index, mrpt::math::TPoint2D &p) const
mrpt::maps::CPointsMap & m_obj
A generic adaptor class for providing Nearest Neighbor (NN) lookup via the nanoflann library...
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 ...
bool isFilterByHeightEnabled() const
Return whether filter-by-height is enabled.
#define ASSERT_(f)
Defines an assertion mechanism.
With this struct options are provided to the observation insertion process.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
A numeric matrix of compile-time fixed size.
bool insertInvalidPoints
Points with x,y,z coordinates set to zero will also be inserted.
TLaserRange3DInsertContext(const mrpt::obs::CObservation3DRangeScan &_rangeScan)
This class allows loading and storing values and vectors of different types from a configuration text...
float kdtree_get_pt(const size_t idx, int dim) const
Returns the dim'th component of the idx'th point in the class:
An adapter to different kinds of point cloud object.
Lightweight 3D point (float version).
const mrpt::aligned_std_vector< float > & getPointsBufferRef_z() const
Provides a direct access to a read-only reference of the internal point buffer.
std::vector< unsigned int > uVars
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
double sigma_dist
Sigma squared (variance, in meters) of the exponential used to model the likelihood (default= 0...
#define DECLARE_MEX_CONVERSION
This must be inserted if a custom conversion method for MEX API is implemented in the class...
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.
A smart look-up-table (LUT) of sin/cos values for 2D laser scans.
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.
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
PointCloudAdapter(const mrpt::maps::CPointsMap &obj)
Constructor (accept a const ref for convenience)
void setPoint(size_t index, const mrpt::math::TPoint3D &p)
void getHeightFilterLevels(double &_z_min, double &_z_max) const
Get the min/max Z levels for points to be actually inserted in the map.
void setPoint(size_t index, float x, float y)
bool m_largestDistanceFromOriginIsUpdated
Auxiliary variables used in "getLargestDistanceFromOrigin".
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - used in derived classes' serialization.
void extractCylinder(const mrpt::math::TPoint2D ¢er, 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 valu...
float scan_x
In internal_loadFromRangeScan3D_prepareOneRange, these are the local coordinates of the scan points b...
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...
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - for usage in derived classes' serialization.
virtual const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const override
If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points ...
TLaserRange2DInsertContext(const mrpt::obs::CObservation2DRangeScan &_rangeScan)
std::vector< float > fVars
Extra variables to be used as desired by the derived class.
virtual void addFrom_classSpecific(const CPointsMap &anotherMap, const size_t nPreviousPoints)=0
Auxiliary method called from within addFrom() automatically, to finish the copying of class-specific ...
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 (Not...
double x
X,Y,Z coordinates.
void getPointXYZ(const size_t idx, T &x, T &y, T &z) const
Get XYZ coordinates of i'th point.
virtual bool savePCDFile(const std::string &filename, bool save_as_binary) const
Save the point cloud as a PCL PCD file, in either ASCII or binary format (requires MRPT built against...
A virtual base class that implements the capability of exporting 3D point clouds and faces to a file ...
bool load2D_from_text_file(const std::string &file)
Load from a text file.
void getPCLPointCloud(POINTCLOUD &cloud) const
Use to convert this MRPT point cloud object into a PCL point cloud object (PointCloud<PointXYZ>).
virtual bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
float getLargestDistanceFromOrigin() const
This method returns the largest distance from the origin to any of the points, such as a sphere cente...
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
float m_largestDistanceFromOrigin
Auxiliary variables used in "getLargestDistanceFromOrigin".
GLsizei const GLchar ** string
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.
std::vector< float > fVars
Extra variables to be used as desired by the derived class.
void clipOutOfRange(const mrpt::math::TPoint2D &point, float maxRange)
Delete points which are more far than "maxRange" away from the given "point".
virtual void setPoint(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)
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.
float coords_t
The type of each point XYZ coordinates.
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(...
virtual ~TLikelihoodOptions()
bool also_interpolate
If set to true, far points (<1m) are interpolated with samples at "minDistSqrBetweenLaserPoints" inte...
void clipOutOfRangeInZ(float zMin, float zMax)
Delete points out of the given "z" axis range have been removed.
mrpt::aligned_std_vector< float > m_z
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
mrpt::obs::CSinCosLookUpTableFor2DScans m_scans_sincos_cache
Cache of sin/cos values for the latest 2D scan geometries.
unsigned long getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
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 t...
void mark_as_modified() const
Users normally don't need to call this.
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 addToExistingPointsMap
Applicable to "loadFromRangeScan" only! If set to false, the points from the scan are loaded...
Virtual base class for "archives": classes abstracting I/O streams.
bool fuseWithExisting
If set to true (default=false), inserted points are "fused" with previously existent ones...
mrpt::aligned_std_vector< float > m_y
std::vector< uint8_t > bVars
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 ...
TLikelihoodOptions likelihoodOptions
bool load3D_from_text_file(const std::string &file)
Load from a text file.
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...
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.
TRenderOptions renderOptions
Declares a virtual base class for all metric maps storage classes.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Declares a class that represents any robot's observation.
Options used when evaluating "computeObservationLikelihood" in the derived classes.
unsigned long getPoint(size_t index, mrpt::math::TPoint3D &p) const
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams ¶ms) const override
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.
void kdtree_mark_as_outdated() const
To be called by child classes when KD tree data changes.
virtual void insertPoint(float x, float y, float z, float R, float G, float B)
overload (RGB data is ignored in classes without color information)
void setPoint(size_t index, const mrpt::math::TPoint2D &p)
A RGB color - floats in the range [0,1].
std::vector< uint8_t > bVars
float horizontalTolerance
The tolerance in rads in pitch & roll for a laser scan to be considered horizontal, considered only when isPlanarMap=true (default=0).
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const override
Computes the matching between this and another 2D point map, which includes finding: ...
GLsizei GLsizei GLchar * source
virtual bool loadPCDFile(const std::string &filename)
Load the point cloud from a PCL PCD file (requires MRPT built against PCL)
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - for usage in derived classes' serialization.
virtual ~CPointsMap()
Virtual destructor.
Helper struct used for internal_loadFromRangeScan3D_prepareOneRange()
TInsertionOptions insertionOptions
The options used when inserting observations in the map.
double max_corr_distance
Maximum distance in meters to consider for the numerator divided by "sigma_dist", so that each point ...
void enableFilterByHeight(bool enable=true)
Enable/disable the filter-by-height functionality.
A helper base class for those PointCloudAdapter<> which do not handle RGB data; it declares needed in...
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
virtual void insertPointFast(float x, float y, float z=0)=0
The virtual method for insertPoint() without calling mark_as_modified()
virtual void setSize(size_t newLength)=0
Resizes all point buffers so they can hold the given number of points, erasing all previous contents ...
virtual void determineMatching3D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const override
Computes the matchings between this and another 3D points map - method used in 3D-ICP.
virtual 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...
uint32_t decimation
Speed up the likelihood computation by considering only one out of N rays (default=10) ...
void extractPoints(const mrpt::math::TPoint3D &corner1, const mrpt::math::TPoint3D &corner2, CPointsMap *outMap, const double &R=1, const double &G=1, const double &B=1)
Extracts the points in the map within the area defined by two corners.
GLenum GLsizei GLsizei height
void setPointXYZ(const size_t idx, const coords_t x, const coords_t y, const coords_t z)
Set XYZ coordinates of i'th point.
const mrpt::aligned_std_vector< float > & getPointsBufferRef_x() const
Provides a direct access to a read-only reference of the internal point buffer.
Parameters for the determination of matchings between point clouds, etc.
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
unsigned __int32 uint32_t
mrpt::aligned_std_vector< float > m_x
The point coordinates.
size_t size() const
Returns the number of stored points in the map.
float getLargestDistanceFromOriginNoRecompute(bool &output_is_valid) const
Like getLargestDistanceFromOrigin() but returns in output_is_valid = false if the distance was not al...
bool disableDeletion
If set to false (default=true) points in the same plane as the inserted scan and inside the free spac...
GLenum const GLfloat * params
void boundingBox(mrpt::math::TPoint3D &pMin, mrpt::math::TPoint3D &pMax) const
virtual void PLY_export_get_vertex(const size_t idx, mrpt::math::TPoint3Df &pt, bool &pt_has_color, mrpt::img::TColorf &pt_color) const override
In a base class, will be called after PLY_export_get_vertex_count() once for each exported point...
void setDimensions(const size_t &height, const size_t &width)
Does nothing as of now.
void insertPoint(const mrpt::math::TPoint3D &p)
virtual bool hasColorPoints() const
Returns true if the point map has a color field for each point.
A virtual base class that implements the capability of importing 3D point clouds and faces from a fil...
Helper struct used for internal_loadFromRangeScan2D_prepareOneRange()
void applyDeletionMask(const std::vector< bool > &mask)
Remove from the map the points marked in a bool's array as "true".
double m_heightfilter_z_max
double m_heightfilter_z_min
The minimum and maximum height for a certain laser scan to be inserted into this map.
float minDistBetweenLaserPoints
The minimum distance between points (in 3D): If two points are too close, one of them is not inserted...
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
std::vector< unsigned int > uVars
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - for usage in derived classes' serialization.