Struct LidarVehicleRegistrationParameters

Struct Documentation

struct LidarVehicleRegistrationParameters

Public Types

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<int> region_num_neighbors = DynamicParameter<int>(50, "Number of neighbors to select around seed point for estimating plane parameters.", 10, 100)
DynamicParameter<bool> region_use_local_plane = DynamicParameter<bool>(true,"Flag whether to estimate a local plane with a center point and a radius. Uncheck ""to estimate an infinate plane.")
DynamicParameter<double> local_plane_radius = DynamicParameter<double>(1.5, "Radius (in m) of local plane, if it is to be estimated.", 0.5, 5.0)
DynamicParameter<double> local_plane_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<int> registration_icp_variant = DynamicParameter<int>(2,"Select ICP variant to use for registration.""\n\t0 = ICP,""\n\t1 = PlaneICP,""\n\t2 = GICP",0, 2, 1)
DynamicParameter<double> registration_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, 10.0)
DynamicParameter<double> registration_icp_rotation_tolerance = DynamicParameter<double>(0.5, "Rotation tolerance for convergence check. Given in degrees.", 0.001, 10.0)
DynamicParameter<double> registration_icp_translation_tolerance = DynamicParameter<double>(0.001,"Translation tolerance for convergence check. Given in unit of the""LiDAR point cloud, typically meters.",0.00001, 0.1)