Point Cloud Filters

Point cloud Filters in mp2p_icp are used to modify or extract part of the information from an input point cloud. This can involve tasks like removing noise, downsampling, segmenting points into different layers based on properties (like intensity or curvature), or adjusting per-point attributes (like timestamps or intensity).

All filters inherit from mp2p_icp_filters::FilterBase and can be configured either programmatically or via a YAML file using the filter pipeline API, e.g. mp2p_icp_filters::filter_pipeline_from_yaml() or mp2p_icp_filters::filter_pipeline_from_yaml_file().




Filter: FilterAdjustTimestamps

Description: Modifies the per-point timestamps of a map layer according to a set of criteria.

Parameters:

  • pointcloud_layer (std::string): The name of the point cloud layer to process.

  • silently_ignore_no_timestamps (bool, default: false): If true, no exception is thrown if the input layer does not contain timestamps; an empty output is produced instead.

  • time_offset (double, default: 0.0): An optional time offset to be added on top of the adjustment. Useful for synchronizing multiple sensors.

  • method (TimestampAdjustMethod, default: MiddleIsZero): The criterion for adjusting timestamps:
    • EarliestIsZero: Adjusts such that the earliest timestamp is 0. Successive ones represent real elapsed seconds.

    • MiddleIsZero: Adjusts such that the middle timestamp is 0. The rest are positive/negative elapsed seconds.

    • Normalize: Normalizes all timestamps to the range \([0, 1]\).

filters:
  #...
  - class_name: mp2p_icp_filters::FilterAdjustTimestamps
    params:
      pointcloud_layer: 'raw'
      silently_ignore_no_timestamps: true
      method: 'MiddleIsZero'

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterAdjustTimestamps

Filter: FilterBoundingBox

Description: Splits a point cloud into points inside and outside a given 3D bounding box.

Parameters:

  • input_pointcloud_layer (std::string, default: raw): The input point cloud layer name.

  • inside_pointcloud_layer (std::string, optional): The output layer name for points INSIDE the bounding box. If empty, these points are discarded.

  • outside_pointcloud_layer (std::string, optional): The output layer name for points OUTSIDE the bounding box. If empty, these points are discarded.

  • bounding_box_min (float[3]): The \((x, y, z)\) coordinates of the minimum corner of the bounding box (e.g., [-10, -10, -5]). Can use robocentric variables (e.g., robot_x).

  • bounding_box_max (float[3]): The \((x, y, z)\) coordinates of the maximum corner of the bounding box (e.g., [10, 10, 5]). Can use robocentric variables.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterBoundingBox
    params:
      input_pointcloud_layer: 'raw'
      inside_pointcloud_layer: 'close_points'
      bounding_box_min: [ -10, -10, -1 ]
      bounding_box_max: [ 10, 10, 5 ]

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterBoundingBox

Filter: FilterByIntensity

Description: Thresholds an input cloud by its intensity values, segmenting points into low, mid, and high intensity layers.

Parameters:

  • input_pointcloud_layer (std::string): The input point cloud layer name.

  • output_layer_low_intensity (std::string, optional): Output layer for points with \(\text{intensity} < \text{low\_threshold}\).

  • output_layer_high_intensity (std::string, optional): Output layer for points with \(\text{intensity} > \text{high\_threshold}\).

  • output_layer_mid_intensity (std::string, optional): Output layer for points with \(\text{intensity} \in [\text{low\_threshold}, \text{high\_threshold}]\).

  • low_threshold (float, default: 0.10): The minimum intensity value for the ‘mid’ range.

  • high_threshold (float, default: 0.90): The maximum intensity value for the ‘mid’ range.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterByIntensity
    params:
      input_pointcloud_layer: 'raw'
      output_layer_high_intensity: 'high_i'
      low_threshold: 0.1
      high_threshold: 0.9

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterByIntensity

Filter: FilterByRange

Description: Filters points based on their range (distance) from a specified center point (default is the origin \((0, 0, 0)\)).

Parameters:

  • input_pointcloud_layer (std::string, default: raw): The input point cloud layer name.

  • output_layer_between (std::string, optional): Output layer for points within the \([\text{range\_min}, \text{range\_max}]\) distance range.

  • output_layer_outside (std::string, optional): Output layer for points outside the \([\text{range\_min}, \text{range\_max}]\) distance range.

  • range_min (float, default: 3.0): The minimum distance threshold.

  • range_max (float, default: 90.0): The maximum distance threshold.

  • center (float[3], default: [0, 0, 0]): The center point from which ranges are measured. Can use robot pose variables (e.g., robot_x).

  • metric_l_infinity (bool, default: false): If true, the L-infinity norm (maximum component) is used for distance calculation, which is more efficient than the default L2 Euclidean norm.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterByRange
    params:
      input_pointcloud_layer: 'raw'
      output_layer_between: 'valid_range'
      range_min: 3.0
      range_max: 90.0

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterByRange

