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
24 changes: 17 additions & 7 deletions apps/icp-run/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,6 @@
#include <mrpt/system/datetime.h>
#include <mrpt/system/filesystem.h>

#include <fstream>

// CLI flags:
static TCLAP::CmdLine cmd("icp-run");

Expand Down Expand Up @@ -122,7 +120,10 @@ static mrpt::obs::CRawlog::Ptr load_rawlog(const std::string& filename)
mrpt::img::CImage::setImagesPathBase(mrpt::obs::CRawlog::detectImagesDirectory(filename));

auto& r = rawlogsCache[filename];
if (r) return r;
if (r)
{
return r;
}
r = mrpt::obs::CRawlog::Create();

std::cout << "Loading rawlog file `" << filename << "`..." << std::endl;
Expand Down Expand Up @@ -184,7 +185,7 @@ static mp2p_icp::metric_map_t::Ptr load_input_pc(const std::string& filename, bo
{
const auto sepPos = extPos + 7;
const auto fil = filename.substr(0, sepPos);
const auto rawlogIndex = std::stod(filename.substr(sepPos + 1));
const auto rawlogIndex = std::stoi(filename.substr(sepPos + 1));

const auto r = load_rawlog(fil);

Expand Down Expand Up @@ -257,7 +258,10 @@ void runIcp()
// ------------------------------
auto [icp, icpParams] = mp2p_icp::icp_pipeline_from_yaml(cfg);

if (argGenerateDebugFiles.isSet()) icpParams.generateDebugFiles = true;
if (argGenerateDebugFiles.isSet())
{
icpParams.generateDebugFiles = true;
}

const auto initialGuess = mrpt::math::TPose3D::FromString(argInitialGuess.getValue());

Expand Down Expand Up @@ -301,7 +305,10 @@ void runIcp()
}
}

if (argProfile.isSet()) icp->profiler().enable(true);
if (argProfile.isSet())
{
icp->profiler().enable(true);
}

const double t_ini = mrpt::Clock::nowDouble();

Expand All @@ -321,7 +328,10 @@ int main(int argc, char** argv)
try
{
// Parse arguments:
if (!cmd.parse(argc, argv)) return 1; // should exit.
if (!cmd.parse(argc, argv))
{
return 1; // should exit.
}

runIcp();
}
Expand Down
17 changes: 14 additions & 3 deletions apps/mm-filter/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,12 +83,18 @@ void run_mm_filter(Cli& cli)
std::string errMsg;
const auto plugins = cli.arg_plugins.getValue();
std::cout << "Loading plugin(s): " << plugins << std::endl;
if (!mrpt::system::loadPluginModules(plugins, errMsg)) throw std::runtime_error(errMsg);
if (!mrpt::system::loadPluginModules(plugins, errMsg))
{
throw std::runtime_error(errMsg);
}
}

const auto& filInput = cli.argInput.getValue();

if (cli.argPipeline.isSet()) ASSERT_FILE_EXISTS_(cli.argPipeline.getValue());
if (cli.argPipeline.isSet())
{
ASSERT_FILE_EXISTS_(cli.argPipeline.getValue());
}

std::cout << "[mm-filter] Reading input map from: '" << filInput << "'..." << std::endl;

Expand Down Expand Up @@ -141,7 +147,9 @@ void run_mm_filter(Cli& cli)
std::cout << "[mm-filter] Writing metric map to: '" << filOut << "'..." << std::endl;

if (!mm.save_to_file(filOut))
{
THROW_EXCEPTION_FMT("Error writing to target file '%s'", filOut.c_str());
}
}
} // namespace

Expand All @@ -152,7 +160,10 @@ int main(int argc, char** argv)
Cli cli;

// Parse arguments:
if (!cli.cmd.parse(argc, argv)) return 1; // should exit.
if (!cli.cmd.parse(argc, argv))
{
return 1; // should exit.
}

run_mm_filter(cli);
}
Expand Down
12 changes: 9 additions & 3 deletions apps/mm-georef/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,14 +159,17 @@ void run_mm_georef(Cli& cli)
std::string errMsg;
const auto plugins = cli.arg_plugins.getValue();
std::cout << "Loading plugin(s): " << plugins << std::endl;
if (!mrpt::system::loadPluginModules(plugins, errMsg)) throw std::runtime_error(errMsg);
if (!mrpt::system::loadPluginModules(plugins, errMsg))
{
throw std::runtime_error(errMsg);
}
}

if (cli.argExtract.isSet())
{
return run_mm_extract(cli);
}
else if (cli.argInject.isSet())
if (cli.argInject.isSet())
{
return run_mm_inject(cli);
}
Expand All @@ -184,7 +187,10 @@ int main(int argc, char** argv)
Cli cli;

// Parse arguments:
if (!cli.cmd.parse(argc, argv)) return 1; // should exit.
if (!cli.cmd.parse(argc, argv))
{
return 1; // should exit.
}

run_mm_georef(cli);
}
Expand Down
5 changes: 4 additions & 1 deletion apps/mm-info/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,10 @@ int main(int argc, char** argv)
try
{
// Parse arguments:
if (!cmd.parse(argc, argv)) return 1; // should exit.
if (!cmd.parse(argc, argv))
{
return 1; // should exit.
}

run_mm_info();
}
Expand Down
54 changes: 54 additions & 0 deletions docs/source/mp2p_icp_filters.rst
Original file line number Diff line number Diff line change
Expand Up @@ -278,6 +278,60 @@ Useful for edge extraction (LOAM-style).

---

