mp2p_icp_filters library
Overview
LiDAR and point cloud segmentation and filtering algorithms.
// typedefs typedef std::vector<FilterBase::Ptr> mp2p_icp_filters::FilterPipeline; typedef std::vector<Generator::Ptr> mp2p_icp_filters::GeneratorSet; // enums enum mp2p_icp_filters::DecimateMethod; enum mp2p_icp_filters::MotionCompensationMethod; enum mp2p_icp_filters::TimestampAdjustMethod; // structs struct mp2p_icp_filters::NotImplementedError; struct mp2p_icp_filters::sm2mm_options_t; // classes class mp2p_icp_filters::FilterAbsoluteTimestamp; class mp2p_icp_filters::FilterAdjustTimestamps; class mp2p_icp_filters::FilterBase; class mp2p_icp_filters::FilterBoundingBox; class mp2p_icp_filters::FilterByExpression; class mp2p_icp_filters::FilterByIntensity; class mp2p_icp_filters::FilterByRange; class mp2p_icp_filters::FilterByRing; class mp2p_icp_filters::FilterClear; class mp2p_icp_filters::FilterCurvature; class mp2p_icp_filters::FilterDecimate; class mp2p_icp_filters::FilterDecimateAdaptive; class mp2p_icp_filters::FilterDecimateVoxels; class mp2p_icp_filters::FilterDeleteLayer; class mp2p_icp_filters::FilterDeskew; class mp2p_icp_filters::FilterEdgesPlanes; class mp2p_icp_filters::FilterFartherPointSampling; class mp2p_icp_filters::FilterMLS; class mp2p_icp_filters::FilterMerge; class mp2p_icp_filters::FilterNormalizeIntensity; class mp2p_icp_filters::FilterPoleDetector; class mp2p_icp_filters::FilterRemoveByVoxelOccupancy; class mp2p_icp_filters::FilterRemovePointCloudField; class mp2p_icp_filters::FilterRenameLayer; class mp2p_icp_filters::FilterSOR; class mp2p_icp_filters::FilterVoxelSOR; class mp2p_icp_filters::FilterVoxelSlice; class mp2p_icp_filters::Generator; class mp2p_icp_filters::GeneratorEdgesFromCurvature; class mp2p_icp_filters::GeneratorEdgesFromRangeImage; class mp2p_icp_filters::PointCloudToVoxelGrid; class mp2p_icp_filters::PointCloudToVoxelGridSingle; // global variables static constexpr static std::string_view mp2p_icp_filters::POINT_FIELD_INTENSITY = "intensity"; static constexpr static std::string_view mp2p_icp_filters::POINT_FIELD_RING_ID = "ring"; static constexpr static std::string_view mp2p_icp_filters::POINT_FIELD_TIMESTAMP = "t"; // global functions void mp2p_icp_filters::apply_filter_pipeline( const FilterPipeline& filters, mp2p_icp::metric_map_t& inOut, const mrpt::optional_ref<mrpt::system::CTimeLogger>& profiler = std::nullopt ); FilterPipeline mp2p_icp_filters::filter_pipeline_from_yaml( const mrpt::containers::yaml& c, const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO ); FilterPipeline mp2p_icp_filters::filter_pipeline_from_yaml_file( const std::string& filename, const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO ); bool mp2p_icp_filters::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, const mrpt::optional_ref<mrpt::system::CTimeLogger>& profiler = std::nullopt ); mp2p_icp::metric_map_t mp2p_icp_filters::apply_generators( const GeneratorSet& generators, const mrpt::obs::CObservation& obs, const std::optional<mrpt::poses::CPose3D>& robotPose = std::nullopt ); bool mp2p_icp_filters::apply_generators( const GeneratorSet& generators, const mrpt::obs::CSensoryFrame& sf, mp2p_icp::metric_map_t& output, const std::optional<mrpt::poses::CPose3D>& robotPose = std::nullopt ); mp2p_icp::metric_map_t mp2p_icp_filters::apply_generators( const GeneratorSet& generators, const mrpt::obs::CSensoryFrame& sf, const std::optional<mrpt::poses::CPose3D>& robotPose = std::nullopt ); GeneratorSet mp2p_icp_filters::generators_from_yaml( const mrpt::containers::yaml& c, const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO ); GeneratorSet mp2p_icp_filters::generators_from_yaml_file( const std::string& filename, const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO ); mrpt::maps::CPointsMap::Ptr mp2p_icp_filters::GetOrCreatePointLayer( mp2p_icp::metric_map_t& m, const std::string& layerName, bool allowEmptyName = true, const std::string& classForLayerCreation = "mrpt::maps::CSimplePointsMap" ); void mp2p_icp_filters::simplemap_to_metricmap( const mrpt::maps::CSimpleMap& sm, mp2p_icp::metric_map_t& outMap, const mrpt::containers::yaml& pipeline, const sm2mm_options_t& options = {} );
Typedefs
typedef std::vector<FilterBase::Ptr> mp2p_icp_filters::FilterPipeline
A sequence of filters
typedef std::vector<Generator::Ptr> mp2p_icp_filters::GeneratorSet
A set of generators
Global Functions
void mp2p_icp_filters::apply_filter_pipeline( const FilterPipeline& filters, mp2p_icp::metric_map_t& inOut, const mrpt::optional_ref<mrpt::system::CTimeLogger>& profiler = std::nullopt )
Applies a pipeline of filters to a given metric_map_t
FilterPipeline mp2p_icp_filters::filter_pipeline_from_yaml( const mrpt::containers::yaml& c, const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO )
Creates a pipeline of filters from a YAML configuration block (a sequence). Refer to YAML file examples. Returns an empty pipeline for an empty or null yaml node. Returned filters are already initialize()’d.
bool mp2p_icp_filters::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, const mrpt::optional_ref<mrpt::system::CTimeLogger>& profiler = std::nullopt )
Applies a set of generators to a given input raw observation(s) and generates a metric_map_t.
The former contents on the output metric_map_t object are untouched, so calling this function several times can be used to accumulate point cloud elements from different sensors.
Returns:
true if any of the generators actually processed “obs”
GeneratorSet mp2p_icp_filters::generators_from_yaml( const mrpt::containers::yaml& c, const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO )
Creates a set of generators from a YAML configuration block (a sequence). Returns an empty generators set for an empty or null yaml node. Refer to YAML file examples. Returned generators are already initialize()’d.
void mp2p_icp_filters::simplemap_to_metricmap( const mrpt::maps::CSimpleMap& sm, mp2p_icp::metric_map_t& outMap, const mrpt::containers::yaml& pipeline, const sm2mm_options_t& options = {} )
Utility function to build metric maps (”.mm”) from raw observations as a simple map (”.sm”). For a ready-to-use CLI application exposing this function, as well as documentation on the meaning of each argument, see sm2mm.
The former contents of outMap are cleared.
If options.georeferencing is set, robot poses are transformed into the ENU frame (via T_enu_to_map \oplus robotPose) before being handed to the generators, and the output map is tagged with the corresponding georeferencing metadata (with T_enu_to_map set to identity).