Filter: FilterByRing

Description: Keeps only a given subset of an input cloud based on the LiDAR “ring_id” (assuming the point cloud has ring data).

Parameters:

  • input_pointcloud_layer (std::string): The input point cloud layer name.

  • output_layer_selected (std::string, optional): Output layer for points whose ring ID is in selected_ring_ids.

  • output_layer_non_selected (std::string, optional): Output layer for points whose ring ID is NOT in selected_ring_ids.

  • selected_ring_ids (std::set): A list of ring IDs to keep/select (e.g., [0, 1, 5, 6]).

filters:
  #...
  - class_name: mp2p_icp_filters::FilterByRing
    params:
      input_pointcloud_layer: 'raw'
      output_layer_selected: 'ground_rings'
      selected_ring_ids: [ 0, 1, 15, 16 ]

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterByRing

Filter: FilterCurvature

Description: Classifies a sorted input point cloud (e.g., a single LiDAR scan line) by local curvature, estimated from the angle between a point and its immediate former and posterior neighbors. Useful for edge extraction (LOAM-style).

Parameters:

  • input_pointcloud_layer (std::string, default: raw): The input point cloud layer name. Must be sorted for meaningful results.

  • output_layer_larger_curvature (std::string, optional): Output layer for points with larger curvature (often “edges”).

  • output_layer_smaller_curvature (std::string, optional): Output layer for points with smaller curvature (often “flatter” surfaces).

  • output_layer_other (std::string, optional): Output layer for points that do not fall into the above two categories.

  • max_cosine (float, default: 0.5f): A threshold related to the angle of the local neighborhood for classifying high curvature.

  • min_clearance (float, default: 0.02f): The minimum distance a neighbor must be to be considered in the curvature calculation (m).

  • max_gap (float, default: 1.00f): The maximum gap distance between a point and its neighbor (m).

filters:
  #...
  - class_name: mp2p_icp_filters::FilterCurvature
    params:
      input_pointcloud_layer: 'raw_sorted'
      output_layer_larger_curvature: 'edges'
      output_layer_smaller_curvature: 'planes'

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterCurvature

Filter: FilterDecimateAdaptive

Description: Accepts an input point cloud, voxelizes it, and generates a new layer with an adaptive sampling to aim for a specific desired output point count.

Parameters:

  • input_pointcloud_layer (std::string, default: raw): The input point cloud layer name.

  • output_pointcloud_layer (std::string): The output layer name for the adaptively decimated cloud.

  • desired_output_point_count (unsigned int, default: 1000): The target number of points in the output cloud.

  • minimum_input_points_per_voxel (unsigned int, default: 1): Voxels with fewer points than this threshold will not generate any output point.

  • voxel_size (float, default: 0.10): The size of the voxel grid used for downsampling (m).

  • parallelization_grain_size (size_t, default: 16384): Grain size for parallel processing of input clouds (used when TBB is enabled).

filters:
  #...
  - class_name: mp2p_icp_filters::FilterDecimateAdaptive
    params:
      input_pointcloud_layer: 'raw'
      output_pointcloud_layer: 'adaptively_decimated'
      desired_output_point_count: 5000
      voxel_size: 0.2

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterDecimateAdaptive

Filter: FilterDecimateVoxels

Description: Builds a new layer with a decimated version of one or more input layers using a uniform voxel grid.

Parameters:

  • input_pointcloud_layer (std::vector, default: [raw]): One or more input layers to read and merge points from.

  • error_on_missing_input_layer (bool, default: true): If true, an exception is thrown if an input layer is missing. Otherwise, it’s silently ignored.

  • output_pointcloud_layer (std::string): The output point cloud layer name. New points are appended if the layer already exists.

  • voxel_filter_resolution (float, default: 1.0f): Size of each voxel edge (m).

  • use_tsl_robin_map (bool, default: true): Whether to use tsl::robin_map (faster for smaller clouds) or std::map (faster for large clouds) as the container implementation.

  • minimum_input_points_to_filter (uint32_t, default: 0): If the total number of input points is less than this, all points are passed through without decimation.

  • flatten_to (std::optional): If defined, the 3D points are “flattened” into a 2D planar cloud at a constant height \(z\). Additional point fields (ring, intensity, timestamp) are NOT copied in this mode.

  • decimate_method (DecimateMethod, default: FirstPoint): The method to pick the representative point for each voxel:
    • FirstPoint: Picks the first point inserted into the voxel (most efficient).

    • ClosestToAverage: Picks the point closest to the average position of all voxel points.

    • VoxelAverage: Calculates and uses the average position of all voxel points (a new point).

    • RandomPoint: Picks one of the voxel points at random.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterDecimateVoxels
    params:
      input_pointcloud_layer: [ 'raw', 'intensity_low' ]
      output_pointcloud_layer: 'decimated'
      voxel_filter_resolution: 0.1
      decimate_method: 'VoxelAverage'

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterDecimateVoxels

