Struct LidarTargetDetectionParameters

Struct Documentation

struct LidarTargetDetectionParameters

Public Types

enum ENormalEstSearchMethod

Values:

enumerator RADIUS_SEARCH
enumerator NEAREST_NEIGHBOR_SEARCH
enum EIcpMethod

Values:

enumerator ICP
enumerator PlaneICP
enumerator GICP

Public Functions

inline void declareDynamic(rclcpp::Node *ipNode) const

Declare parameters as dynamic to be adjusted during runtime.

Parameters:

ipNode[in] Pointer to node for which the parameters are to be declared.

inline bool tryToSetParameter(const rclcpp::Parameter &iParameter)

Try to set available parameter from given rclcpp::Parameter.

This will try through all parameters in list and try to set value.

Returns:

True, if successful, i.e., if a parameter from the list has been updated. False otherwise.

Public Members

DynamicParameter<double> max_range = DynamicParameter<double>(6.0,"Maximum range at which to filter the incomming point cloud prior to any processing. ""Any point with a range (absolute distance from sensor) larger than max_range will be ""discarded. Turn to 0 to switch off.",0.0, 20.0)
DynamicParameter<int> normal_estimation_search_method = DynamicParameter<int>(1,"Select method to use for neighbor search.""\n\t0 = RADIUS_SEARCH,""\n\t1 = NEAREST_NEIGHBOR_SEARCH",0, 1, 1)
DynamicParameter<double> normal_estimation_search_radius = DynamicParameter<double>(100.0,"Radius in which to search for neighbors.\n""In case of 'RadiusSearch', this is a spatial extend.\n""In case of 'NearestNeighborSearch', this represents the number of nearest ""neighbors (truncated to int).",0.001, 500.0)
DynamicParameter<int> region_growing_cluster_size_min = DynamicParameter<int>(100,"Minimum number of points a cluster needs to contain in order to be considered as ""valid inside the region growing.",10, 999)
DynamicParameter<int> region_growing_cluster_size_max = DynamicParameter<int>(10000,"Maximum number of points a cluster needs to contain in order to be considered as ""valid inside the region growing.",1000, 999999)
DynamicParameter<int> region_growing_number_neighbors = DynamicParameter<int>(30, "Number of neighbor points to consider during region growing.", 1, 100)
DynamicParameter<double> region_growing_angle_thresh = DynamicParameter<double>(1.8,"Angle in degrees used as the allowable range for the normals deviation. ""If the deviation between points normals is less than the smoothness threshold ""then they are suggested to be in the same cluster.",0.1, 10.0)
DynamicParameter<double> region_growing_curvature_thresh = DynamicParameter<double>(0.8,"Second criteria for the region growing.  If two points have a small normals deviation ""then the disparity between their curvatures is tested.",0.1, 10.0)
DynamicParameter<double> size_filter_width_min_tolerance = DynamicParameter<double>(0.05,"Tolerance (in m) of the minimum board width when filtering the clusters based on ""their size.",0.01, 0.5)
DynamicParameter<double> size_filter_width_max_tolerance = DynamicParameter<double>(0.1,"Tolerance (in m) of the maximum board width when filtering the clusters based on ""their size.",0.01, 0.5)
DynamicParameter<double> size_filter_height_min_tolerance = DynamicParameter<double>(0.05,"Tolerance (in m) of the minimum board height when filtering the clusters based on ""their size.",0.01, 0.5)
DynamicParameter<double> size_filter_height_max_tolerance = DynamicParameter<double>(0.5,"Tolerance (in m) of the maximum board height when filtering the clusters based on ""their size.",0.01, 0.5)
DynamicParameter<double> ransac_distance_thresh = DynamicParameter<double>(0.05, "Distance threshold (in m) from model for points to count as inliers during RANSAC.", 0.01, 0.5)
DynamicParameter<double> ransac_rotation_variance = DynamicParameter<double>(1.0,"Maximum angle in rotation (in degrees) to be sampled when computing the new ""coefficients within RANSAC.",0.01, 180.0)
DynamicParameter<double> ransac_translation_variance = DynamicParameter<double>(0.08,"Maximum distance in translation (in m) to be sampled when computing the new ""coefficients within RANSAC.",0.01, 1.0)
DynamicParameter<bool> ransac_optimize_coefficients = DynamicParameter<bool>(true, "Option to activate the optimization of the coefficients by means of ICP.")
DynamicParameter<int> target_icp_variant = DynamicParameter<int>(2,"Select ICP variant to use to optimize coefficients.""\n\t0 = ICP,""\n\t1 = PlaneICP,""\n\t2 = GICP",0, 2, 1)
DynamicParameter<double> target_icp_max_correspondence_distance = DynamicParameter<double>(0.1,"Maximum distance for ICP to search for point correspondences. ""Given as ratio with respect to shorter side of calibration target.",0.001, 1.0)
DynamicParameter<double> target_icp_rotation_tolerance = DynamicParameter<double>(0.5, "Rotation tolerance for convergence check. Given in degrees.", 0.001, 10.0)
DynamicParameter<double> target_icp_translation_tolerance = DynamicParameter<double>(0.001,"Translation tolerance for convergence check. Given in unit of the""LiDAR point cloud, typically meters.",0.000001, 1.0)