Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ endif()
add_subdirectory(3rdparty)

# find dependencies:
find_package(MRPT 2.15.0 REQUIRED COMPONENTS
find_package(MRPT 2.15.4 REQUIRED COMPONENTS
containers
tfest
maps
Expand Down
4 changes: 2 additions & 2 deletions agents.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ Quick-start reference for AI agents and new contributors.
- **Version**: 2.7.1 (March 2026)
- **License**: BSD-3-Clause
- **Maintainer**: Jose Luis Blanco-Claraco
- **Minimum MRPT**: 2.15.0
- **Minimum MRPT**: 2.15.4

---

Expand Down Expand Up @@ -172,7 +172,7 @@ SIMD-optimized translation units are compiled separately with `-mavx` / `-msse2`

| Dependency | Notes |
|-----------|-------|
| MRPT ≥ 2.15.0 | containers, tfest, maps, gui, topography — mandatory |
| MRPT ≥ 2.15.4 | containers, tfest, maps, gui, topography — mandatory |
| TBB | Optional; enables parallel ICP iterations |
| mola_common | CMake scripts; fetched as git submodule |
| mola_imu_preintegration | Optional; advanced deskew in FilterDeskew |
Expand Down
21 changes: 2 additions & 19 deletions apps/txt2mm/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,20 +21,13 @@

#include <mp2p_icp/metricmap.h>
#include <mrpt/3rdparty/tclap/CmdLine.h>
#include <mrpt/maps/CGenericPointsMap.h>
#include <mrpt/maps/CSimplePointsMap.h>
#include <mrpt/math/CMatrixDynamic.h>
#include <mrpt/obs/CObservationPointCloud.h>
#include <mrpt/system/filesystem.h>
#include <mrpt/version.h>

#if MRPT_VERSION >= 0x20f00 // 2.15.0
#include <mrpt/maps/CGenericPointsMap.h>
#else
#include <mrpt/maps/CColouredPointsMap.h>
#include <mrpt/maps/CPointsMapXYZI.h>
#include <mrpt/maps/CPointsMapXYZIRT.h>
#endif

const char* VALID_FORMATS = "(xyz|xyzi|xyzirt|xyzrgb|xyzrgb_normalized)";

// Replicated here from CGenericPointsMap until MRPT 2.15.3 is minimum required version:
Expand Down Expand Up @@ -214,14 +207,10 @@ int main(int argc, char** argv)
{
ASSERT_GE_(nCols, 6U);
const bool rgb_normalized = (format == "xyzrgb_normalized");
#if MRPT_VERSION >= 0x20f00 // 2.15.0
auto pts = mrpt::maps::CGenericPointsMap::Create();
auto pts = mrpt::maps::CGenericPointsMap::Create();
pts->registerField_float("color_r");
pts->registerField_float("color_g");
pts->registerField_float("color_b");
#else
auto pts = mrpt::maps::CColouredPointsMap::Create();
#endif
pts->reserve(nRows);
if (nCols > 6)
{
Expand Down Expand Up @@ -250,15 +239,9 @@ int main(int argc, char** argv)
b_val = mrpt::u8tof(static_cast<uint8_t>(data(i, idxBlue)));
}

#if MRPT_VERSION >= 0x20f00 // 2.15.0
pts->insertPointField_float("color_r", r_val);
pts->insertPointField_float("color_g", g_val);
pts->insertPointField_float("color_b", b_val);
#else
pts->insertPointField_color_R(r_val);
pts->insertPointField_color_G(g_val);
pts->insertPointField_color_B(b_val);
#endif
}

pc = pts;
Expand Down
1 change: 1 addition & 0 deletions demos/sm2mm_bonxai_voxelmap.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ generators:
throw_on_unhandled_observation_class: true
process_class_names_regex: ".*"
#process_sensor_labels_regex: '.*'
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans

# --------------------------------------------------------
# 2) Per local frame filtering
Expand Down
1 change: 1 addition & 0 deletions demos/sm2mm_bonxai_voxelmap_gridmap.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ generators:
throw_on_unhandled_observation_class: true
process_class_names_regex: ".*"
#process_sensor_labels_regex: '.*'
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans

# --------------------------------------------------------
# 2) Per local frame filtering
Expand Down
1 change: 1 addition & 0 deletions demos/sm2mm_bonxai_voxelmap_gridmap_no_deskew.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ generators:
throw_on_unhandled_observation_class: true
process_class_names_regex: ".*"
#process_sensor_labels_regex: '.*'
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans

# --------------------------------------------------------
# 2) Per local frame filtering
Expand Down
10 changes: 5 additions & 5 deletions demos/sm2mm_no_decim_imu.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,18 @@
# See: https://github.com/MOLAorg/mp2p_icp/tree/develop/apps/sm2mm
#
# Explanation of this particular pipeline:
# - Generators: empty, so the default generator is used (everything in one
# layer named 'raw' with all points).
# - Generators: default generator is used (creates an 'raw' layer).
# - Filters: Deskew using IMU, remove close points.
# - Final filters: intensity normalization.
# -----------------------------------------------------------------------------

# --------------------------------------------------------
# 1) Generator (observation -> local frame metric maps)
# --------------------------------------------------------
#generators:
# - class_name: mp2p_icp_filters::Generator
# params: ~
generators:
- class_name: mp2p_icp_filters::Generator
params:
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans
Comment thread
jlblancoc marked this conversation as resolved.

# --------------------------------------------------------
# 2) Per local frame filtering
Expand Down
4 changes: 2 additions & 2 deletions demos/sm2mm_no_decim_imu_mls.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,7 @@
# See: https://github.com/MOLAorg/mp2p_icp/tree/develop/apps/sm2mm
#
# Explanation of this particular pipeline:
# - Generators: empty, so the default generator is used (everything in one
# layer named 'raw' with all points).
# - Generators: default generator is used (creates an 'raw' layer).
# - Filters: Deskew using IMU, remove close points.
# - Final filters: intensity normalization, MLS filtering.
# -----------------------------------------------------------------------------
Expand All @@ -17,6 +16,7 @@ generators:
- class_name: mp2p_icp_filters::Generator
params:
generate_view_vector: true # Generate "view" vectors for advanced normals handling (Default=true)
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans

# --------------------------------------------------------
# 2) Per local frame filtering
Expand Down
1 change: 1 addition & 0 deletions demos/sm2mm_no_decim_imu_mls_keyframe_map.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ generators:
- class_name: mp2p_icp_filters::Generator
params:
name: "generator_default"
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans

# This one will just create the layer "localmap", expected by the GICP LIO algorithm for localization
- class_name: mp2p_icp_filters::Generator
Expand Down
10 changes: 5 additions & 5 deletions demos/sm2mm_pointcloud_voxelize.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,18 @@
# See: https://github.com/MOLAorg/mp2p_icp/tree/develop/apps/sm2mm
#
# Explanation of this particular pipeline:
# - Generators: empty, so the default generator is used (everything in one
# layer named 'raw' with all points).
# - Generators: default generator is used (creates an 'raw' layer).
# - Filters: Just one downsampling filter, with an additional removal of close
# points (e.g. the robot body)
# -----------------------------------------------------------------------------

# --------------------------------------------------------
# 1) Generator (observation -> local frame metric maps)
# --------------------------------------------------------
#generators:
# - class_name: mp2p_icp_filters::Generator
# params: ~
generators:
- class_name: mp2p_icp_filters::Generator
params:
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans
Comment thread
jlblancoc marked this conversation as resolved.

# --------------------------------------------------------
# 2) Per local frame filtering
Expand Down
10 changes: 5 additions & 5 deletions demos/sm2mm_pointcloud_voxelize_no_deskew.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,18 @@
# See: https://github.com/MOLAorg/mp2p_icp/tree/develop/apps/sm2mm
#
# Explanation of this particular pipeline:
# - Generators: empty, so the default generator is used (everything in one
# layer named 'raw' with all points).
# - Generators: default generator is used (creates an 'raw' layer).
# - Filters: Just one downsampling filter, with an additional removal of close
# points (e.g. the robot body)
# -----------------------------------------------------------------------------

# --------------------------------------------------------
# 1) Generator (observation -> local frame metric maps)
# --------------------------------------------------------
#generators:
# - class_name: mp2p_icp_filters::Generator
# params: ~
generators:
- class_name: mp2p_icp_filters::Generator
params:
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans

# --------------------------------------------------------
# 2) Per local frame filtering
Expand Down
1 change: 1 addition & 0 deletions demos/sm2mm_voxels_static_dynamic_points.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@ generators:
throw_on_unhandled_observation_class: true
process_class_names_regex: "(mrpt::obs::CObservationPointCloud|mrpt::obs::CObservation3DRangeScan|mrpt::obs::CObservation2DRangeScan)"
process_sensor_labels_regex: ".*"
filterOutPointsAtZero: true # Remove invalid points in 'organized' LiDAR scans
metric_map_definition:
# Any class derived from mrpt::maps::CMetricMap https://docs.mrpt.org/reference/latest/group_mrpt_maps_grp.html
class: mrpt::maps::CGenericPointsMap
Expand Down
4 changes: 2 additions & 2 deletions mp2p_icp_filters/include/mp2p_icp_filters/FilterDeskew.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,8 @@ enum class MotionCompensationMethod : uint8_t
* reference time point, which can be the start or middle point of the scan. This can be
* controlled by adding a FilterAdjustTimestamps before this block.
*
* - The input layer must contain a point cloud in the format
* mrpt::maps::CPointsMapXYZIRT or mrpt::maps::CGenericPointsMap so timestamps are present.
* - The input layer must contain a point cloud of type mrpt::maps::CGenericPointsMap
* so timestamps are present.
Comment thread
jlblancoc marked this conversation as resolved.
*
* - If the input layer is of a different type, or the `t` field is missing,
* an exception will be thrown by default, unless the option
Expand Down
14 changes: 14 additions & 0 deletions mp2p_icp_filters/include/mp2p_icp_filters/Generator.h
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,20 @@ class Generator : public mrpt::rtti::CObject, // RTTI support
*/
bool generate_view_vector = true;

/** When processing mrpt::obs::CObservationPointCloud as inputs, this will be the class of
* the generated layer, in which the cloud will be later inserted.
* Set to empty means use the same class as the original cloud in the observation.
* Default is to use the modern CGenericPointsMap which is capable of arbitrary point cloud
* fields.
*/
std::string default_pointcloud_class = "mrpt::maps::CGenericPointsMap";

/** When processing mrpt::obs::CObservationPointCloud as inputs, this controls whether
* points with (x,y,z)=(0,0,0) should be discarded as invalid ones; e.g. typical in
* organized clouds from LiDAR sensors.
*/
bool filterOutPointsAtZero = false;

/** If not empty, it will be used instead of class name in Logger and Profiler.
* This is loaded from the `name` key in the YAML configuration block.
*/
Expand Down
4 changes: 0 additions & 4 deletions mp2p_icp_filters/src/FilterAdjustTimestamps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,11 +82,7 @@ void FilterAdjustTimestamps::filter(mp2p_icp::metric_map_t& inOut) const
return;
}

#if MRPT_VERSION >= 0x020f00 // 2.15.0
auto* TsPtr = pc.getPointsBufferRef_float_field("t");
#else
auto* TsPtr = pc.getPointsBufferRef_timestamp();
#endif

if (TsPtr == nullptr || (TsPtr->empty() && !pc.empty()))
{
Expand Down
15 changes: 4 additions & 11 deletions mp2p_icp_filters/src/FilterBoundingBox.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
* @date Sep 10, 2021
*/

#include <mp2p_icp/pointcloud_field_utils.h>
#include <mp2p_icp_filters/FilterBoundingBox.h>
#include <mp2p_icp_filters/GetOrCreatePointLayer.h>
#include <mrpt/containers/yaml.h>
Expand Down Expand Up @@ -106,19 +107,19 @@ void FilterBoundingBox::filter(mp2p_icp::metric_map_t& inOut) const
outsidePc->reserve(outsidePc->size() + pc.size() / 10);
}

#if MRPT_VERSION >= 0x020f00 // 2.15.0
mrpt::maps::CPointsMap::InsertCtx ctxOutside, ctxInside;
if (insidePc)
{
insidePc->registerPointFieldsFrom(pc);
ctxInside = insidePc->prepareForInsertPointsFrom(pc);
mp2p_icp::warn_on_field_padding_mismatch(pc, *insidePc, *this);
}
if (outsidePc)
{
outsidePc->registerPointFieldsFrom(pc);
ctxOutside = outsidePc->prepareForInsertPointsFrom(pc);
mp2p_icp::warn_on_field_padding_mismatch(pc, *outsidePc, *this);
}
#endif

const auto& xs = pc.getPointsBufferRef_x();
const auto& ys = pc.getPointsBufferRef_y();
Expand All @@ -129,18 +130,10 @@ void FilterBoundingBox::filter(mp2p_icp::metric_map_t& inOut) const
const bool isInside = params.bounding_box.containsPoint({xs[i], ys[i], zs[i]});

auto* targetPc = isInside ? insidePc.get() : outsidePc.get();
#if MRPT_VERSION >= 0x020f00 // 2.15.0
auto* ctx = isInside ? &ctxInside : &ctxOutside;
#endif
auto* ctx = isInside ? &ctxInside : &ctxOutside;
if (targetPc)
{
#if MRPT_VERSION >= 0x020f03 // 2.15.3
targetPc->insertPointFrom(i, *ctx);
#elif MRPT_VERSION >= 0x020f00 // 2.15.0
targetPc->insertPointFrom(pc, i, *ctx);
#else
targetPc->insertPointFrom(pc, i);
#endif
}
}

