31 void PointCloudUtility::fusePointclouds(std::string file1, std::string file2, std::string out)
33 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pc1 = loadPointCloud(file1);
34 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pc2 = loadPointCloud(file2);
35 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pc1Aligned = pcl::PointCloud<pcl::PointXYZRGBA>::Ptr(
new pcl::PointCloud<pcl::PointXYZRGBA>);
36 pcl::ApproximateVoxelGrid<pcl::PointXYZRGBA> filter;
38 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr temp1 = pcl::PointCloud<pcl::PointXYZRGBA>::Ptr(
new pcl::PointCloud<pcl::PointXYZRGBA>);
39 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr temp2 = pcl::PointCloud<pcl::PointXYZRGBA>::Ptr(
new pcl::PointCloud<pcl::PointXYZRGBA>);
49 pcl::IterativeClosestPoint<pcl::PointXYZRGBA, pcl::PointXYZRGBA> aligner;
50 aligner.setEuclideanFitnessEpsilon(1e-20);
51 aligner.setTransformationEpsilon(1e-20);
52 aligner.setMaximumIterations(10000000);
53 aligner.setUseReciprocalCorrespondences(
true);
54 aligner.setInputSource(pc1);
55 aligner.setInputTarget(pc2);
56 aligner.align(*pc1Aligned);
57 pcl::PointCloud<pcl::PointXYZRGBA> pcout = *pc2 + *pc1Aligned;
59 pcl::io::savePCDFileASCII(out, pcout);
62 void PointCloudUtility::moveOrigin(std::string file, std::string out, Eigen::Vector3f translation)
65 transform.block<3, 1>(0, 3) = translation;
66 this->transformPointcloud(file, out,
transform);
69 void PointCloudUtility::rotatePointCloud(std::string file, std::string out,
Eigen::Matrix3f rotation)
73 this->transformPointcloud(file, out,
transform);
76 void PointCloudUtility::transformPointcloud(std::string file, std::string out,
Eigen::Matrix4f pose)
78 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
pc = loadPointCloud(file);
79 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr transformed_cloud(
new pcl::PointCloud<pcl::PointXYZRGBA>());
80 pcl::transformPointCloud<pcl::PointXYZRGBA>(*
pc, *transformed_cloud, pose);
82 pcl::io::savePCDFileASCII(out, *transformed_cloud);
84 void PointCloudUtility::showResult(std::string file)
86 pcl::visualization::PCLVisualizer viewer;
87 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
pc = loadPointCloud(file);
88 viewer.addPointCloud(
pc);
89 viewer.addCoordinateSystem(1.0);
91 while (!viewer.wasStopped())
97 void PointCloudUtility::process()
99 std::string file1 = getProperty<std::string>(
"PointCloud1").getValue();
100 std::string file2 = getProperty<std::string>(
"PointCloud2").getValue();
101 std::string out = getProperty<std::string>(
"ResultFileName").getValue();
102 bool merge = getProperty<bool>(
"Merge").getValue();
103 bool transform = getProperty<bool>(
"Transform").getValue();
104 bool view = getProperty<bool>(
"Show").getValue();
105 std::string temp =
"temp.pcd";
110 fusePointclouds(file1, file2, temp);
115 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
pc = loadPointCloud(file1);
116 pcl::io::savePCDFileASCII(temp, *
pc);
120 Eigen::Vector3f tVector;
121 tVector << getProperty<float>(
"X").getValue(),
122 getProperty<float>(
"Y").getValue(),
123 getProperty<float>(
"Z").getValue();
125 rot << getProperty<float>(
"Roll").getValue(),
126 getProperty<float>(
"Pitch").getValue(),
127 getProperty<float>(
"Yaw").getValue();
129 VirtualRobot::MathTools::posrpy2eigen4f(tVector, rot,
transpose);
130 transformPointcloud(temp, out,
transpose);
135 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
pc = loadPointCloud(temp);
136 pcl::io::savePCDFileASCII(out, *
pc);
158 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr PointCloudUtility::loadPointCloud(std::string
filename)
161 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr model(
new pcl::PointCloud<pcl::PointXYZRGBA>());
167 else if (pcl::io::loadPCDFile<pcl::PointXYZRGBA>(
filename.c_str(), *model) == -1)