Skip to content

Commit 8a24fd7

Browse files
committed
Progress simplifying CPointsMap API
1 parent 21ebd8a commit 8a24fd7

16 files changed

+82
-338
lines changed

libs/maps/include/mrpt/maps/CColouredPointsMap.h

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ class CColouredPointsMap : public CPointsMap
3434
public:
3535
CColouredPointsMap() = default;
3636

37-
CColouredPointsMap(const CPointsMap& o) { CPointsMap::operator=(o); }
37+
explicit CColouredPointsMap(const CPointsMap& o) { CPointsMap::operator=(o); }
3838
CColouredPointsMap(const CColouredPointsMap& o) : CPointsMap() { impl_copyFrom(o); }
3939
CColouredPointsMap& operator=(const CPointsMap& o)
4040
{
@@ -102,11 +102,6 @@ class CColouredPointsMap : public CPointsMap
102102
const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt) override;
103103

104104
protected:
105-
void addFrom_classSpecific(
106-
const CPointsMap& anotherMap,
107-
size_t nPreviousPoints,
108-
const bool filterOutPointsAtZero) override;
109-
110105
// Friend methods:
111106
template <class Derived>
112107
friend struct detail::loadFromRangeImpl;

libs/maps/include/mrpt/maps/CGenericPointsMap.h

Lines changed: 4 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -49,17 +49,11 @@ class CGenericPointsMap : public CPointsMap
4949
/** @name Register/unregister custom data fields
5050
@{ */
5151

52-
/** Registers a new data channel of type `float`.
53-
* If the map is not empty, the new channel is filled with default values (0)
54-
* to match the current point count.
55-
*/
56-
void registerField_float(const std::string& fieldName);
52+
// see docs in parent class
53+
bool registerField_float(const std::string& fieldName) override;
5754

58-
/** Registers a new data channel of type `uint16_t`.
59-
* If the map is not empty, the new channel is filled with default values (0)
60-
* to match the current point count.
61-
*/
62-
void registerField_uint16(const std::string& fieldName);
55+
// see docs in parent class
56+
bool registerField_uint16(const std::string& fieldName) override;
6357

6458
/** Removes a data channel.
6559
* \return True if the field existed and was removed, false otherwise.
@@ -199,12 +193,6 @@ class CGenericPointsMap : public CPointsMap
199193
/** Map from field name to data vector */
200194
std::map<std::string, mrpt::aligned_std_vector<uint16_t>> m_uint16_fields;
201195

202-
// See base class
203-
void addFrom_classSpecific(
204-
const CPointsMap& anotherMap,
205-
size_t nPreviousPoints,
206-
const bool filterOutPointsAtZero) override;
207-
208196
/** Clear the map, erasing all the points and all fields */
209197
void internal_clear() override;
210198

libs/maps/include/mrpt/maps/CPointsMap.h

Lines changed: 53 additions & 42 deletions
Original file line numberDiff line numberDiff line change
@@ -199,14 +199,13 @@ class CPointsMap :
199199
const size_t N = obj.size();
200200
this->clear();
201201
this->reserve(N);
202-
for (size_t i = 0; i < N; i++) insertPointFrom(obj, i);
202+
this->registerPointFieldsFrom(obj);
203+
for (size_t i = 0; i < N; i++)
204+
{
205+
insertPointFrom(obj, i);
206+
}
203207
}
204208

205-
/** Auxiliary method called from within \a addFrom() automatically, to
206-
* finish the copying of class-specific data */
207-
virtual void addFrom_classSpecific(
208-
const CPointsMap& anotherMap, size_t nPreviousPoints, const bool filterOutPointsAtZero) = 0;
209-
210209
public:
211210
/** @} */
212211
// --------------------------------------------
@@ -357,6 +356,30 @@ class CPointsMap :
357356
insertAnotherMap(&anotherMap, mrpt::poses::CPose3D::Identity());
358357
}
359358

