Skip to content

Commit 959303f

Browse files
committed
Progress import from develop
1 parent 025af2d commit 959303f

17 files changed

+1033
-343
lines changed

modules/mrpt_maps/include/mrpt/maps/CGenericPointsMap.h

Lines changed: 21 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,17 @@
1-
/* +------------------------------------------------------------------------+
2-
| Mobile Robot Programming Toolkit (MRPT) |
3-
| https://www.mrpt.org/ |
4-
| |
5-
| Copyright (c) 2005-2024, Individual contributors, see AUTHORS file |
6-
| See: https://www.mrpt.org/Authors - All rights reserved. |
7-
| Released under BSD License. See: https://www.mrpt.org/License |
8-
+------------------------------------------------------------------------+ */
1+
/* _
2+
| | Mobile Robot Programming Toolkit (MRPT)
3+
_ __ ___ _ __ _ __ | |_
4+
| '_ ` _ \| '__| '_ \| __| https://www.mrpt.org/
5+
| | | | | | | | |_) | |_
6+
|_| |_| |_|_| | .__/ \__| https://github.com/MRPT/mrpt/
7+
| |
8+
|_|
9+
10+
Copyright (c) 2005-2025, Individual contributors, see AUTHORS file
11+
See: https://www.mrpt.org/Authors - All rights reserved.
12+
SPDX-License-Identifier: BSD-3-Clause
13+
*/
14+
915
#pragma once
1016

1117
#include <mrpt/core/aligned_std_vector.h>
@@ -14,7 +20,8 @@
1420
#include <mrpt/opengl/pointcloud_adapters.h>
1521
#include <mrpt/serialization/CSerializable.h>
1622

17-
#include <map>
23+
#include <string_view>
24+
#include <unordered_map>
1825