Expand Down
16 changes: 0 additions & 16 deletions mp2p_icp_filters/src/FilterByIntensity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,6 @@ void FilterByIntensity::filter(mp2p_icp::metric_map_t& inOut) const
ASSERT_EQUAL_(Is.size(), xs.size());
const size_t N = xs.size();

#if MRPT_VERSION >= 0x020f00 // 2.15.0
mrpt::maps::CPointsMap::InsertCtx ctxLow, ctxHigh, ctxMid;
if (outLow)
{
Expand All @@ -143,7 +142,6 @@ void FilterByIntensity::filter(mp2p_icp::metric_map_t& inOut) const
outMid->registerPointFieldsFrom(pc);
ctxMid = outMid->prepareForInsertPointsFrom(pc);
}
#endif

size_t countLow = 0, countMid = 0, countHigh = 0;

Expand All @@ -153,43 +151,29 @@ void FilterByIntensity::filter(mp2p_icp::metric_map_t& inOut) const

mrpt::maps::CPointsMap* trg = nullptr;

#if MRPT_VERSION >= 0x020f00 // 2.15.0
mrpt::maps::CPointsMap::InsertCtx* ctx = nullptr;
#endif
if (I < params.low_threshold)
{
trg = outLow.get();
++countLow;
#if MRPT_VERSION >= 0x020f00 // 2.15.0
ctx = &ctxLow;
#endif
}
else if (I > params.high_threshold)
{
trg = outHigh.get();
++countHigh;
#if MRPT_VERSION >= 0x020f00 // 2.15.0
ctx = &ctxHigh;
#endif
}
else
{
trg = outMid.get();
++countMid;
#if MRPT_VERSION >= 0x020f00 // 2.15.0
ctx = &ctxMid;
#endif
}

if (trg)
{
#if MRPT_VERSION >= 0x020f03 // 2.15.3
trg->insertPointFrom(i, *ctx);
#elif MRPT_VERSION >= 0x020f00 // 2.15.0
trg->insertPointFrom(pc, i, *ctx);
#else
trg->insertPointFrom(pc, i);
#endif
}
}

Expand Down
Loading
Loading