359+
/** @name Register/unregister custom data fields
360+
@{ */
361+
362+
/** Registers a new data channel of type `float`.
363+
* If the map is not empty, the new channel is filled with default values (0)
364+
* to match the current point count.
365+
* \return true if the field could effectively be added to the underlying point map class.
366+
* \sa hasPointField(), getPointFieldNames_float()
367+
*/
368+
virtual bool registerField_float(const std::string& fieldName)
369+
{
370+
return fieldName == "x" || fieldName == "y" || fieldName == "z";
371+
}
372+
373+
/** Registers a new data channel of type `uint16_t`.
374+
* If the map is not empty, the new channel is filled with default values (0)
375+
* to match the current point count.
376+
* \return true if the field could effectively be added to the underlying point map class.
377+
* \sa hasPointField(), getPointFieldNames_uint16()
378+
*/
379+
virtual bool registerField_uint16(const std::string& fieldName) { return false; }
380+
381+
/** @} */
382+
360383
// --------------------------------------------------
361384
/** @name File input/output methods
362385
@{ */
@@ -745,16 +768,34 @@ class CPointsMap :
745768
}
746769

747770
/** Must be called before insertPointFrom() to make sure we have the required fields.
771+
* \return true if ALL fields could be added, false if some would be missing because the
772+
* underlying point cloud class cannot hold them.
748773
*/
749-
void copyPointFieldsFrom(const mrpt::maps::CPointsMap& source)
774+
bool registerPointFieldsFrom(const mrpt::maps::CPointsMap& source)
750775
{
751-
//
752-
xx;
776+
bool allAdded = true;
777+
for (const auto& f : source.getPointFieldNames_float())
778+
{
779+
if (!this->hasPointField(f))
780+
{
781+
const bool added = registerField_float(f);
782+
allAdded = allAdded && added;
783+
}
784+
}
785+
for (const auto& f : source.getPointFieldNames_uint16())
786+
{
787+
if (!this->hasPointField(f))
788+
{
789+
const bool added = this->registerField_uint16(f);
790+
allAdded = allAdded && added;
791+
}
792+
}
793+
return allAdded;
753794
}
754795

755796
/** Generic method to copy *all* applicable point properties from
756797
* one map to another, e.g. timestamp, intensity, etc.
757-
* \note Before calling this in a loop, make sure of calling copyPointFieldsFrom()
798+
* \note Before calling this in a loop, make sure of calling registerPointFieldsFrom()
758799
*/
759800
void insertPointFrom(const mrpt::maps::CPointsMap& source, size_t sourcePointIndex)
760801
{
@@ -768,11 +809,11 @@ class CPointsMap :
768809
// Optional fields: only if they already exist on both maps:
769810
for (const auto& f : this->getPointFieldNames_float())
770811
{
771-
insertPointField_float(f, this->getPointField_float(i, f));
812+
insertPointField_float(f, source.getPointField_float(i, f));
772813
}
773814
for (const auto& f : this->getPointFieldNames_uint16())
774815
{
775-
insertPointField_uint16(f, this->getPointField_uint16(i, f));
816+
insertPointField_uint16(f, source.getPointField_uint16(i, f));
776817
}
777818
mark_as_modified();
778819
}
@@ -1009,22 +1050,6 @@ class CPointsMap :
10091050
*/
10101051
void getVisualizationInto(mrpt::opengl::CSetOfObjects& outObj) const override;
10111052