1926
namespace mrpt::maps
2027
{
@@ -61,12 +68,13 @@ class CGenericPointsMap : public CPointsMap
6168
bool unregisterField(const std::string_view& fieldName);
6269

6370
/** Returns the map of float fields: map<field_name, vector_of_data> */
64-
const std::map<std::string_view, mrpt::aligned_std_vector<float>>& float_fields() const
71+
const std::unordered_map<std::string_view, mrpt::aligned_std_vector<float>>& float_fields() const
6572
{
6673
return m_float_fields;
6774
}
6875
/** Returns the map of uint16_t fields: map<field_name, vector_of_data> */
69-
const std::map<std::string_view, mrpt::aligned_std_vector<uint16_t>>& uint16_fields() const
76+
const std::unordered_map<std::string_view, mrpt::aligned_std_vector<uint16_t>>& uint16_fields()
77+
const
7078
{
7179
return m_uint16_fields;
7280
}
@@ -80,12 +88,6 @@ class CGenericPointsMap : public CPointsMap
8088
void resize(size_t newLength) override;
8189
void setSize(size_t newLength) override;
8290

83-
/** Inserts a new point (X,Y,Z).
84-
* You **must** call `insertPointField_float()` or `insertPointField_uint16()`
85-
* *after* this for each registered field to keep data vectors synchronized.
86-
*/
87-
void insertPointFast(float x, float y, float z = 0) override;
88-
8991
void getPointAllFieldsFast(size_t index, std::vector<float>& point_data) const override;
9092
void setPointAllFieldsFast(size_t index, const std::vector<float>& point_data) override;
9193

@@ -190,9 +192,9 @@ class CGenericPointsMap : public CPointsMap
190192

191193
protected:
192194
/** Map from field name to data vector */
193-
std::map<std::string_view, mrpt::aligned_std_vector<float>> m_float_fields;
195+
std::unordered_map<std::string_view, mrpt::aligned_std_vector<float>> m_float_fields;
194196
/** Map from field name to data vector */
195-
std::map<std::string_view, mrpt::aligned_std_vector<uint16_t>> m_uint16_fields;
197+
std::unordered_map<std::string_view, mrpt::aligned_std_vector<uint16_t>> m_uint16_fields;
196198

197199
/** Clear the map, erasing all the points and all fields */
198200
void internal_clear() override;

modules/mrpt_maps/src/maps/CColouredOctoMap.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -95,7 +95,7 @@ void CColouredOctoMap::serializeTo(mrpt::serialization::CArchive& out) const
9595
out << genericMapParams; // v2
9696

9797
// v2->v3: remove CMemoryChunk
98-
std::stringstream ss;
98+
std::stringstream ss(std::ios::in | std::ios::out | std::ios::binary);
9999
m_impl->m_octomap.writeBinaryConst(ss);
100100
const std::string& buf = ss.str();
101101
out << buf;
@@ -127,7 +127,7 @@ void CColouredOctoMap::serializeFrom(mrpt::serialization::CArchive& in, uint8_t
127127

128128
if (!buf.empty())
129129
{
130-
std::stringstream ss;
130+
std::stringstream ss(std::ios::in | std::ios::out | std::ios::binary);
131131
ss.str(buf);
132132
ss.seekg(0);
133133
m_impl->m_octomap.readBinary(ss);

modules/mrpt_maps/src/maps/CColouredPointsMap.cpp

Lines changed: 14 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,17 @@
1-
/* +------------------------------------------------------------------------+
2-
| Mobile Robot Programming Toolkit (MRPT) |
3-
| https://www.mrpt.org/ |
4-
| |
5-
| Copyright (c) 2005-2025, Individual contributors, see AUTHORS file |
6-
| See: https://www.mrpt.org/Authors - All rights reserved. |
7-
| Released under BSD License. See: https://www.mrpt.org/License |
8-
+------------------------------------------------------------------------+ */
9-
10-
#include "maps-precomp.h" // Precomp header
11-
//
12-
#include <mrpt/core/bits_mem.h>
13-
#include <mrpt/img/color_maps.h>
1+
/* _
2+
| | Mobile Robot Programming Toolkit (MRPT)
3+
_ __ ___ _ __ _ __ | |_
4+
| '_ ` _ \| '__| '_ \| __| https://www.mrpt.org/
5+
| | | | | | | | |_) | |_
6+
|_| |_| |_|_| | .__/ \__| https://github.com/MRPT/mrpt/
7+
| |
8+
|_|
9+
10+
Copyright (c) 2005-2025, Individual contributors, see AUTHORS file
11+
See: https://www.mrpt.org/Authors - All rights reserved.
12+
SPDX-License-Identifier: BSD-3-Clause
13+
*/
14+
1415
#include <mrpt/maps/CColouredPointsMap.h>
1516
#include <mrpt/maps/CSimplePointsMap.h>
1617
#include <mrpt/obs/CObservation3DRangeScan.h>
@@ -567,33 +568,6 @@ void CColouredPointsMap::PLY_export_get_vertex(
567568
pt_color.B = m_color_B[idx];
568569
}
569570

570-
/*---------------------------------------------------------------
571-
addFrom_classSpecific
572-
---------------------------------------------------------------*/
573-
void CColouredPointsMap::addFrom_classSpecific(
574-
const CPointsMap& anotherMap, size_t nPreviousPoints, const bool filterOutPointsAtZero)
575-
{
576-
const size_t nOther = anotherMap.size();
577-
578-
// Specific data for this class:
579-
const auto* anotheMap_col = dynamic_cast<const CColouredPointsMap*>(&anotherMap);
580-
581-
if (anotheMap_col)
582-
{
583-
for (size_t i = 0, j = nPreviousPoints; i < nOther; i++)
584-
{
585-
if (filterOutPointsAtZero && anotheMap_col->m_x[i] == 0 && anotheMap_col->m_y[i] == 0 &&
586-
anotheMap_col->m_z[i] == 0)
587-
continue; // skip
588-
589-
m_color_R[j] = anotheMap_col->m_color_R[i];
590-
m_color_G[j] = anotheMap_col->m_color_G[i];
591-
m_color_B[j] = anotheMap_col->m_color_B[i];
592-
j++;
593-
}
594-
}
595-
}
596-
597571
namespace mrpt::maps::detail
598572
{
599573
using mrpt::maps::CColouredPointsMap;

0 commit comments

Comments
 (0)