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: 2 additions & 0 deletions apps/mm-filter/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@
#include <mrpt/containers/yaml.h>
#include <mrpt/system/filesystem.h>

#include <stdexcept>

namespace
{

Expand Down
1 change: 1 addition & 0 deletions apps/mm-georef/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <mrpt/system/os.h>

#include <fstream>
#include <stdexcept>

namespace
{
Expand Down
21 changes: 20 additions & 1 deletion apps/mm-info/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,18 +24,37 @@
#include <mrpt/containers/yaml.h>
#include <mrpt/core/Clock.h>
#include <mrpt/system/filesystem.h>
#include <mrpt/system/os.h>

#include <stdexcept>

// CLI flags:
namespace
{
TCLAP::CmdLine cmd("mm-filter");
TCLAP::CmdLine cmd("mm-info");

TCLAP::UnlabeledValueArg<std::string> argMapFile(
"input", "Load this metric map file (*.mm)", true, "myMap.mm", "myMap.mm", cmd);

TCLAP::ValueArg<std::string> arg_plugins(
"l", "load-plugins", "One or more (comma separated) *.so files to load as plugins", false,
"foobar.so", "foobar.so", cmd);
} // namespace

void run_mm_info()
{
// Load plugins:
if (arg_plugins.isSet())
{
std::string errMsg;
const auto plugins = arg_plugins.getValue();
std::cout << "Loading plugin(s): " << plugins << std::endl;
if (!mrpt::system::loadPluginModules(plugins, errMsg))
{
throw std::runtime_error(errMsg);
}
}

const auto& filInput = argMapFile.getValue();

ASSERT_FILE_EXISTS_(argMapFile.getValue());
Expand Down
17 changes: 17 additions & 0 deletions apps/mm2grid/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

#include <fstream>
#include <iostream>
#include <stdexcept>

// ---------------------------------------------------------------------------
// CLI flags
Expand Down Expand Up @@ -79,6 +80,10 @@ TCLAP::SwitchArg argNegate(
"occupied (negate: true in the YAML).",
cmd);

TCLAP::ValueArg<std::string> arg_plugins(
"", "load-plugins", "One or more (comma separated) *.so files to load as plugins", false,
"foobar.so", "foobar.so", cmd);

} // namespace

// ---------------------------------------------------------------------------
Expand All @@ -87,6 +92,18 @@ void run_mm2grid()
{
using namespace std::string_literals;

// Load plugins:
if (arg_plugins.isSet())
{
std::string errMsg;
const auto plugins = arg_plugins.getValue();
std::cout << "Loading plugin(s): " << plugins << std::endl;
if (!mrpt::system::loadPluginModules(plugins, errMsg))
{
throw std::runtime_error(errMsg);
}
}
Comment thread
jlblancoc marked this conversation as resolved.

const auto& filInput = argMapFile.getValue();
ASSERT_FILE_EXISTS_(filInput);

Expand Down
18 changes: 18 additions & 0 deletions apps/mm2las/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <mrpt/maps/CPointsMap.h>
#include <mrpt/poses/CPose3D.h>
#include <mrpt/system/filesystem.h>
#include <mrpt/system/os.h>
#include <mrpt/system/string_utils.h>
#include <mrpt/topography/conversions.h>
#include <mrpt/topography/data_types.h>
Expand Down Expand Up @@ -68,6 +69,10 @@ TCLAP::ValueArg<std::string> argFrame(
"in the map, they are used directly; otherwise, the conversion is computed on the fly.",
false, "map", "map|enu|geodetic", cmd);

TCLAP::ValueArg<std::string> arg_plugins(
"l", "load-plugins", "One or more (comma separated) *.so files to load as plugins", false,
"foobar.so", "foobar.so", cmd);

// ----------------------------------------------------------------
// LAS 1.4 Format Structures
// ----------------------------------------------------------------
Expand Down Expand Up @@ -1187,6 +1192,19 @@ int main(int argc, char** argv)
{
return 0;
}

// Load plugins:
if (arg_plugins.isSet())
{
std::string errMsg;
const auto plugins = arg_plugins.getValue();
std::cout << "Loading plugin(s): " << plugins << std::endl;
if (!mrpt::system::loadPluginModules(plugins, errMsg))
{
throw std::runtime_error(errMsg);
}
}

mp2p_icp::metric_map_t mm;
mm.load_from_file(arg_input.getValue());

Expand Down
19 changes: 19 additions & 0 deletions apps/mm2ply/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,13 @@
#include <mrpt/maps/CPointsMap.h>
#include <mrpt/poses/CPose3D.h>
#include <mrpt/system/filesystem.h>
#include <mrpt/system/os.h>
#include <mrpt/system/string_utils.h>
#include <mrpt/version.h>

#include <fstream>
#include <iostream>
#include <stdexcept>

// CLI flags
TCLAP::CmdLine cmd("mm2ply");
Expand Down Expand Up @@ -59,6 +61,10 @@ TCLAP::ValueArg<std::string> argFrame(
"'enu' transforms points to the East-North-Up frame (requires georeferencing data in the map).",
false, "map", "map|enu", cmd);

TCLAP::ValueArg<std::string> arg_plugins(
"l", "load-plugins", "One or more (comma separated) *.so files to load as plugins", false,
"foobar.so", "foobar.so", cmd);

// ----------------------------------------------------------------
// PLY Export Logic using CPointsMap field-generic API
// ----------------------------------------------------------------
Expand Down Expand Up @@ -401,6 +407,19 @@ int main(int argc, char** argv)
{
return 0;
}

// Load plugins:
if (arg_plugins.isSet())
{
std::string errMsg;
const auto plugins = arg_plugins.getValue();
std::cout << "Loading plugin(s): " << plugins << std::endl;
if (!mrpt::system::loadPluginModules(plugins, errMsg))
{
throw std::runtime_error(errMsg);
}
}

mp2p_icp::metric_map_t mm;
mm.load_from_file(arg_input.getValue());

Expand Down
18 changes: 18 additions & 0 deletions apps/mm2txt/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
#include <mrpt/system/string_utils.h>
#include <mrpt/version.h>

#include <stdexcept>

#if MRPT_VERSION < 0x030000 // <3.0.0
#include <mrpt/maps/CPointsMapXYZI.h>
#include <mrpt/maps/CPointsMapXYZIRT.h>
Expand Down Expand Up @@ -68,6 +70,10 @@ TCLAP::ValueArg<std::string> argFrame(
"'enu' transforms points to the East-North-Up frame (requires georeferencing data in the map).",
false, "map", "map|enu", cmd);

TCLAP::ValueArg<std::string> arg_plugins(
"", "load-plugins", "One or more (comma separated) *.so files to load as plugins", false,
"foobar.so", "foobar.so", cmd);

Comment thread
coderabbitai[bot] marked this conversation as resolved.
bool saveToTxt(
const mrpt::maps::CGenericPointsMap& pts, const std::string& fileName, bool printHeader,
const std::vector<std::string>& selectedFields = {},
Expand Down Expand Up @@ -218,6 +224,18 @@ void run_mm2txt()
{
using namespace std::string_literals;

// Load plugins:
if (arg_plugins.isSet())
{
std::string errMsg;
const auto plugins = arg_plugins.getValue();
std::cout << "Loading plugin(s): " << plugins << std::endl;
if (!mrpt::system::loadPluginModules(plugins, errMsg))
{
throw std::runtime_error(errMsg);
}
}

const auto& filInput = argMapFile.getValue();

ASSERT_FILE_EXISTS_(argMapFile.getValue());
Expand Down
20 changes: 20 additions & 0 deletions apps/rawlog-filter/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,12 @@
#include <mrpt/obs/CSensoryFrame.h>
#include <mrpt/serialization/CArchive.h>
#include <mrpt/system/filesystem.h>
#include <mrpt/system/os.h>
#include <mrpt/system/progress.h>
#include <mrpt/version.h>

#include <stdexcept>

#if MRPT_VERSION >= 0x020f07
#include <mrpt/io/CCompressedOutputStream.h>
#else
Expand Down Expand Up @@ -81,12 +84,29 @@ struct Cli
TCLAP::ValueArg<std::string> arg_verbosity_level{
"v", "verbosity", "Verbosity level: ERROR|WARN|INFO|DEBUG (Default: INFO)", false, "",
"INFO", cmd};

TCLAP::ValueArg<std::string> arg_plugins{
"l", "load-plugins", "One or more (comma separated) *.so files to load as plugins",
false, "foobar.so", "foobar.so",
cmd};
};

void run_mm_filter(Cli& cli)
{
using namespace std::string_literals;

// Load plugins:
if (cli.arg_plugins.isSet())
{
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);
}
}

ASSERT_FILE_EXISTS_(cli.argInput.getValue());
ASSERT_FILE_EXISTS_(cli.argPipeline.getValue());

Expand Down
9 changes: 7 additions & 2 deletions docs/source/app_mm-info.rst
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,19 @@ The tool provides information about the layers, point counts, and other metadata

USAGE:

mm-info <myMap.mm> [--] [--version] [-h]
mm-info <myMap.mm> [-l <foobar.so>] [--] [--version] [-h]


Where:
Where:

<myMap.mm>
(required) Load this metric map file (*.mm)

-l <foobar.so>, --load-plugins <foobar.so>
One or more (comma separated) *.so files to load as plugins (e.g.
``libmola_metric_maps.so``). Use this when the map contains custom
map types that are not part of the default mp2p_icp build.

--, --ignore_rest
Ignores the rest of the labeled arguments following this flag.

Expand Down
2 changes: 2 additions & 0 deletions docs/source/app_mm2grid.rst
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ Usage
mm2grid <input.mm> [-l <layer_name>] [-o <output_base>]
[--occupied-thresh <value>] [--free-thresh <value>]
[--mode trinary|scale|raw] [--negate]
[--load-plugins <plugin.so>]

Arguments
^^^^^^^^^
Expand All @@ -61,6 +62,7 @@ Arguments
- ``--negate`` (optional): If set, the color interpretation is inverted:
black pixels are free and white pixels are occupied. Sets ``negate: 1`` in
the YAML. Default: not set (``negate: 0``).
- ``--load-plugins <file.so>`` (optional): One or more (comma separated) ``.so`` plugin files to load before reading the map. Use this to load custom map types (e.g. ``--load-plugins libmola_metric_maps.so``).

Examples
^^^^^^^^
Expand Down
3 changes: 2 additions & 1 deletion docs/source/app_mm2las.rst
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ Usage

.. code-block:: bash

mm2las -i <input.mm> [-o <output_prefix>] [--export-fields <field1,field2,...>] [--frame map|enu|geodetic]
mm2las -i <input.mm> [-o <output_prefix>] [--export-fields <field1,field2,...>] [--frame map|enu|geodetic] [-l <plugin.so>]

Arguments
^^^^^^^^^
Expand All @@ -36,6 +36,7 @@ Arguments
- ``--export-fields <field1,field2,...>`` (optional): Comma-separated list of fields to export. If omitted, all available fields are exported, with non-standard fields becoming Extra Dimensions.
- ``--system-id <string>``: Sets the System Identifier in the LAS header (default: "mm2las").
- ``--generating-software <string>``: Sets the Generating Software in the LAS header (default: "MOLA mm2las").
- ``-l, --load-plugins <file.so>`` (optional): One or more (comma separated) ``.so`` plugin files to load before reading the map. Use this to load custom map types (e.g. ``--load-plugins libmola_metric_maps.so``).
- ``--frame <map|enu|geodetic>`` (optional): Coordinate frame for exported points. ``map`` (default) exports coordinates in the map local frame. ``enu`` transforms all point coordinates to the East-North-Up frame using the georeferencing information stored in the map. ``geodetic`` exports points as WGS-84 geographic coordinates (EPSG:4979) with longitude as X, latitude as Y, and ellipsoidal height as Z, embedding the CRS as a WKT VLR in the LAS file for full georeferencing support in GIS software. Requires that the input map contains georeferencing data with valid geodetic coordinates. If per-point ``latitude``/``longitude``/``altitude`` double fields already exist in the map (e.g., from ``mola-mm-add-geodetic``), they are used directly; otherwise, the conversion from map coordinates is computed on the fly.


Expand Down
3 changes: 2 additions & 1 deletion docs/source/app_mm2ply.rst
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ Usage

.. code-block:: bash

mm2ply -i <input.mm> [-o <output_prefix>] [-b] [--export-fields <field1,field2,...>] [--ignore-missing-fields] [--frame map|enu]
mm2ply -i <input.mm> [-o <output_prefix>] [-b] [--export-fields <field1,field2,...>] [--ignore-missing-fields] [--frame map|enu] [-l <plugin.so>]

Arguments
^^^^^^^^^
Expand All @@ -35,6 +35,7 @@ Arguments
- ``--export-fields <field1,field2,...>`` (optional): Comma-separated list of fields to export in the specified order. If not provided, all available fields will be exported. Spaces around commas are allowed
- ``--ignore-missing-fields`` (optional): If defined, the lack of any of the ``--export-fields`` in the map will be considered a warning instead of an error.
- ``--frame <map|enu>`` (optional): Coordinate frame for exported points. ``map`` (default) exports coordinates in the map local frame. ``enu`` transforms all point coordinates to the East-North-Up frame using the georeferencing information stored in the map. Requires that the input map contains georeferencing data; otherwise, an error is raised.
- ``-l, --load-plugins <file.so>`` (optional): One or more (comma separated) ``.so`` plugin files to load before reading the map. Use this to load custom map types (e.g. ``--load-plugins libmola_metric_maps.so``).

Examples
^^^^^^^^
Expand Down
6 changes: 5 additions & 1 deletion docs/source/app_mm2txt.rst
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,10 @@ Usage

.. code-block:: bash

mm2txt <input.mm> [-l <layer_name>] [--export-fields <field1,field2,...>] [--ignore-missing-fields] [--frame map|enu]
mm2txt <input.mm> [-l <layer_name>] [--export-fields <field1,field2,...>] [--ignore-missing-fields] [--frame map|enu] [--load-plugins <plugin.so>]

.. note::
In ``mm2txt``, ``-l`` is reserved for ``--layer``. Use ``--load-plugins`` (no short flag) for plugin loading.

Arguments
^^^^^^^^^
Expand All @@ -34,6 +37,7 @@ Arguments
- ``-l, --layer <name>`` (optional): Layer to export. If not provided, all layers will be exported. This argument can appear multiple times to export specific layers
- ``--export-fields <field1,field2,...>`` (optional): Comma-separated list of fields to export in the specified order. If not provided, all available fields will be exported. Spaces around commas are allowed
- ``--ignore-missing-fields`` (optional): If defined, the lack of any of the ``--export-fields`` in the map will be considered a warning instead of an error.
- ``--load-plugins <file.so>`` (optional): One or more (comma separated) ``.so`` plugin files to load before reading the map. Use this to load custom map types (e.g. ``--load-plugins libmola_metric_maps.so``).
- ``--frame <map|enu>`` (optional): Coordinate frame for exported points. ``map`` (default) exports coordinates in the map local frame. ``enu`` transforms all point coordinates to the East-North-Up frame using the georeferencing information stored in the map. Requires that the input map contains georeferencing data; otherwise, an error is raised.

Examples
Expand Down
2 changes: 2 additions & 0 deletions mp2p_icp_filters/src/FilterAbsoluteTimestamp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
#include <mrpt/system/datetime.h>
#include <mrpt/version.h>

#include <stdexcept>

IMPLEMENTS_MRPT_OBJECT(FilterAbsoluteTimestamp, mp2p_icp_filters::FilterBase, mp2p_icp_filters)

using namespace mp2p_icp_filters;
Expand Down
2 changes: 2 additions & 0 deletions mp2p_icp_filters/src/FilterDeskew.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#include <mola_imu_preintegration/ImuIntegrationParams.h>
#include <mola_imu_preintegration/ImuTransformer.h>
#include <mola_imu_preintegration/trajectory_from_buffer.h>

#include <stdexcept>
#endif

#include <mp2p_icp/pointcloud_field_utils.h>
Expand Down
2 changes: 2 additions & 0 deletions mp2p_icp_filters/src/FilterSOR.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
#include <mrpt/math/ops_containers.h> // meanAndCov
#include <mrpt/version.h>

#include <stdexcept>

#if defined(MP2P_HAS_TBB)
#include <tbb/blocked_range.h>
#include <tbb/parallel_for.h>
Expand Down
Loading
Loading