Go to the documentation of this file.
   16 #include <mrpt/3rdparty/tclap/CmdLine.h> 
   17 #include <mrpt/containers/yaml.h> 
   18 #include <mrpt/io/lazy_load_path.h> 
   19 #include <mrpt/system/COutputLogger.h> 
   20 #include <mrpt/system/filesystem.h> 
   23 static TCLAP::CmdLine 
cmd(
"sm2mm");
 
   25 static TCLAP::ValueArg<std::string> 
argInput(
 
   26     "i", 
"input", 
"Input .simplemap file", 
true, 
"map.simplemap", 
"map.simplemap", 
cmd);
 
   28 static TCLAP::ValueArg<std::string> 
argOutput(
 
   29     "o", 
"output", 
"Output .mm file to write to", 
true, 
"out.mm", 
"out.mm", 
cmd);
 
   31 static TCLAP::ValueArg<std::string> 
argPlugins(
 
   33     "One or more (comma separated) *.so files to load as plugins, e.g. " 
   34     "defining new CMetricMap classes",
 
   35     false, 
"foobar.so", 
"foobar.so", 
cmd);
 
   39     "YAML file with the mp2p_icp_filters pipeline to load. It can optionally " 
   40     "contain a `filters:`, a `generators:`, and a `final_filters:` sections. " 
   41     "If this argument is not provided, the default generator will be used and " 
   42     "no filtering will be applied, which might be ok in some cases. " 
   43     "See the app README for examples:\n" 
   44     "https://github.com/MOLAorg/mp2p_icp/tree/master/apps/sm2mm",
 
   45     false, 
"pipeline.yaml", 
"pipeline.yaml", 
cmd);
 
   48     "v", 
"verbosity", 
"Verbosity level: ERROR|WARN|INFO|DEBUG (Default: INFO)", 
false, 
"", 
"INFO",
 
   53     "Lazy-load base directory for datasets with externally-stored observations", 
false,
 
   54     "dataset_Images", 
"<ExternalsDirectory>", 
cmd);
 
   57     "", 
"no-progress-bar",
 
   58     "Disables the progress bar. Useful for cleaner output when using DEBUG " 
   64     "If provided, the simplemap keyframes until this index will be discarded " 
   65     "and it will start at this point.",
 
   70     "If provided, the simplemap keyframes will be processed up to this index " 
   76     const auto& filSM = 
argInput.getValue();
 
   78     mrpt::maps::CSimpleMap sm;
 
   80     std::cout << 
"[sm2mm] Reading simplemap from: '" << filSM << 
"'..." << std::endl;
 
   83     sm.loadFromFile(filSM);
 
   85     std::cout << 
"[sm2mm] Done read simplemap with " << sm.size() << 
" keyframes." << std::endl;
 
   89     mrpt::containers::yaml yamlData;  
 
   94         ASSERT_FILE_EXISTS_(filYaml);
 
   95         yamlData = mrpt::containers::yaml::FromFile(filYaml);
 
  100     mrpt::system::VerbosityLevel logLevel = mrpt::system::LVL_INFO;
 
  103         using vl = mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>;
 
  123     const auto filOut = 
argOutput.getValue();
 
  124     std::cout << 
"[sm2mm] Writing metric map to: '" << filOut << 
"'..." << std::endl;
 
  127         THROW_EXCEPTION_FMT(
"Error writing to target file '%s'", filOut.c_str());
 
  130 int main(
int argc, 
char** argv)
 
  135         if (!
cmd.parse(argc, argv)) 
return 1;  
 
  139     catch (
const std::exception& e)
 
  141         std::cerr << e.what();
 
  
static TCLAP::ValueArg< std::string > argOutput("o", "output", "Output .mm file to write to", true, "out.mm", "out.mm", cmd)
static TCLAP::ValueArg< std::string > argInput("i", "input", "Input .simplemap file", true, "map.simplemap", "map.simplemap", cmd)
static TCLAP::ValueArg< std::string > argPlugins("l", "load-plugins", "One or more (comma separated) *.so files to load as plugins, e.g. " "defining new CMetricMap classes", false, "foobar.so", "foobar.so", cmd)
bool save_to_file(const std::string &fileName) const
static TCLAP::CmdLine cmd("sm2mm")
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={})
static TCLAP::ValueArg< std::string > arg_verbosity_level("v", "verbosity", "Verbosity level: ERROR|WARN|INFO|DEBUG (Default: INFO)", false, "", "INFO", cmd)
mrpt::system::VerbosityLevel verbosity
static TCLAP::ValueArg< std::string > arg_lazy_load_base_dir("", "externals-dir", "Lazy-load base directory for datasets with externally-stored observations", false, "dataset_Images", "<ExternalsDirectory>", cmd)
int main(int argc, char **argv)
Options for simplemap_to_metricmap()
virtual std::string contents_summary() const
static TCLAP::ValueArg< std::string > argPipeline("p", "pipeline", "YAML file with the mp2p_icp_filters pipeline to load. It can optionally " "contain a `filters:`, a `generators:`, and a `final_filters:` sections. " "If this argument is not provided, the default generator will be used and " "no filtering will be applied, which might be ok in some cases. " "See the app README for examples:\n" "https://github.com/MOLAorg/mp2p_icp/tree/master/apps/sm2mm", false, "pipeline.yaml", "pipeline.yaml", cmd)
simplemap-to-metricmap utility function
static TCLAP::SwitchArg argNoProgressBar("", "no-progress-bar", "Disables the progress bar. Useful for cleaner output when using DEBUG " "verbosity level.", cmd)
std::optional< size_t > start_index
Generic container of pointcloud(s), extracted features and other maps.
static TCLAP::ValueArg< size_t > argIndexTo("", "to-index", "If provided, the simplemap keyframes will be processed up to this index " "only.", false, 0, "0", cmd)
std::optional< size_t > end_index
static TCLAP::ValueArg< size_t > argIndexFrom("", "from-index", "If provided, the simplemap keyframes until this index will be discarded " "and it will start at this point.", false, 0, "0", cmd)
mp2p_icp
Author(s): 
autogenerated on Mon May 26 2025 02:45:49