Go to the documentation of this file.
   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> 
   30 static TCLAP::CmdLine 
cmd(
"icp-run");
 
   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);
 
   44     "", 
"input-global", 
"Global input point cloud/map. Same format than input-local. ", 
true,
 
   45     "pointcloud2.txt", 
"pointcloud2.txt", 
cmd);
 
   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);
 
   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);
 
   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);
 
   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);
 
   79     "", 
"entry-name-filters-global",
 
   80     "Overrides the map name in the YAML configuration file for global map " 
   82     false, 
"filters", 
"filters", 
cmd);
 
   85     "", 
"entry-name-filters-local",
 
   86     "Overrides the map name in the YAML configuration file for local map " 
   88     false, 
"filters", 
"filters", 
cmd);
 
   92     "SE(3) transformation of local wrt global, to use as initial guess for the " 
   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);
 
   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.",
 
  104 static TCLAP::SwitchArg 
argProfile(
"", 
"profiler", 
"Enables the ICP profiler.", 
cmd);
 
  114     mrpt::img::CImage::setImagesPathBase(mrpt::obs::CRawlog::detectImagesDirectory(
filename));
 
  118     r = mrpt::obs::CRawlog::Create();
 
  120     std::cout << 
"Loading rawlog file `" << 
filename << 
"`..." << std::endl;
 
  122     bool rawlogReadOk = r->loadFromRawLogFile(
filename, 
true);
 
  123     ASSERT_(rawlogReadOk);
 
  125     std::cout << 
"Done, " << r->size() << 
" entries." << std::endl;
 
  132 static mp2p_icp::metric_map_t::Ptr 
pc_from_rawlog(
const mrpt::obs::CRawlog& r, 
const size_t index)
 
  134     ASSERT_LT_(index, r.size());
 
  138         std::cout << 
"[warning] Using default mp2p_icp_filters::Generator since no " 
  139                      "YAML file was given describing custom generators.\n";
 
  141         auto defaultGen = mp2p_icp_filters::Generator::Create();
 
  142         defaultGen->initialize({});
 
  146     auto pc = mp2p_icp::metric_map_t::Create();
 
  148     auto o = r.getAsGeneric(index);
 
  151     if (
auto sf = std::dynamic_pointer_cast<mrpt::obs::CSensoryFrame>(o); sf)
 
  156     else if (
auto obs = std::dynamic_pointer_cast<mrpt::obs::CObservation>(o); obs)
 
  162         auto e = r.getAsGeneric(index);
 
  164             "Rawlog index %u is neither CSensoryFrame or CObservation. Found " 
  166             static_cast<unsigned int>(index), e->GetRuntimeClass()->className);
 
  175     if (
auto extPos = 
filename.find(
".rawlog:"); extPos != std::string::npos)
 
  177         const auto sepPos      = extPos + 7;
 
  178         const auto fil         = 
filename.substr(0, sepPos);
 
  179         const auto rawlogIndex = std::stod(
filename.substr(sepPos + 1));
 
  187     if (
auto extPos = 
filename.find(
".mm"); extPos != std::string::npos)
 
  189         auto r = mp2p_icp::metric_map_t::Create();
 
  191         bool readOk = r->load_from_file(
filename);
 
  198     if (
auto extPos = 
filename.find(
".icplog"); extPos != std::string::npos)
 
  202         ASSERT_(icplogFileReadOK);
 
  204         auto r = mp2p_icp::metric_map_t::Create();
 
  212     auto pc                                          = mp2p_icp::metric_map_t::Create();
 
  231         std::cout << 
"Created " << 
generators.size() << 
" generators from: " << 
f << std::endl;
 
  233     else if (
cfg.has(
"generators"))
 
  244     std::cout << 
"Input point cloud #1: " << pcLocal->contents_summary() << std::endl;
 
  245     std::cout << 
"Input point cloud #2: " << pcGlobal->contents_summary() << std::endl;
 
  254     const auto initialGuess = mrpt::math::TPose3D::FromString(
argInitialGuess.getValue());
 
  271         if (!filtersLocal.empty())
 
  274             std::cout << 
"Filtered local map: " << pcLocal->contents_summary() << std::endl;
 
  289         if (!filtersGlobal.empty())
 
  292             std::cout << 
"Filtered global map: " << pcGlobal->contents_summary() << std::endl;
 
  296     if (
argProfile.isSet()) icp->profiler().enable(
true);
 
  298     const double t_ini = mrpt::Clock::nowDouble();
 
  301     icp->align(*pcLocal, *pcGlobal, initialGuess, icpParams, icpResults);
 
  303     const double t_end = mrpt::Clock::nowDouble();
 
  305     std::cout << 
"ICP result:\n";
 
  306     icpResults.
print(std::cout);
 
  308     std::cout << 
"- time to solve: " << mrpt::system::formatTimeInterval(t_end - t_ini) << 
"\n";
 
  311 int main(
int argc, 
char** argv)
 
  316         if (!
cmd.parse(argc, argv)) 
return 1;  
 
  320     catch (
const std::exception& e)
 
  322         std::cerr << mrpt::exception_to_str(e);
 
  
Generic ICP algorithm container.
static mp2p_icp_filters::GeneratorSet generators
void apply_filter_pipeline(const FilterPipeline &filters, mp2p_icp::metric_map_t &inOut, const mrpt::optional_ref< mrpt::system::CTimeLogger > &profiler=std::nullopt)
FilterPipeline filter_pipeline_from_yaml_file(const std::string &filename, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
void print(std::ostream &o) const
constexpr static const char * PT_LAYER_RAW
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)
Base virtual class for point cloud filters.
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)
static mrpt::obs::CRawlog::Ptr load_rawlog(const std::string &filename)
static std::map< std::string, mrpt::obs::CRawlog::Ptr > rawlogsCache
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)
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)
FilterPipeline filter_pipeline_from_yaml(const mrpt::containers::yaml &c, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
bool load_from_file(const std::string &fileName)
std::vector< FilterBase::Ptr > FilterPipeline
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)
static mp2p_icp::metric_map_t::Ptr load_input_pc(const std::string &filename, bool local)
std::vector< Generator::Ptr > GeneratorSet
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)
GeneratorSet generators_from_yaml_file(const std::string &filename, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
metric_map_t::ConstPtr pcGlobal
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)
Base virtual class for point cloud filters.
Loads and setup an ICP pipeline from a YAML configuration file.
mrpt::maps::CSimplePointsMap::Ptr load_xyz_file(const std::string &fil)
static TCLAP::SwitchArg argProfile("", "profiler", "Enables the ICP profiler.", cmd)
static TCLAP::ValueArg< std::string > argInputGlobal("", "input-global", "Global input point cloud/map. Same format than input-local. ", true, "pointcloud2.txt", "pointcloud2.txt", cmd)
static TCLAP::CmdLine cmd("icp-run")
Generic representation of pointcloud(s) and/or extracted features.
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)
metric_map_t::ConstPtr pcLocal
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)
int main(int argc, char **argv)
Unit tests common utilities.
static mp2p_icp::metric_map_t::Ptr pc_from_rawlog(const mrpt::obs::CRawlog &r, const size_t index)
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)
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)
GeneratorSet generators_from_yaml(const mrpt::containers::yaml &c, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
mp2p_icp
Author(s): 
autogenerated on Mon May 26 2025 02:45:49