Filter: `FilterDecimate`
------------------------

**Description**: Naive point cloud downsampling that reduces the number of points by keeping only one out of every N points.
The filter can be configured either with a fixed decimation factor or by specifying a target maximum size (in which case the decimation factor is computed automatically).

If the output layer already exists, new points are accumulated on it; previous contents are not cleared.

.. note::
This filter is non-deterministic regarding the spatial distribution of points, as it relies purely on the internal storage order.
For spatially-aware downsampling, consider using :cpp:class:`FilterDecimateVoxels` or :cpp:class:`FilterDecimateAdaptive` instead.

**Parameters**:

* **input\_layer** (:cpp:type:`std::string`, default: `raw`): The input point cloud layer name.

* **output\_layer** (:cpp:type:`std::string`): The output layer name for the decimated cloud.

* **decimation** (:cpp:type:`uint32\_t`, default: `0`): Keep one out of every N points.
If greater than 0, this parameter takes precedence over ``target_max_size``.
For example, ``decimation=10`` keeps every 10th point, resulting in approximately 10% of the original points.

* **target\_max\_size** (:cpp:type:`uint64\_t`, default: `0`): Target maximum number of points in the output cloud.
Used only if ``decimation`` is 0.
The decimation factor is computed automatically to achieve approximately this many output points.

.. code-block:: yaml

filters:
#...
# Example 1: Fixed decimation factor
- class_name: mp2p_icp_filters::FilterDecimate
params:
input_layer: 'raw'
output_layer: 'decimated'
decimation: 5 # Keep every 5th point

# Example 2: Target maximum size
- class_name: mp2p_icp_filters::FilterDecimate
params:
input_layer: 'raw'
output_layer: 'decimated'
target_max_size: 10000 # Aim for ~10k points

.. rubric:: Before → After Screenshot

.. image:: decimate_example.png
:alt: Screenshot showing point cloud before and after applying FilterDecimate

|

---

Comment thread
jlblancoc marked this conversation as resolved.

Filter: `FilterDecimateAdaptive`
--------------------------------

Expand Down
2 changes: 2 additions & 0 deletions mp2p_icp_filters/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ set(LIB_SRCS
src/FilterByRange.cpp
src/FilterByRing.cpp
src/FilterCurvature.cpp
src/FilterDecimate.cpp
src/FilterDecimateAdaptive.cpp
src/FilterDecimateVoxels.cpp
src/FilterDeleteLayer.cpp
Expand Down Expand Up @@ -47,6 +48,7 @@ set(LIB_PUBLIC_HDRS
include/mp2p_icp_filters/FilterByRange.h
include/mp2p_icp_filters/FilterByRing.h
include/mp2p_icp_filters/FilterCurvature.h
include/mp2p_icp_filters/FilterDecimate.h
include/mp2p_icp_filters/FilterDecimateAdaptive.h
include/mp2p_icp_filters/FilterDecimateVoxels.h
include/mp2p_icp_filters/FilterDeleteLayer.h
Expand Down
78 changes: 78 additions & 0 deletions mp2p_icp_filters/include/mp2p_icp_filters/FilterDecimate.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
/* _
_ __ ___ ___ | | __ _
| '_ ` _ \ / _ \| |/ _` | Modular Optimization framework for
| | | | | | (_) | | (_| | Localization and mApping (MOLA)
|_| |_| |_|\___/|_|\__,_| https://github.com/MOLAorg/mola

A repertory of multi primitive-to-primitive (MP2P) ICP algorithms
and map building tools. mp2p_icp is part of MOLA.

Copyright (C) 2018-2026 Jose Luis Blanco, University of Almeria,
and individual contributors.
SPDX-License-Identifier: BSD-3-Clause
*/
/**
* @file FilterDecimate.h
* @brief Naive point cloud downsampling (every N-th point).
* @author Jose Luis Blanco Claraco
* @date Jan 12, 2026
*/

#pragma once

#include <mp2p_icp/metricmap.h>
#include <mp2p_icp_filters/FilterBase.h>

namespace mp2p_icp_filters
{
/**
* @brief Naive point cloud downsampling.
*
* This filter reduces the number of points by keeping only one out of every N
* points. It can be configured either with a fixed decimation factor or by
* providing a target maximum size (in which case the decimation factor is
* computed automatically).
*
* If the output layer exists, new points are accumulated on it: previous contents are not cleared.
*
* Note: This filter is non-deterministic regarding the spatial distribution
* of points, as it relies purely on the internal storage order.
*
* \ingroup mp2p_icp_filters_grp
*/
class FilterDecimate : public mp2p_icp_filters::FilterBase
{
DEFINE_MRPT_OBJECT(FilterDecimate, mp2p_icp_filters)
public:
FilterDecimate();

// See docs in FilterBase
void filter(mp2p_icp::metric_map_t& inOut) const override;

struct Parameters
{
void load_from_yaml(const mrpt::containers::yaml& c);

/** Input layer name (must be a point cloud) */
std::string input_layer = mp2p_icp::metric_map_t::PT_LAYER_RAW;

/** Output layer name */
std::string output_layer;

/** Keep one out of every 'decimation' points. If > 0, this takes
* precedence over target_max_size. */
uint32_t decimation = 0;

/** Target maximum number of points in the output cloud.
* Used only if decimation == 0. */
uint64_t target_max_size = 0;
};

/** Algorithm parameters */
Parameters params;

protected:
void initialize_filter(const mrpt::containers::yaml& c) override;
};

} // namespace mp2p_icp_filters
Loading
Loading