Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
mp2p_icp_filters::Generator Class Reference

#include <Generator.h>

Inheritance diagram for mp2p_icp_filters::Generator:
Inheritance graph
[legend]

Classes

struct  Parameters
 

Public Member Functions

 Generator ()
 

Protected Member Functions

virtual bool filterPointCloud (const mrpt::maps::CPointsMap &pc, mp2p_icp::metric_map_t &out) const
 
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
 
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
 

Protected Attributes

bool initialized_ = false
 
std::regex process_class_names_regex_
 
std::regex process_sensor_labels_regex_
 

Generator API

Parameters params_
 
virtual void initialize (const mrpt::containers::yaml &cfg_block)
 
virtual void process (const mrpt::obs::CObservation &input_raw, mp2p_icp::metric_map_t &inOut) const
 

Detailed Description

Generic base class providing process(), converting a generic mrpt::obs::CObservation into a metric_map_t with just a point cloud layer (named raw).

This pointcloud-t can optionally then be passed through one or more FilterBase implementations to detect features, decimate it, etc.

Specializations of Generator may exist and could be implemented to exploit the structured information in the original CObservation data to be more efficient in detecting features (e.g. corners, etc.).

Internally, fifferent signatures exists for:

Derived classes may implement all or only one of those methods. An exception NotImplementedError will be thrown if an non-implemented method is called.

Note
process() is not required to be thread (multientry) safe.

A set of generators can be loaded from a YAML file and applied together using mp2p_icp_filters::apply_generators().

Definition at line 72 of file Generator.h.

Constructor & Destructor Documentation

◆ Generator()

Generator::Generator ( )

Definition at line 28 of file Generator.cpp.

Member Function Documentation

◆ filterPointCloud()

bool Generator::filterPointCloud ( const mrpt::maps::CPointsMap &  pc,
mp2p_icp::metric_map_t out 
) const
protectedvirtual

Process a 2D/3D point-cloud.

Returns
false if not implemented

Definition at line 177 of file Generator.cpp.

◆ filterRotatingScan()

bool Generator::filterRotatingScan ( const mrpt::obs::CObservationRotatingScan &  pc,
mp2p_icp::metric_map_t out 
) const
protectedvirtual

Process a 3D lidar scan.

Returns
false if not implemented

Definition at line 202 of file Generator.cpp.

◆ filterScan2D()

bool Generator::filterScan2D ( const mrpt::obs::CObservation2DRangeScan &  pc,
mp2p_icp::metric_map_t out 
) const
protectedvirtual

Process a 2D lidar scan.

Returns
false if not implemented

Definition at line 156 of file Generator.cpp.

◆ filterScan3D()

bool Generator::filterScan3D ( const mrpt::obs::CObservation3DRangeScan &  pc,
mp2p_icp::metric_map_t out 
) const
protectedvirtual

Process a depth camera observation.

Returns
false if not implemented

Definition at line 170 of file Generator.cpp.

◆ filterVelodyneScan()

bool Generator::filterVelodyneScan ( const mrpt::obs::CObservationVelodyneScan &  pc,
mp2p_icp::metric_map_t out 
) const
protectedvirtual

Process a 3D lidar scan.

Returns
false if not implemented

Definition at line 163 of file Generator.cpp.

◆ initialize()

void Generator::initialize ( const mrpt::containers::yaml &  cfg_block)
virtual

Loads, from a YAML configuration block, all the common, and implementation-specific parameters. If you redefine this method, remember calling this method on the parent class.

Definition at line 38 of file Generator.cpp.

◆ process()

void Generator::process ( const mrpt::obs::CObservation &  input_raw,
mp2p_icp::metric_map_t inOut 
) const
virtual

See docs above for Generator. This method dispatches the observation by type to the corresponding virtual method

Definition at line 53 of file Generator.cpp.

Member Data Documentation

◆ initialized_

bool mp2p_icp_filters::Generator::initialized_ = false
protected

Definition at line 147 of file Generator.h.

◆ params_

Parameters mp2p_icp_filters::Generator::params_

Definition at line 121 of file Generator.h.

◆ process_class_names_regex_

std::regex mp2p_icp_filters::Generator::process_class_names_regex_
protected

Definition at line 148 of file Generator.h.

◆ process_sensor_labels_regex_

std::regex mp2p_icp_filters::Generator::process_sensor_labels_regex_
protected

Definition at line 149 of file Generator.h.


The documentation for this class was generated from the following files:


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:05