1012-
/** This method returns the largest distance from the origin to any of the
1013-
* points, such as a sphere centered at the origin with this radius cover
1014-
* ALL the points in the map (the results are buffered, such as, if the map
1015-
* is not modified, the second call will be much faster than the first one).
1016-
*/
1017-
float getLargestDistanceFromOrigin() const;
1018-
1019-
/** Like \a getLargestDistanceFromOrigin() but returns in \a output_is_valid
1020-
* = false if the distance was not already computed, skipping its
1021-
* computation then, unlike getLargestDistanceFromOrigin() */
1022-
float getLargestDistanceFromOriginNoRecompute(bool& output_is_valid) const
1023-
{
1024-
output_is_valid = m_largestDistanceFromOriginIsUpdated;
1025-
return m_largestDistanceFromOrigin;
1026-
}
1027-
10281053
/** Computes the bounding box of all the points, or (0,0 ,0,0, 0,0) if there
10291054
* are no points.
10301055
* Results are cached unless the map is somehow modified to avoid repeated
@@ -1212,7 +1237,6 @@ class CPointsMap :
12121237
* kd-tree cache, and such. */
12131238
inline void mark_as_modified() const
12141239
{
1215-
m_largestDistanceFromOriginIsUpdated = false;
12161240
m_boundingBoxIsUpdated = false;
12171241
kdtree_mark_as_outdated();
12181242
}
@@ -1277,16 +1301,6 @@ class CPointsMap :
12771301
/** Cache of sin/cos values for the latest 2D scan geometries. */
12781302
mrpt::obs::CSinCosLookUpTableFor2DScans m_scans_sincos_cache;
12791303

1280-
/** Auxiliary variables used in "getLargestDistanceFromOrigin"
1281-
* \sa getLargestDistanceFromOrigin
1282-
*/
1283-
mutable float m_largestDistanceFromOrigin{0};
1284-
1285-
/** Auxiliary variables used in "getLargestDistanceFromOrigin"
1286-
* \sa getLargestDistanceFromOrigin
1287-
*/
1288-
mutable bool m_largestDistanceFromOriginIsUpdated;
1289-
12901304
mutable bool m_boundingBoxIsUpdated;
12911305
mutable mrpt::math::TBoundingBoxf m_boundingBox;
12921306

@@ -1300,9 +1314,6 @@ class CPointsMap :
13001314
const mrpt::obs::CObservation& obs,
13011315
const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt) override;
13021316

1303-
/** Helper method for ::copyFrom() */
1304-
void base_copyFrom(const CPointsMap& obj);
1305-
13061317
/** @name PLY Import virtual methods to implement in base classes
13071318
@{ */
13081319
/** In a base class, reserve memory to prepare subsequent calls to

libs/maps/include/mrpt/maps/CPointsMapXYZI.h

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -99,12 +99,6 @@ class CPointsMapXYZI : public CPointsMap
9999
const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt) override;
100100

101101
protected:
102-
// See base class
103-
void addFrom_classSpecific(
104-
const CPointsMap& anotherMap,
105-
size_t nPreviousPoints,
106-
const bool filterOutPointsAtZero) override;
107-
108102
// Friend methods:
109103
template <class Derived>
110104
friend struct detail::loadFromRangeImpl;

libs/maps/include/mrpt/maps/CPointsMapXYZIRT.h

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,6 @@
1515

1616
namespace mrpt::maps
1717
{
18-
class CPointsMapXYZI;
19-
2018
/** A map of 3D points with channels: X,Y,Z,I (intensity), R (ring), T (time).
2119
*
2220
* - `ring` (`uint16_t`) holds the "ring number", or the "row index" for
@@ -44,10 +42,8 @@ class CPointsMapXYZIRT : public CPointsMap
4442

4543
explicit CPointsMapXYZIRT(const CPointsMap& o) { CPointsMap::operator=(o); }
4644
CPointsMapXYZIRT(const CPointsMapXYZIRT& o);
47-
explicit CPointsMapXYZIRT(const CPointsMapXYZI& o);
4845
CPointsMapXYZIRT& operator=(const CPointsMap& o);
4946
CPointsMapXYZIRT& operator=(const CPointsMapXYZIRT& o);
50-
CPointsMapXYZIRT& operator=(const CPointsMapXYZI& o);
5147

5248
/** @name Pure virtual interfaces to be implemented by any class derived from CPointsMap
5349
@{ */
@@ -118,12 +114,6 @@ class CPointsMapXYZIRT : public CPointsMap
118114
const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt) override;
119115

120116
protected:
121-
// See base class
122-
void addFrom_classSpecific(
123-
const CPointsMap& anotherMap,
124-
size_t nPreviousPoints,
125-
const bool filterOutPointsAtZero) override;
126-
127117
// Friend methods:
128118
template <class Derived>
129119
friend struct detail::loadFromRangeImpl;

