Go to the documentation of this file.
16 #include <mrpt/containers/yaml.h>
17 #include <mrpt/maps/CPointsMap.h>
18 #include <mrpt/obs/obs_frwds.h>
19 #include <mrpt/rtti/CObject.h>
20 #include <mrpt/system/COutputLogger.h>
73 public mrpt::system::COutputLogger
88 virtual void initialize(
const mrpt::containers::yaml& cfg_block);
95 const mrpt::obs::CObservation& input_raw,
129 const mrpt::obs::CObservation2DRangeScan& pc,
133 const mrpt::obs::CObservation3DRangeScan& pc,
137 const mrpt::obs::CObservationVelodyneScan& pc,
144 const mrpt::obs::CObservationRotatingScan& pc,
185 const mrpt::containers::yaml& c,
186 const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO);
197 const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO);
virtual bool filterPointCloud(const mrpt::maps::CPointsMap &pc, mp2p_icp::metric_map_t &out) const
virtual void initialize(const mrpt::containers::yaml &cfg_block)
static mp2p_icp_filters::GeneratorSet generators
std::regex process_class_names_regex_
constexpr static const char * PT_LAYER_RAW
std::string process_class_names_regex
void load_from_yaml(const mrpt::containers::yaml &c)
virtual bool filterRotatingScan(const mrpt::obs::CObservationRotatingScan &pc, mp2p_icp::metric_map_t &out) const
virtual bool filterScan2D(const mrpt::obs::CObservation2DRangeScan &pc, mp2p_icp::metric_map_t &out) const
bool throw_on_unhandled_observation_class
void apply_generators(const GeneratorSet &generators, const mrpt::obs::CObservation &obs, mp2p_icp::metric_map_t &output)
std::vector< Generator::Ptr > GeneratorSet
std::string process_sensor_labels_regex
GeneratorSet generators_from_yaml_file(const std::string &filename, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
Generic representation of pointcloud(s) and/or extracted features.
Generic container of pointcloud(s), extracted features and other maps.
virtual void process(const mrpt::obs::CObservation &input_raw, mp2p_icp::metric_map_t &inOut) const
std::string target_pointcloud_layer
std::regex process_sensor_labels_regex_
virtual bool filterScan3D(const mrpt::obs::CObservation3DRangeScan &pc, mp2p_icp::metric_map_t &out) const
virtual bool filterVelodyneScan(const mrpt::obs::CObservationVelodyneScan &pc, mp2p_icp::metric_map_t &out) const
GeneratorSet generators_from_yaml(const mrpt::containers::yaml &c, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)