apps/icp-run/main.cpp
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
6 
14 #include <mp2p_icp/ICP.h>
16 #include <mp2p_icp/load_xyz_file.h>
17 #include <mp2p_icp/metricmap.h>
20 #include <mrpt/3rdparty/tclap/CmdLine.h>
21 #include <mrpt/core/Clock.h>
22 #include <mrpt/img/CImage.h>
23 #include <mrpt/obs/CRawlog.h>
24 #include <mrpt/system/datetime.h>
25 #include <mrpt/system/filesystem.h>
26 
27 #include <fstream>
28 
29 // CLI flags:
30 static TCLAP::CmdLine cmd("icp-run");
31 
32 static TCLAP::ValueArg<std::string> argInputLocal(
33  "", "input-local",
34  "Local input point cloud/map."
35  "It is interpreted as a rawlog entry if using the "
36  "format `<RAWLOG_FILE.rawlog>:<N>` to select the N-th entry in the "
37  "rawlog; otherwise, if the file extension is `.mm` it is loaded as a "
38  "serialized metric_map_t object; if it is a `.icplog` file, the local map "
39  "from that icp log is taken as input; in any other case, the file is "
40  "assumed to be a 3D pointcloud stored as a Nx3 ASCII matrix file.",
41  true, "pointcloud1.txt", "pointcloud1.txt", cmd);
42 
43 static TCLAP::ValueArg<std::string> argInputGlobal(
44  "", "input-global", "Global input point cloud/map. Same format than input-local. ", true,
45  "pointcloud2.txt", "pointcloud2.txt", cmd);
46 
47 static TCLAP::ValueArg<std::string> argYamlConfigFile(
48  "c", "config",
49  "YAML config file describing the ICP pipeline. See docs:\n"
50  " https://docs.mola-slam.org/latest/"
51  "module-mp2p-icp.html#yaml-pipeline-definition-files",
52  true, "icp-config.yaml", "icp-config.yaml", cmd);
53 
54 static TCLAP::ValueArg<std::string> argYamlConfigFileGenerators(
55  "", "config-generators",
56  "YAML config file describing the Generators. Can be also defined via an "
57  "entry `generators` in the main `--config` yaml file. "
58  "Can be used when processing a rawlog as input; if not present, a default "
59  "Generator object will be used.",
60  false, "generators-config.yaml", "generators-config.yaml", cmd);
61 
62 static TCLAP::ValueArg<std::string> argYamlConfigFileFiltersLocal(
63  "", "config-filters-local",
64  "YAML config file describing a filtering pipeline for local map."
65  "If not provided, and the main --config yaml file contains a "
66  "`filters` entry (can be overriden with --entry-name-filters-local), it "
67  "will be used instead.",
68  false, "filters-config.yaml", "filters-config.yaml", cmd);
69 
70 static TCLAP::ValueArg<std::string> argYamlConfigFileFiltersGlobal(
71  "", "config-filters-global",
72  "YAML config file describing a filtering pipeline for global map."
73  "If not provided, and the main --config yaml file contains a"
74  "`filters` entry (can be overriden with --entry-name-filters-global), it "
75  "will be used instead.",
76  false, "filters-config.yaml", "filters-config.yaml", cmd);
77 
78 static TCLAP::ValueArg<std::string> argCfgNameFiltersGlobal(
79  "", "entry-name-filters-global",
80  "Overrides the map name in the YAML configuration file for global map "
81  "filter.",
82  false, "filters", "filters", cmd);
83 
84 static TCLAP::ValueArg<std::string> argCfgNameFiltersLocal(
85  "", "entry-name-filters-local",
86  "Overrides the map name in the YAML configuration file for local map "
87  "filter.",
88  false, "filters", "filters", cmd);
89 
90 static TCLAP::ValueArg<std::string> argInitialGuess(
91  "", "guess",
92  "SE(3) transformation of local wrt global, to use as initial guess for the "
93  "ICP algorithm. "
94  "Format: \"[x y z yaw_deg pitch_deg roll_deg]\"",
95  false, "[0 0 0 0 0 0]", "[0 0 0 0 0 0]", cmd);
96 
97 static TCLAP::SwitchArg argGenerateDebugFiles(
98  "d", "generate-debug-log",
99  "Enforces generation of the .icplog debug log files for posterior "
100  "visualization with icp-log-viewer, overriding the "
101  "`generateDebugFiles` value in the configuration YAML file.",
102  cmd);
103 
104 static TCLAP::SwitchArg argProfile("", "profiler", "Enables the ICP profiler.", cmd);
105 
106 // To avoid reading the same .rawlog file twice:
107 static std::map<std::string, mrpt::obs::CRawlog::Ptr> rawlogsCache;
108 
109 static mrpt::obs::CRawlog::Ptr load_rawlog(const std::string& filename)
110 {
111  ASSERT_FILE_EXISTS_(filename);
112 
113  // enable loading externally-stored lazy load objects:
114  mrpt::img::CImage::setImagesPathBase(mrpt::obs::CRawlog::detectImagesDirectory(filename));
115 
116  auto& r = rawlogsCache[filename];
117  if (r) return r;
118  r = mrpt::obs::CRawlog::Create();
119 
120  std::cout << "Loading rawlog file `" << filename << "`..." << std::endl;
121 
122  bool rawlogReadOk = r->loadFromRawLogFile(filename, true);
123  ASSERT_(rawlogReadOk);
124 
125  std::cout << "Done, " << r->size() << " entries." << std::endl;
126 
127  return r;
128 }
129 
131 
132 static mp2p_icp::metric_map_t::Ptr pc_from_rawlog(const mrpt::obs::CRawlog& r, const size_t index)
133 {
134  ASSERT_LT_(index, r.size());
135 
136  if (generators.empty())
137  {
138  std::cout << "[warning] Using default mp2p_icp_filters::Generator since no "
139  "YAML file was given describing custom generators.\n";
140 
141  auto defaultGen = mp2p_icp_filters::Generator::Create();
142  defaultGen->initialize({});
143  generators.push_back(defaultGen);
144  }
145 
146  auto pc = mp2p_icp::metric_map_t::Create();
147 
148  auto o = r.getAsGeneric(index);
149  ASSERT_(o);
150 
151  if (auto sf = std::dynamic_pointer_cast<mrpt::obs::CSensoryFrame>(o); sf)
152  {
153  // Sensory-frame format:
155  }
156  else if (auto obs = std::dynamic_pointer_cast<mrpt::obs::CObservation>(o); obs)
157  {
159  }
160  else
161  {
162  auto e = r.getAsGeneric(index);
163  THROW_EXCEPTION_FMT(
164  "Rawlog index %u is neither CSensoryFrame or CObservation. Found "
165  "class name: '%s'",
166  static_cast<unsigned int>(index), e->GetRuntimeClass()->className);
167  }
168 
169  return pc;
170 }
171 
172 static mp2p_icp::metric_map_t::Ptr load_input_pc(const std::string& filename, bool local)
173 {
174  // rawlog?
175  if (auto extPos = filename.find(".rawlog:"); extPos != std::string::npos)
176  {
177  const auto sepPos = extPos + 7;
178  const auto fil = filename.substr(0, sepPos);
179  const auto rawlogIndex = std::stod(filename.substr(sepPos + 1));
180 
181  const auto r = load_rawlog(fil);
182 
183  return pc_from_rawlog(*r, rawlogIndex);
184  }
185 
186  // serialized metric_map_t object?
187  if (auto extPos = filename.find(".mm"); extPos != std::string::npos)
188  {
189  auto r = mp2p_icp::metric_map_t::Create();
190 
191  bool readOk = r->load_from_file(filename);
192  ASSERT_(readOk);
193 
194  return r;
195  }
196 
197  // icplog?
198  if (auto extPos = filename.find(".icplog"); extPos != std::string::npos)
199  {
201  bool icplogFileReadOK = lr.load_from_file(filename);
202  ASSERT_(icplogFileReadOK);
203 
204  auto r = mp2p_icp::metric_map_t::Create();
205  *r = local ? *lr.pcLocal : *lr.pcGlobal;
206  return r;
207  }
208 
209  // Otherwise: assume it's an ASCII point cloud file:
210  mrpt::maps::CSimplePointsMap::Ptr points = mp2p_icp::load_xyz_file(filename);
211 
212  auto pc = mp2p_icp::metric_map_t::Create();
213  pc->layers[mp2p_icp::metric_map_t::PT_LAYER_RAW] = points;
214 
215  return pc;
216 }
217 
218 void runIcp()
219 {
220  const auto cfg = mrpt::containers::yaml::FromFile(argYamlConfigFile.getValue());
221 
222  // ------------------------------
223  // Generators set
224  // ------------------------------
225  if (argYamlConfigFileGenerators.isSet())
226  {
227  const auto& f = argYamlConfigFileGenerators.getValue();
228 
230 
231  std::cout << "Created " << generators.size() << " generators from: " << f << std::endl;
232  }
233  else if (cfg.has("generators"))
234  {
236  }
237 
238  // ------------------------------
239  // Original input point clouds
240  // ------------------------------
241  auto pcLocal = load_input_pc(argInputLocal.getValue(), true);
242  auto pcGlobal = load_input_pc(argInputGlobal.getValue(), false);
243 
244  std::cout << "Input point cloud #1: " << pcLocal->contents_summary() << std::endl;
245  std::cout << "Input point cloud #2: " << pcGlobal->contents_summary() << std::endl;
246 
247  // ------------------------------
248  // Build ICP pipeline:
249  // ------------------------------
250  auto [icp, icpParams] = mp2p_icp::icp_pipeline_from_yaml(cfg);
251 
252  if (argGenerateDebugFiles.isSet()) icpParams.generateDebugFiles = true;
253 
254  const auto initialGuess = mrpt::math::TPose3D::FromString(argInitialGuess.getValue());
255 
256  // -----------------------------------------
257  // Apply filtering pipeline, if defined
258  // -----------------------------------------
259  {
261  if (argYamlConfigFileFiltersLocal.isSet())
262  {
264  argYamlConfigFileFiltersLocal.getValue());
265  }
266  else if (cfg.has(argCfgNameFiltersLocal.getValue()))
267  {
268  filtersLocal =
270  }
271  if (!filtersLocal.empty())
272  {
273  mp2p_icp_filters::apply_filter_pipeline(filtersLocal, *pcLocal);
274  std::cout << "Filtered local map: " << pcLocal->contents_summary() << std::endl;
275  }
276  }
277  {
278  mp2p_icp_filters::FilterPipeline filtersGlobal;
279  if (argYamlConfigFileFiltersGlobal.isSet())
280  {
282  argYamlConfigFileFiltersGlobal.getValue());
283  }
284  else if (cfg.has(argCfgNameFiltersGlobal.getValue()))
285  {
287  cfg[argCfgNameFiltersGlobal.getValue()]);
288  }
289  if (!filtersGlobal.empty())
290  {
291  mp2p_icp_filters::apply_filter_pipeline(filtersGlobal, *pcGlobal);
292  std::cout << "Filtered global map: " << pcGlobal->contents_summary() << std::endl;
293  }
294  }
295 
296  if (argProfile.isSet()) icp->profiler().enable(true);
297 
298  const double t_ini = mrpt::Clock::nowDouble();
299 
300  mp2p_icp::Results icpResults;
301  icp->align(*pcLocal, *pcGlobal, initialGuess, icpParams, icpResults);
302 
303  const double t_end = mrpt::Clock::nowDouble();
304 
305  std::cout << "ICP result:\n";
306  icpResults.print(std::cout);
307 
308  std::cout << "- time to solve: " << mrpt::system::formatTimeInterval(t_end - t_ini) << "\n";
309 }
310 
311 int main(int argc, char** argv)
312 {
313  try
314  {
315  // Parse arguments:
316  if (!cmd.parse(argc, argv)) return 1; // should exit.
317 
318  runIcp();
319  }
320  catch (const std::exception& e)
321  {
322  std::cerr << mrpt::exception_to_str(e);
323  return 1;
324  }
325  return 0;
326 }
ICP.h
Generic ICP algorithm container.
generators
static mp2p_icp_filters::GeneratorSet generators
Definition: apps/icp-run/main.cpp:130
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp_filters::apply_filter_pipeline
void apply_filter_pipeline(const FilterPipeline &filters, mp2p_icp::metric_map_t &inOut, const mrpt::optional_ref< mrpt::system::CTimeLogger > &profiler=std::nullopt)
Definition: FilterBase.cpp:24
mp2p_icp_filters::filter_pipeline_from_yaml_file
FilterPipeline filter_pipeline_from_yaml_file(const std::string &filename, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
Definition: FilterBase.cpp:69
mp2p_icp::LogRecord
Definition: LogRecord.h:30
mp2p_icp::Results::print
void print(std::ostream &o) const
Definition: Results.cpp:49
mp2p_icp::metric_map_t::PT_LAYER_RAW
constexpr static const char * PT_LAYER_RAW
Definition: metricmap.h:64
testing::internal::string
::std::string string
Definition: gtest.h:1979
argYamlConfigFileFiltersLocal
static TCLAP::ValueArg< std::string > argYamlConfigFileFiltersLocal("", "config-filters-local", "YAML config file describing a filtering pipeline for local map." "If not provided, and the main --config yaml file contains a " "`filters` entry (can be overriden with --entry-name-filters-local), it " "will be used instead.", false, "filters-config.yaml", "filters-config.yaml", cmd)
Generator.h
Base virtual class for point cloud filters.
argCfgNameFiltersLocal
static TCLAP::ValueArg< std::string > argCfgNameFiltersLocal("", "entry-name-filters-local", "Overrides the map name in the YAML configuration file for local map " "filter.", false, "filters", "filters", cmd)
load_rawlog
static mrpt::obs::CRawlog::Ptr load_rawlog(const std::string &filename)
Definition: apps/icp-run/main.cpp:109
rawlogsCache
static std::map< std::string, mrpt::obs::CRawlog::Ptr > rawlogsCache
Definition: apps/icp-run/main.cpp:107
argInputLocal
static TCLAP::ValueArg< std::string > argInputLocal("", "input-local", "Local input point cloud/map." "It is interpreted as a rawlog entry if using the " "format `<RAWLOG_FILE.rawlog>:<N>` to select the N-th entry in the " "rawlog; otherwise, if the file extension is `.mm` it is loaded as a " "serialized metric_map_t object; if it is a `.icplog` file, the local map " "from that icp log is taken as input; in any other case, the file is " "assumed to be a 3D pointcloud stored as a Nx3 ASCII matrix file.", true, "pointcloud1.txt", "pointcloud1.txt", cmd)
argYamlConfigFileFiltersGlobal
static TCLAP::ValueArg< std::string > argYamlConfigFileFiltersGlobal("", "config-filters-global", "YAML config file describing a filtering pipeline for global map." "If not provided, and the main --config yaml file contains a" "`filters` entry (can be overriden with --entry-name-filters-global), it " "will be used instead.", false, "filters-config.yaml", "filters-config.yaml", cmd)
mp2p_icp_filters::filter_pipeline_from_yaml
FilterPipeline filter_pipeline_from_yaml(const mrpt::containers::yaml &c, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
Definition: FilterBase.cpp:39
kitti-run-seq.cfg
cfg
Definition: kitti-run-seq.py:7
mp2p_icp::LogRecord::load_from_file
bool load_from_file(const std::string &fileName)
Definition: LogRecord.cpp:98
mp2p_icp_filters::FilterPipeline
std::vector< FilterBase::Ptr > FilterPipeline
Definition: FilterBase.h:75
mp2p_icp::icp_pipeline_from_yaml
std::tuple< mp2p_icp::ICP::Ptr, mp2p_icp::Parameters > icp_pipeline_from_yaml(const mrpt::containers::yaml &config, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
Definition: icp_pipeline_from_yaml.cpp:17
load_input_pc
static mp2p_icp::metric_map_t::Ptr load_input_pc(const std::string &filename, bool local)
Definition: apps/icp-run/main.cpp:172
mp2p_icp_filters::GeneratorSet
std::vector< Generator::Ptr > GeneratorSet
Definition: Generator.h:190
argCfgNameFiltersGlobal
static TCLAP::ValueArg< std::string > argCfgNameFiltersGlobal("", "entry-name-filters-global", "Overrides the map name in the YAML configuration file for global map " "filter.", false, "filters", "filters", cmd)
mp2p_icp_filters::generators_from_yaml_file
GeneratorSet generators_from_yaml_file(const std::string &filename, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
Definition: Generator.cpp:331
mp2p_icp::LogRecord::pcGlobal
metric_map_t::ConstPtr pcGlobal
Definition: LogRecord.h:42
argInitialGuess
static TCLAP::ValueArg< std::string > argInitialGuess("", "guess", "SE(3) transformation of local wrt global, to use as initial guess for the " "ICP algorithm. " "Format: \"[x y z yaw_deg pitch_deg roll_deg]\"", false, "[0 0 0 0 0 0]", "[0 0 0 0 0 0]", cmd)
FilterBase.h
Base virtual class for point cloud filters.
icp_pipeline_from_yaml.h
Loads and setup an ICP pipeline from a YAML configuration file.
mp2p_icp::load_xyz_file
mrpt::maps::CSimplePointsMap::Ptr load_xyz_file(const std::string &fil)
Definition: load_xyz_file.cpp:21
argProfile
static TCLAP::SwitchArg argProfile("", "profiler", "Enables the ICP profiler.", cmd)
argInputGlobal
static TCLAP::ValueArg< std::string > argInputGlobal("", "input-global", "Global input point cloud/map. Same format than input-local. ", true, "pointcloud2.txt", "pointcloud2.txt", cmd)
cmd
static TCLAP::CmdLine cmd("icp-run")
metricmap.h
Generic representation of pointcloud(s) and/or extracted features.
argYamlConfigFile
static TCLAP::ValueArg< std::string > argYamlConfigFile("c", "config", "YAML config file describing the ICP pipeline. See docs:\n" " https://docs.mola-slam.org/latest/" "module-mp2p-icp.html#yaml-pipeline-definition-files", true, "icp-config.yaml", "icp-config.yaml", cmd)
mp2p_icp::LogRecord::pcLocal
metric_map_t::ConstPtr pcLocal
Definition: LogRecord.h:42
mp2p_icp::Results
Definition: Results.h:21
mp2p_icp_filters::apply_generators
bool apply_generators(const GeneratorSet &generators, const mrpt::obs::CObservation &obs, mp2p_icp::metric_map_t &output, const std::optional< mrpt::poses::CPose3D > &robotPose=std::nullopt)
Definition: Generator.cpp:242
main
int main(int argc, char **argv)
Definition: apps/icp-run/main.cpp:311
load_xyz_file.h
Unit tests common utilities.
pc_from_rawlog
static mp2p_icp::metric_map_t::Ptr pc_from_rawlog(const mrpt::obs::CRawlog &r, const size_t index)
Definition: apps/icp-run/main.cpp:132
runIcp
void runIcp()
Definition: apps/icp-run/main.cpp:218
kitti-batch-convert.filename
filename
Definition: kitti-batch-convert.py:6
argGenerateDebugFiles
static TCLAP::SwitchArg argGenerateDebugFiles("d", "generate-debug-log", "Enforces generation of the .icplog debug log files for posterior " "visualization with icp-log-viewer, overriding the " "`generateDebugFiles` value in the configuration YAML file.", cmd)
argYamlConfigFileGenerators
static TCLAP::ValueArg< std::string > argYamlConfigFileGenerators("", "config-generators", "YAML config file describing the Generators. Can be also defined via an " "entry `generators` in the main `--config` yaml file. " "Can be used when processing a rawlog as input; if not present, a default " "Generator object will be used.", false, "generators-config.yaml", "generators-config.yaml", cmd)
mp2p_icp_filters::generators_from_yaml
GeneratorSet generators_from_yaml(const mrpt::containers::yaml &c, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
Definition: Generator.cpp:298


mp2p_icp
Author(s):
autogenerated on Mon May 26 2025 02:45:49