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",
45  "Global input point cloud/map. Same format than input-local. ", true,
46  "pointcloud2.txt", "pointcloud2.txt", cmd);
47 
48 static TCLAP::ValueArg<std::string> argYamlConfigFile(
49  "c", "config",
50  "YAML config file describing the ICP pipeline. See docs:\n"
51  " https://docs.mola-slam.org/latest/"
52  "module-mp2p-icp.html#yaml-pipeline-definition-files",
53  true, "icp-config.yaml", "icp-config.yaml", cmd);
54 
55 static TCLAP::ValueArg<std::string> argYamlConfigFileGenerators(
56  "", "config-generators",
57  "YAML config file describing the Generators. Can be also defined via an "
58  "entry `generators` in the main `--config` yaml file. "
59  "Can be used when processing a rawlog as input; if not present, a default "
60  "Generator object will be used.",
61  false, "generators-config.yaml", "generators-config.yaml", cmd);
62 
63 static TCLAP::ValueArg<std::string> argYamlConfigFileFiltersLocal(
64  "", "config-filters-local",
65  "YAML config file describing a filtering pipeline for local map."
66  "If not provided, and the main --config yaml file contains a "
67  "`filters` entry (can be overriden with --entry-name-filters-local), it "
68  "will be used instead.",
69  false, "filters-config.yaml", "filters-config.yaml", cmd);
70 
71 static TCLAP::ValueArg<std::string> argYamlConfigFileFiltersGlobal(
72  "", "config-filters-global",
73  "YAML config file describing a filtering pipeline for global map."
74  "If not provided, and the main --config yaml file contains a"
75  "`filters` entry (can be overriden with --entry-name-filters-global), it "
76  "will be used instead.",
77  false, "filters-config.yaml", "filters-config.yaml", cmd);
78 
79 static TCLAP::ValueArg<std::string> argCfgNameFiltersGlobal(
80  "", "entry-name-filters-global",
81  "Overrides the map name in the YAML configuration file for global map "
82  "filter.",
83  false, "filters", "filters", cmd);
84 
85 static TCLAP::ValueArg<std::string> argCfgNameFiltersLocal(
86  "", "entry-name-filters-local",
87  "Overrides the map name in the YAML configuration file for local map "
88  "filter.",
89  false, "filters", "filters", cmd);
90 
91 static TCLAP::ValueArg<std::string> argInitialGuess(
92  "", "guess",
93  "SE(3) transformation of local wrt global, to use as initial guess for the "
94  "ICP algorithm. "
95  "Format: \"[x y z yaw_deg pitch_deg roll_deg]\"",
96  false, "[0 0 0 0 0 0]", "[0 0 0 0 0 0]", cmd);
97 
98 static TCLAP::SwitchArg argGenerateDebugFiles(
99  "d", "generate-debug-log",
100  "Enforces generation of the .icplog debug log files for posterior "
101  "visualization with icp-log-viewer, overriding the "
102  "`generateDebugFiles` value in the configuration YAML file.",
103  cmd);
104 
105 static TCLAP::SwitchArg argProfile(
106  "", "profiler", "Enables the ICP profiler.", cmd);
107 
108 // To avoid reading the same .rawlog file twice:
109 static std::map<std::string, mrpt::obs::CRawlog::Ptr> rawlogsCache;
110 
111 static mrpt::obs::CRawlog::Ptr load_rawlog(const std::string& filename)
112 {
113  ASSERT_FILE_EXISTS_(filename);
114 
115  // enable loading externally-stored lazy load objects:
116  mrpt::img::CImage::setImagesPathBase(
117  mrpt::obs::CRawlog::detectImagesDirectory(filename));
118 
119  auto& r = rawlogsCache[filename];
120  if (r) return r;
121  r = mrpt::obs::CRawlog::Create();
122 
123  std::cout << "Loading rawlog file `" << filename << "`..." << std::endl;
124 
125  bool rawlogReadOk = r->loadFromRawLogFile(filename, true);
126  ASSERT_(rawlogReadOk);
127 
128  std::cout << "Done, " << r->size() << " entries." << std::endl;
129 
130  return r;
131 }
132 
134 
135 static mp2p_icp::metric_map_t::Ptr pc_from_rawlog(
136  const mrpt::obs::CRawlog& r, const size_t index)
137 {
138  ASSERT_LT_(index, r.size());
139 
140  if (generators.empty())
141  {
142  std::cout
143  << "[warning] Using default mp2p_icp_filters::Generator since no "
144  "YAML file was given describing custom generators.\n";
145 
146  auto defaultGen = mp2p_icp_filters::Generator::Create();
147  defaultGen->initialize({});
148  generators.push_back(defaultGen);
149  }
150 
151  auto pc = mp2p_icp::metric_map_t::Create();
152 
153  auto o = r.getAsGeneric(index);
154  ASSERT_(o);
155 
156  if (auto sf = std::dynamic_pointer_cast<mrpt::obs::CSensoryFrame>(o); sf)
157  {
158  // Sensory-frame format:
160  }
161  else if (auto obs = std::dynamic_pointer_cast<mrpt::obs::CObservation>(o);
162  obs)
163  {
165  }
166  else
167  {
168  auto e = r.getAsGeneric(index);
169  THROW_EXCEPTION_FMT(
170  "Rawlog index %u is neither CSensoryFrame or CObservation. Found "
171  "class name: '%s'",
172  static_cast<unsigned int>(index), e->GetRuntimeClass()->className);
173  }
174 
175  return pc;
176 }
177 
178 static mp2p_icp::metric_map_t::Ptr load_input_pc(
179  const std::string& filename, bool local)
180 {
181  // rawlog?
182  if (auto extPos = filename.find(".rawlog:"); extPos != std::string::npos)
183  {
184  const auto sepPos = extPos + 7;
185  const auto fil = filename.substr(0, sepPos);
186  const auto rawlogIndex = std::stod(filename.substr(sepPos + 1));
187 
188  const auto r = load_rawlog(fil);
189 
190  return pc_from_rawlog(*r, rawlogIndex);
191  }
192 
193  // serialized metric_map_t object?
194  if (auto extPos = filename.find(".mm"); extPos != std::string::npos)
195  {
196  auto r = mp2p_icp::metric_map_t::Create();
197 
198  bool readOk = r->load_from_file(filename);
199  ASSERT_(readOk);
200 
201  return r;
202  }
203 
204  // icplog?
205  if (auto extPos = filename.find(".icplog"); extPos != std::string::npos)
206  {
208  bool icplogFileReadOK = lr.load_from_file(filename);
209  ASSERT_(icplogFileReadOK);
210 
211  auto r = mp2p_icp::metric_map_t::Create();
212  *r = local ? *lr.pcLocal : *lr.pcGlobal;
213  return r;
214  }
215 
216  // Otherwise: assume it's an ASCII point cloud file:
217  mrpt::maps::CSimplePointsMap::Ptr points =
219 
220  auto pc = mp2p_icp::metric_map_t::Create();
221  pc->layers[mp2p_icp::metric_map_t::PT_LAYER_RAW] = points;
222 
223  return pc;
224 }
225 
226 void runIcp()
227 {
228  const auto cfg =
229  mrpt::containers::yaml::FromFile(argYamlConfigFile.getValue());
230 
231  // ------------------------------
232  // Generators set
233  // ------------------------------
234  if (argYamlConfigFileGenerators.isSet())
235  {
236  const auto& f = argYamlConfigFileGenerators.getValue();
237 
239 
240  std::cout << "Created " << generators.size()
241  << " generators from: " << f << std::endl;
242  }
243  else if (cfg.has("generators"))
244  {
246  }
247 
248  // ------------------------------
249  // Original input point clouds
250  // ------------------------------
251  auto pcLocal = load_input_pc(argInputLocal.getValue(), true);
252  auto pcGlobal = load_input_pc(argInputGlobal.getValue(), false);
253 
254  std::cout << "Input point cloud #1: " << pcLocal->contents_summary()
255  << std::endl;
256  std::cout << "Input point cloud #2: " << pcGlobal->contents_summary()
257  << std::endl;
258 
259  // ------------------------------
260  // Build ICP pipeline:
261  // ------------------------------
262  auto [icp, icpParams] = mp2p_icp::icp_pipeline_from_yaml(cfg);
263 
264  if (argGenerateDebugFiles.isSet()) icpParams.generateDebugFiles = true;
265 
266  const auto initialGuess =
267  mrpt::math::TPose3D::FromString(argInitialGuess.getValue());
268 
269  // -----------------------------------------
270  // Apply filtering pipeline, if defined
271  // -----------------------------------------
272  {
274  if (argYamlConfigFileFiltersLocal.isSet())
275  {
277  argYamlConfigFileFiltersLocal.getValue());
278  }
279  else if (cfg.has(argCfgNameFiltersLocal.getValue()))
280  {
282  cfg[argCfgNameFiltersLocal.getValue()]);
283  }
284  if (!filtersLocal.empty())
285  {
286  mp2p_icp_filters::apply_filter_pipeline(filtersLocal, *pcLocal);
287  std::cout << "Filtered local map: " << pcLocal->contents_summary()
288  << std::endl;
289  }
290  }
291  {
292  mp2p_icp_filters::FilterPipeline filtersGlobal;
293  if (argYamlConfigFileFiltersGlobal.isSet())
294  {
296  argYamlConfigFileFiltersGlobal.getValue());
297  }
298  else if (cfg.has(argCfgNameFiltersGlobal.getValue()))
299  {
301  cfg[argCfgNameFiltersGlobal.getValue()]);
302  }
303  if (!filtersGlobal.empty())
304  {
305  mp2p_icp_filters::apply_filter_pipeline(filtersGlobal, *pcGlobal);
306  std::cout << "Filtered global map: " << pcGlobal->contents_summary()
307  << std::endl;
308  }
309  }
310 
311  if (argProfile.isSet()) icp->profiler().enable(true);
312 
313  const double t_ini = mrpt::Clock::nowDouble();
314 
315  mp2p_icp::Results icpResults;
316  icp->align(*pcLocal, *pcGlobal, initialGuess, icpParams, icpResults);
317 
318  const double t_end = mrpt::Clock::nowDouble();
319 
320  std::cout << "ICP result:\n";
321  icpResults.print(std::cout);
322 
323  std::cout << "- time to solve: "
324  << mrpt::system::formatTimeInterval(t_end - t_ini) << "\n";
325 }
326 
327 int main(int argc, char** argv)
328 {
329  try
330  {
331  // Parse arguments:
332  if (!cmd.parse(argc, argv)) return 1; // should exit.
333 
334  runIcp();
335  }
336  catch (const std::exception& e)
337  {
338  std::cerr << mrpt::exception_to_str(e);
339  return 1;
340  }
341  return 0;
342 }
ICP.h
Generic ICP algorithm container.
generators
static mp2p_icp_filters::GeneratorSet generators
Definition: apps/icp-run/main.cpp:133
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:25
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:72
mp2p_icp::LogRecord
Definition: LogRecord.h:30
mp2p_icp::Results::print
void print(std::ostream &o) const
Definition: Results.cpp:50
mp2p_icp::metric_map_t::PT_LAYER_RAW
constexpr static const char * PT_LAYER_RAW
Definition: metricmap.h:58
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:111
rawlogsCache
static std::map< std::string, mrpt::obs::CRawlog::Ptr > rawlogsCache
Definition: apps/icp-run/main.cpp:109
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:40
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:94
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:18
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:178
mp2p_icp_filters::GeneratorSet
std::vector< Generator::Ptr > GeneratorSet
Definition: Generator.h:198
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:342
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:255
main
int main(int argc, char **argv)
Definition: apps/icp-run/main.cpp:327
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:135
runIcp
void runIcp()
Definition: apps/icp-run/main.cpp:226
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:310


mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:12