sm2mm.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  * ------------------------------------------------------------------------- */
16 #include <mp2p_icp_filters/sm2mm.h>
17 #include <mrpt/core/Clock.h>
18 #include <mrpt/system/progress.h>
19 #include <mrpt/version.h>
20 
21 #include <iostream>
22 
24  const mrpt::maps::CSimpleMap& sm, mp2p_icp::metric_map_t& mm,
25  const mrpt::containers::yaml& yamlData, const sm2mm_options_t& options)
26 {
27  mm.clear();
28 
29  // Generators:
31  if (yamlData.has("generators"))
32  {
34  yamlData["generators"], options.verbosity);
35  }
36  else
37  {
38  std::cout << "[sm2mm] Warning: no generators defined in the pipeline, "
39  "using default generator."
40  << std::endl;
41 
42  auto defaultGen = mp2p_icp_filters::Generator::Create();
43  defaultGen->setMinLoggingLevel(options.verbosity);
44  defaultGen->initialize({});
45  generators.push_back(defaultGen);
46  }
47 
48  // Filters:
50  if (yamlData.has("filters"))
51  {
53  yamlData["filters"], options.verbosity);
54  }
55  else
56  {
57  std::cout << "[sm2mm] Warning: no filters defined in the pipeline."
58  << std::endl;
59  }
60 
61  // Final, overall filters for the whole metric map:
63  if (yamlData.has("final_filters"))
64  {
66  yamlData["final_filters"], options.verbosity);
67  }
68 
69  // sm2mm core code:
70 
71  // Parameters for twist, and possibly other user-provided variables.
75 
76  // Default values for twist variables:
77  ps.updateVariables(
78  {{"vx", .0},
79  {"vy", .0},
80  {"vz", .0},
81  {"wx", .0},
82  {"wy", .0},
83  {"wz", .0}});
84  ps.updateVariables(
85  {{"robot_x", .0},
86  {"robot_y", .0},
87  {"robot_z", .0},
88  {"robot_yaw", .0},
89  {"robot_pitch", .0},
90  {"robot_roll", .0}});
91  ps.updateVariables(options.customVariables);
92  ps.realize();
93 
94  // progress bar:
95  if (options.showProgressBar)
96  std::cout << "\n"; // Needed for the VT100 codes below.
97 
98  const double tStart = mrpt::Clock::nowDouble();
99 
100  size_t nKFs = sm.size();
101  if (options.end_index.has_value())
102  mrpt::keep_min(nKFs, *options.end_index + 1);
103 
104  size_t curKF = 0;
105  if (options.start_index.has_value())
106  mrpt::keep_max(curKF, *options.start_index);
107 
108  for (; curKF < nKFs; curKF++)
109  {
110 #if MRPT_VERSION >= 0x020b05
111  const auto& [pose, sf, twist] = sm.get(curKF);
112  if (twist.has_value())
113  {
114  ps.updateVariables(
115  {{"vx", twist->vx},
116  {"vy", twist->vy},
117  {"vz", twist->vz},
118  {"wx", twist->wx},
119  {"wy", twist->wy},
120  {"wz", twist->wz}});
121  }
122 #else
123  const auto& [pose, sf] = sm.get(curKF);
124 #endif
125  ASSERT_(pose);
126  ASSERT_(sf);
127  const mrpt::poses::CPose3D robotPose = pose->getMeanVal();
128 
129  // Update pose variables:
130  ps.updateVariables(
131  {{"robot_x", robotPose.x()},
132  {"robot_y", robotPose.y()},
133  {"robot_z", robotPose.z()},
134  {"robot_yaw", robotPose.yaw()},
135  {"robot_pitch", robotPose.pitch()},
136  {"robot_roll", robotPose.roll()}});
137  ps.realize();
138 
139  for (const auto& obs : *sf)
140  {
141  ASSERT_(obs);
142  obs->load();
143 
144  bool handled = mp2p_icp_filters::apply_generators(
145  generators, *obs, mm, robotPose);
146 
147  if (!handled) continue;
148 
149  // process it:
151  obs->unload();
152  }
153 
154 #if 0
155  // sanity checks:
156  for (const auto& [name, map] : mm.layers)
157  {
158  const auto* pc = mp2p_icp::MapToPointsMap(*map);
159  if (!pc) continue; // not a point map
160  const bool sanityPassed = mp2p_icp::pointcloud_sanity_check(*pc);
161  ASSERTMSG_(
162  sanityPassed,
163  mrpt::format(
164  "Sanity check did not pass for layer: '%s'", name.c_str()));
165  }
166 #endif
167 
168  // progress bar:
169  if (options.showProgressBar)
170  {
171  const size_t N = nKFs;
172  const double pc = (1.0 * curKF) / N;
173 
174  const double tNow = mrpt::Clock::nowDouble();
175  const double ETA = pc > 0 ? (tNow - tStart) * (1.0 / pc - 1) : .0;
176  const double totalTime = ETA + (tNow - tStart);
177 
178  std::cout
179  << "\033[A\33[2KT\r" // VT100 codes: cursor up and clear
180  // line
181  << mrpt::system::progress(pc, 30)
182  << mrpt::format(
183  " %6zu/%6zu (%.02f%%) ETA=%s / T=%s\n", curKF, N,
184  100 * pc, mrpt::system::formatTimeInterval(ETA).c_str(),
185  mrpt::system::formatTimeInterval(totalTime).c_str());
186  std::cout.flush();
187  }
188  } // end for each KF.
189 
190  // Final optional filtering:
191  if (!finalFilters.empty())
192  {
193  std::cout << "Applying 'final_filters'..." << std::endl;
194 
195  mp2p_icp_filters::apply_filter_pipeline(finalFilters, mm);
196 
197  std::cout << "Done with 'final_filters'." << std::endl;
198  }
199 }
mp2p_icp::ParameterSource
Definition: Parameterizable.h:42
generators
static mp2p_icp_filters::GeneratorSet generators
Definition: apps/icp-run/main.cpp:133
mp2p_icp_filters::sm2mm_options_t::customVariables
std::vector< std::pair< std::string, double > > customVariables
Definition: sm2mm.h:37
mp2p_icp_filters::sm2mm_options_t::showProgressBar
bool showProgressBar
Definition: sm2mm.h:36
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::simplemap_to_metricmap
void simplemap_to_metricmap(const mrpt::maps::CSimpleMap &sm, mp2p_icp::metric_map_t &outMap, const mrpt::containers::yaml &pipeline, const sm2mm_options_t &options={})
Definition: sm2mm.cpp:23
mp2p_icp::metric_map_t::clear
virtual void clear()
Definition: metricmap.cpp:366
mp2p_icp::pointcloud_sanity_check
bool pointcloud_sanity_check(const mrpt::maps::CPointsMap &pc, bool printWarnings=true)
Definition: pointcloud_sanity_check.cpp:19
pointcloud_sanity_check.h
Checks for consistent length of field vectors.
mp2p_icp::ParameterSource::realize
void realize()
Definition: Parameterizable.cpp:37
Generator.h
Base virtual class for point cloud filters.
mp2p_icp_filters::sm2mm_options_t::verbosity
mrpt::system::VerbosityLevel verbosity
Definition: sm2mm.h:35
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
mp2p_icp::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:648
mp2p_icp_filters::sm2mm_options_t
Options for simplemap_to_metricmap()
Definition: sm2mm.h:30
mp2p_icp_filters::FilterPipeline
std::vector< FilterBase::Ptr > FilterPipeline
Definition: FilterBase.h:75
mp2p_icp_filters::GeneratorSet
std::vector< Generator::Ptr > GeneratorSet
Definition: Generator.h:198
sm2mm.h
simplemap-to-metricmap utility function
FilterBase.h
Base virtual class for point cloud filters.
mp2p_icp::ParameterSource::updateVariables
void updateVariables(const std::vector< std::pair< std::string, double >> &nameValuePairs)
Definition: Parameterizable.h:57
mp2p_icp_filters::sm2mm_options_t::start_index
std::optional< size_t > start_index
Definition: sm2mm.h:38
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:49
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
mp2p_icp::AttachToParameterSource
void AttachToParameterSource(std::vector< std::shared_ptr< T >> &setObjects, ParameterSource &source)
Definition: Parameterizable.h:140
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:76
mp2p_icp_filters::sm2mm_options_t::end_index
std::optional< size_t > end_index
Definition: sm2mm.h:39
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