Filter: FilterDeleteLayer

Description: Completely removes one or more point layers from the metric map.

Parameters:

  • pointcloud_layer_to_remove (std::vector): One or more layers to remove.

  • error_on_missing_input_layer (bool, default: true): If true, an exception is thrown if a layer to be removed does not exist. Otherwise, it’s silently ignored.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterDeleteLayer
    params:
      pointcloud_layer_to_remove: [ 'raw', 'temp_layer' ]
      error_on_missing_input_layer: false

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterDeleteLayer

Filter: FilterDeskew

Description: Deskew (motion compensate) a point cloud from a moving LiDAR.

Parameters:

  • input_pointcloud_layer (std::string, default: raw): The input point cloud layer name.

  • output_pointcloud_layer (std::string, optional): The output layer name. Required unless in_place is true.

  • in_place (bool, default: false): If true, the deskewed points replace the input layer (most efficient).

  • output_layer_class (std::string, default: mrpt::maps::CPointsMapXYZI): The class name for the output layer if it needs to be created.

  • silently_ignore_no_timestamps (bool, default: false): If true, no exception is thrown if the input layer lacks timestamps.

  • method (MotionCompensationMethod, default: Linear): The motion compensation method:
    • `None`

    • `Linear`: Uses the constant twist field.

    • `IMU`: Retrieves the precise twist trajectory from the LocalVelocityBuffer.

  • twist (std::optional): The velocity (linear and angular) of the vehicle in the local vehicle frame. Only used for method=Linear.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterDeskew
    params:
      input_pointcloud_layer: 'raw'
      output_pointcloud_layer: 'deskewed'
      method: 'IMU'

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterDeskew

Filter: FilterEdgesPlanes

Description: Classifies point cloud voxels into planes and “edges” based on an eigenvalue analysis of local neighborhood covariance, inspired by the LOAM paper.

Parameters:

  • input_pointcloud_layer (std::string, default: raw): The input point cloud layer name.

  • output_layer_edges (std::string, default: edges): Output layer for edge points.

  • output_layer_planes (std::string, default: planes): Output layer for planar points.

  • voxel_filter_resolution (float, default: 0.5f): Size of each voxel edge (m).

  • full_pointcloud_decimation (unsigned int, default: 20): Decimation factor applied to the original input cloud before analysis.

  • voxel_filter_decimation (unsigned int, default: 1).

  • voxel_filter_max_e2_e0 (float, default: 30.f): Threshold parameter for edge classification (ratio of eigenvalues).

  • voxel_filter_max_e1_e0 (float, default: 30.f): Threshold parameter for planar classification (ratio of eigenvalues).

  • voxel_filter_min_npts (unsigned int, default: 5): Minimum number of points in a voxel to perform the classification.

  • use_tsl_robin_map (bool, default: true).

filters:
  #...
  - class_name: mp2p_icp_filters::FilterEdgesPlanes
    params:
      input_pointcloud_layer: 'raw_down'
      output_layer_edges: 'edges'
      output_layer_planes: 'planes'
      voxel_filter_resolution: 0.5

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterEdgesPlanes

Filter: FilterFartherPointSampling

Description: Subsamples a cloud using the Farther Point Sampling (FPS) algorithm, aiming for a desired number of output points.

Parameters:

  • input_pointcloud_layer (std::string, default: raw): The input point cloud layer name.

  • output_pointcloud_layer (std::string): The output layer name for the sampled cloud.

  • desired_output_point_count (unsigned int, default: 1000): The target number of points in the output cloud.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterFartherPointSampling
    params:
      input_pointcloud_layer: 'raw'
      output_pointcloud_layer: 'sampled'
      desired_output_point_count: 2000

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterFartherPointSampling

Filter: FilterMerge

Description: Takes a point cloud layer (or a mrpt::maps::CVoxelMap layer) and inserts it into another existing layer of arbitrary metric map type. This uses the target layer’s standard insertObservation() method.

