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);
45 "Global input point cloud/map. Same format than input-local. ",
true,
46 "pointcloud2.txt",
"pointcloud2.txt",
cmd);
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);
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);
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);
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);
80 "",
"entry-name-filters-global",
81 "Overrides the map name in the YAML configuration file for global map "
83 false,
"filters",
"filters",
cmd);
86 "",
"entry-name-filters-local",
87 "Overrides the map name in the YAML configuration file for local map "
89 false,
"filters",
"filters",
cmd);
93 "SE(3) transformation of local wrt global, to use as initial guess for the "
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);
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.",
106 "",
"profiler",
"Enables the ICP profiler.",
cmd);
116 mrpt::img::CImage::setImagesPathBase(
117 mrpt::obs::CRawlog::detectImagesDirectory(
filename));
121 r = mrpt::obs::CRawlog::Create();
123 std::cout <<
"Loading rawlog file `" <<
filename <<
"`..." << std::endl;
125 bool rawlogReadOk = r->loadFromRawLogFile(
filename,
true);
126 ASSERT_(rawlogReadOk);
128 std::cout <<
"Done, " << r->size() <<
" entries." << std::endl;
136 const mrpt::obs::CRawlog& r,
const size_t index)
138 ASSERT_LT_(index, r.size());
143 <<
"[warning] Using default mp2p_icp_filters::Generator since no "
144 "YAML file was given describing custom generators.\n";
146 auto defaultGen = mp2p_icp_filters::Generator::Create();
147 defaultGen->initialize({});
151 auto pc = mp2p_icp::metric_map_t::Create();
153 auto o = r.getAsGeneric(index);
156 if (
auto sf = std::dynamic_pointer_cast<mrpt::obs::CSensoryFrame>(o); sf)
161 else if (
auto obs = std::dynamic_pointer_cast<mrpt::obs::CObservation>(o);
168 auto e = r.getAsGeneric(index);
170 "Rawlog index %u is neither CSensoryFrame or CObservation. Found "
172 static_cast<unsigned int>(index), e->GetRuntimeClass()->className);
182 if (
auto extPos =
filename.find(
".rawlog:"); extPos != std::string::npos)
184 const auto sepPos = extPos + 7;
185 const auto fil =
filename.substr(0, sepPos);
186 const auto rawlogIndex = std::stod(
filename.substr(sepPos + 1));
194 if (
auto extPos =
filename.find(
".mm"); extPos != std::string::npos)
196 auto r = mp2p_icp::metric_map_t::Create();
198 bool readOk = r->load_from_file(
filename);
205 if (
auto extPos =
filename.find(
".icplog"); extPos != std::string::npos)
209 ASSERT_(icplogFileReadOK);
211 auto r = mp2p_icp::metric_map_t::Create();
217 mrpt::maps::CSimplePointsMap::Ptr points =
220 auto pc = mp2p_icp::metric_map_t::Create();
241 <<
" generators from: " <<
f << std::endl;
243 else if (
cfg.has(
"generators"))
254 std::cout <<
"Input point cloud #1: " << pcLocal->contents_summary()
256 std::cout <<
"Input point cloud #2: " << pcGlobal->contents_summary()
266 const auto initialGuess =
284 if (!filtersLocal.empty())
287 std::cout <<
"Filtered local map: " << pcLocal->contents_summary()
303 if (!filtersGlobal.empty())
306 std::cout <<
"Filtered global map: " << pcGlobal->contents_summary()
311 if (
argProfile.isSet()) icp->profiler().enable(
true);
313 const double t_ini = mrpt::Clock::nowDouble();
316 icp->align(*pcLocal, *pcGlobal, initialGuess, icpParams, icpResults);
318 const double t_end = mrpt::Clock::nowDouble();
320 std::cout <<
"ICP result:\n";
321 icpResults.
print(std::cout);
323 std::cout <<
"- time to solve: "
324 << mrpt::system::formatTimeInterval(t_end - t_ini) <<
"\n";
327 int main(
int argc,
char** argv)
332 if (!
cmd.parse(argc, argv))
return 1;
336 catch (
const std::exception& e)
338 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 Wed Oct 23 2024 02:45:40