libs/maps/include/mrpt/maps/CSimplePointsMap.h

Lines changed: 1 addition & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ class CSimplePointsMap : public CPointsMap
3434
public:
3535
/** Default constructor */
3636
CSimplePointsMap() = default;
37-
CSimplePointsMap(const CPointsMap& o) { CPointsMap::operator=(o); }
37+
explicit CSimplePointsMap(const CPointsMap& o) { CPointsMap::operator=(o); }
3838
CSimplePointsMap(const CSimplePointsMap& o) : CPointsMap() { CPointsMap::operator=(o); }
3939
CSimplePointsMap& operator=(const CPointsMap& o)
4040
{
@@ -92,14 +92,6 @@ class CSimplePointsMap : public CPointsMap
9292
const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt) override;
9393

9494
protected:
95-
void addFrom_classSpecific(
96-
[[maybe_unused]] const CPointsMap& anotherMap,
97-
[[maybe_unused]] size_t nPreviousPoints,
98-
[[maybe_unused]] const bool filterOutPointsAtZero) override
99-
{
100-
// No extra data.
101-
}
102-
10395
// Friend methods:
10496
template <class Derived>
10597
friend struct detail::loadFromRangeImpl;

libs/maps/include/mrpt/maps/CWeightedPointsMap.h

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ class CWeightedPointsMap : public CPointsMap
3333
public:
3434
/** Default constructor */
3535
CWeightedPointsMap() = default;
36-
CWeightedPointsMap(const CPointsMap& o) { impl_copyFrom(o); }
36+
explicit CWeightedPointsMap(const CPointsMap& o) { impl_copyFrom(o); }
3737
CWeightedPointsMap(const CWeightedPointsMap& o) : CPointsMap() { impl_copyFrom(o); }
3838
CWeightedPointsMap& operator=(const CPointsMap& o)
3939
{
@@ -97,11 +97,6 @@ class CWeightedPointsMap : public CPointsMap
9797
const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt) override;
9898

9999
protected:
100-
void addFrom_classSpecific(
101-
const CPointsMap& anotherMap,
102-
size_t nPreviousPoints,
103-
const bool filterOutPointsAtZero) override;
104-
105100
// Friend methods:
106101
template <class Derived>
107102
friend struct detail::loadFromRangeImpl;

libs/maps/src/maps/CColouredPointsMap.cpp

Lines changed: 0 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -577,33 +577,6 @@ void CColouredPointsMap::PLY_export_get_vertex(
577577
pt_color.B = m_color_B[idx];
578578
}
579579

580-
/*---------------------------------------------------------------
581-
addFrom_classSpecific
582-
---------------------------------------------------------------*/
583-
void CColouredPointsMap::addFrom_classSpecific(
584-
const CPointsMap& anotherMap, size_t nPreviousPoints, const bool filterOutPointsAtZero)
585-
{
586-
const size_t nOther = anotherMap.size();
587-
588-
// Specific data for this class:
589-
const auto* anotheMap_col = dynamic_cast<const CColouredPointsMap*>(&anotherMap);
590-
591-
if (anotheMap_col)
592-
{
593-
for (size_t i = 0, j = nPreviousPoints; i < nOther; i++)
594-
{
595-
if (filterOutPointsAtZero && anotheMap_col->m_x[i] == 0 && anotheMap_col->m_y[i] == 0 &&
596-
anotheMap_col->m_z[i] == 0)
597-
continue; // skip
598-
599-
m_color_R[j] = anotheMap_col->m_color_R[i];
600-
m_color_G[j] = anotheMap_col->m_color_G[i];
601-
m_color_B[j] = anotheMap_col->m_color_B[i];
602-
j++;
603-
}
604-
}
605-
}
606-
607580
namespace mrpt::maps::detail
608581
{
609582
using mrpt::maps::CColouredPointsMap;

0 commit comments

Comments
 (0)