Parameters:

  • input_pointcloud_layer (std::string): The point cloud or map layer to be inserted.

  • target_layer (std::string): The destination layer into which the points will be merged.

  • input_layer_in_local_coordinates (bool, default: false): If true, the input_pointcloud_layer is assumed to be in the vehicle frame and is transformed by robot_pose before insertion.

  • robot_pose (mrpt::math::TPose3D): The pose of the robot/vehicle. Required if input_layer_in_local_coordinates is true.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterMerge
    params:
      input_pointcloud_layer: 'local_scan'
      target_layer: 'global_map'
      input_layer_in_local_coordinates: true

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterMerge

Filter: FilterNormalizeIntensity

Description: Normalizes the intensity channel of a point cloud layer such that intensity values end up in the range \([0, 1]\). The data is updated in-place in the input/output layer.

Parameters:

  • pointcloud_layer (std::string): The point cloud layer to process.

  • remember_intensity_range (bool, default: false): If true, the filter keeps an internal record of the minimum and maximum intensities observed in past clouds to maintain a consistent normalization.

  • fixed_maximum_intensity (double, default: 0.0): If non-zero, this value is used as the fixed maximum intensity for normalization.

  • fixed_minimum_intensity (double, default: 0.0): If fixed_maximum_intensity is non-zero, this value is used as the fixed minimum intensity for normalization.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterNormalizeIntensity
    params:
      pointcloud_layer: 'raw'
      remember_intensity_range: true

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterNormalizeIntensity

Filter: FilterPoleDetector

Description: Identifies and separates points that appear to belong to a pole or vertical structure. This is done by analyzing the min/max Z-span in 2D grid cells.

Parameters:

  • input_pointcloud_layer (std::string, default: raw): The input point cloud layer name.

  • output_layer_poles (std::string, optional): Output layer name for points that are poles.

  • output_layer_no_poles (std::string, optional): Output layer name for points that are not poles.

  • grid_size (float, default: 2.0f): Size of the 2D grid cell used for analysis (m).

  • minimum_relative_height (float, default: 2.5f): Minimum required height span in a cell to be considered a pole candidate.

  • maximum_relative_height (float, default: 25.0f): Maximum allowed height span in a cell.

  • minimum_points_per_cell (uint32_t, default: 50): Minimum number of points required in a cell for analysis.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterPoleDetector
    params:
      input_pointcloud_layer: 'raw'
      output_layer_poles: 'poles'
      grid_size: 1.0
      minimum_relative_height: 3.0

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterPoleDetector

Filter: FilterRemoveByVoxelOccupancy

Description: Removes points from an input point cloud based on the occupancy status of the corresponding voxels in a separate mrpt::maps::CVoxelMap layer. This is typically used to separate static (high occupancy) and dynamic (low occupancy) objects.

Parameters:

  • input_pointcloud_layer (std::string): The input point cloud to be filtered.

  • input_voxel_layer (std::string): The layer containing the occupancy data (mrpt::maps::CVoxelMap).

  • output_layer_static_objects (std::string, optional): Output layer for points within high-occupancy voxels (“static objects”).

  • output_layer_dynamic_objects (std::string, optional): Output layer for points within low-occupancy voxels (“dynamic objects”).

  • occupancy_threshold (float, default: 0.6f): The occupancy probability threshold. Voxels above this are considered “static”.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterRemoveByVoxelOccupancy
    params:
      input_pointcloud_layer: 'raw'
      input_voxel_layer: 'voxel_map'
      output_layer_static_objects: 'static'
      occupancy_threshold: 0.7

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterRemoveByVoxelOccupancy

Filter: FilterVoxelSlice

Description: Takes an input layer of type mrpt::maps::CVoxelMap (e.g., Bonxai) and extracts a single 2D slice at a specified Z-range, collapsing the voxel column into an occupancy gridmap.

Parameters:

  • input_voxel_layer (std::string): The input voxel map layer (mrpt::maps::CVoxelMap).

  • output_gridmap_layer (std::string): The output 2D occupancy grid map layer.

  • z_min (double): The minimum Z-coordinate for the slice.

  • z_max (double): The maximum Z-coordinate for the slice.

filters:
  #...
  - class_name: mp2p_icp_filters::FilterVoxelSlice
    params:
      input_voxel_layer: 'voxel_map'
      output_gridmap_layer: '2d_slice'
      z_min: -0.5
      z_max: 0.5

Before → After Screenshot

Screenshot showing point cloud before and after applying FilterVoxelSlice