Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
ICP Class Reference

Class for performing Iterative Closest Point (ICP) registration. More...

#include <icp.hpp>

Collaboration diagram for ICP:
Collaboration graph

Public Member Functions

 ICP (std::string target_file, double max_correspondence_distance, long max_iteration, double transformation_epsilon, double euclidean_fitness_epsilon)
 Constructor for the ICP class.
 
double executeICP (pcl::PointCloud< pcl::PointXYZI >::Ptr source, pcl::PointCloud< pcl::PointXYZI >::Ptr final_cloud)
 Execute the ICP registration.
 

Private Attributes

pcl::IterativeClosestPoint< pcl::PointXYZI, pcl::PointXYZI > _icp_
 ICP object.
 

Detailed Description

Class for performing Iterative Closest Point (ICP) registration.

Definition at line 12 of file icp.hpp.

Constructor & Destructor Documentation

◆ ICP()

ICP::ICP ( std::string  target_file,
double  max_correspondence_distance,
long  max_iteration,
double  transformation_epsilon,
double  euclidean_fitness_epsilon 
)

Constructor for the ICP class.

Parameters
target_filePath to the target point cloud file.
max_correspondence_distanceMaximum correspondence distance for ICP.
max_iterationMaximum number of iterations for ICP.
transformation_epsilonTransformation epsilon for convergence criteria.
euclidean_fitness_epsilonEuclidean fitness epsilon for convergence criteria.

Definition at line 4 of file icp.cpp.

Member Function Documentation

◆ executeICP()

double ICP::executeICP ( pcl::PointCloud< pcl::PointXYZI >::Ptr  source,
pcl::PointCloud< pcl::PointXYZI >::Ptr  final_cloud 
)

Execute the ICP registration.

Parameters
sourceSource point cloud for registration.
final_cloudFinal registered point cloud.
Returns
Fitness score after registration.

Definition at line 24 of file icp.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ _icp_

pcl::IterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI> ICP::_icp_
private

ICP object.

Definition at line 14 of file icp.hpp.


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