Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
icp.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <iostream>
4#include <pcl/io/pcd_io.h>
5#include <pcl/point_types.h>
6#include <pcl/registration/icp.h>
7
12class ICP{
13 private:
14 pcl::IterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI> _icp_;
16 public:
25 ICP(std::string target_file, double max_correspondence_distance, long max_iteration,
26 double transformation_epsilon, double euclidean_fitness_epsilon);
27
34 double executeICP(pcl::PointCloud<pcl::PointXYZI>::Ptr source,
35 pcl::PointCloud<pcl::PointXYZI>::Ptr final_cloud);
36};
Class for performing Iterative Closest Point (ICP) registration.
Definition icp.hpp:12
pcl::IterativeClosestPoint< pcl::PointXYZI, pcl::PointXYZI > _icp_
ICP object.
Definition icp.hpp:14
double executeICP(pcl::PointCloud< pcl::PointXYZI >::Ptr source, pcl::PointCloud< pcl::PointXYZI >::Ptr final_cloud)
Execute the ICP registration.
Definition icp.cpp:24