Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <pcl/PCLPointCloud2.h>
00040 #include <pcl/point_types.h>
00041 #include <pcl/common/distances.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/console/time.h>
00046 #include <pcl/kdtree/kdtree_flann.h>
00047
00048
00049 using namespace pcl;
00050 using namespace pcl::io;
00051 using namespace pcl::console;
00052
00053 std::string default_correspondence_type = "index";
00054
00055 void
00056 printHelp (int, char **argv)
00057 {
00058 print_error ("Syntax is: %s source.pcd target.pcd output_intensity.pcd <options>\n", argv[0]);
00059 print_info (" where options are:\n");
00060 print_info (" -correspondence X = the way of selecting the corresponding pair in the target cloud for the current point in the source cloud\n");
00061 print_info (" options are: index = points with identical indices are paired together. Note: both clouds need to have the same number of points\n");
00062 print_info (" nn = source point is paired with its nearest neighbor in the target cloud\n");
00063 print_info (" nnplane = source point is paired with its projection on the plane determined by the nearest neighbor in the target cloud. Note: target cloud needs to contain normals\n");
00064 print_info (" (default: ");
00065 print_value ("%s", default_correspondence_type.c_str ()); print_info (")\n");
00066 }
00067
00068 bool
00069 loadCloud (const std::string &filename, pcl::PCLPointCloud2 &cloud)
00070 {
00071 TicToc tt;
00072
00073
00074 tt.tic ();
00075 if (loadPCDFile (filename, cloud) < 0)
00076 return (false);
00077
00078
00079
00080 return (true);
00081 }
00082
00083 void
00084 compute (const pcl::PCLPointCloud2::ConstPtr &cloud_source, const pcl::PCLPointCloud2::ConstPtr &cloud_target,
00085 pcl::PCLPointCloud2 &output, std::string correspondence_type)
00086 {
00087
00088 TicToc tt;
00089 tt.tic ();
00090
00091 PointCloud<PointXYZ>::Ptr xyz_source (new PointCloud<PointXYZ> ());
00092 fromPCLPointCloud2 (*cloud_source, *xyz_source);
00093 PointCloud<PointXYZ>::Ptr xyz_target (new PointCloud<PointXYZ> ());
00094 fromPCLPointCloud2 (*cloud_target, *xyz_target);
00095
00096 PointCloud<PointXYZI>::Ptr output_xyzi (new PointCloud<PointXYZI> ());
00097 output_xyzi->points.resize (xyz_source->points.size ());
00098 output_xyzi->height = cloud_source->height;
00099 output_xyzi->width = cloud_source->width;
00100
00101 float rmse = 0.0f;
00102
00103 if (correspondence_type == "index")
00104 {
00105
00106
00107 if (xyz_source->points.size () != xyz_target->points.size ())
00108 {
00109 print_error ("Source and target clouds do not have the same number of points.\n");
00110 return;
00111 }
00112
00113 for (size_t point_i = 0; point_i < xyz_source->points.size (); ++point_i)
00114 {
00115 if (!pcl_isfinite (xyz_source->points[point_i].x) || !pcl_isfinite (xyz_source->points[point_i].y) || !pcl_isfinite (xyz_source->points[point_i].z))
00116 continue;
00117 if (!pcl_isfinite (xyz_target->points[point_i].x) || !pcl_isfinite (xyz_target->points[point_i].y) || !pcl_isfinite (xyz_target->points[point_i].z))
00118 continue;
00119
00120
00121 float dist = squaredEuclideanDistance (xyz_source->points[point_i], xyz_target->points[point_i]);
00122 rmse += dist;
00123
00124 output_xyzi->points[point_i].x = xyz_source->points[point_i].x;
00125 output_xyzi->points[point_i].y = xyz_source->points[point_i].y;
00126 output_xyzi->points[point_i].z = xyz_source->points[point_i].z;
00127 output_xyzi->points[point_i].intensity = dist;
00128 }
00129 rmse = sqrtf (rmse / static_cast<float> (xyz_source->points.size ()));
00130 }
00131 else if (correspondence_type == "nn")
00132 {
00133
00134
00135 KdTreeFLANN<PointXYZ>::Ptr tree (new KdTreeFLANN<PointXYZ> ());
00136 tree->setInputCloud (xyz_target);
00137
00138 for (size_t point_i = 0; point_i < xyz_source->points.size (); ++ point_i)
00139 {
00140 if (!pcl_isfinite (xyz_source->points[point_i].x) || !pcl_isfinite (xyz_source->points[point_i].y) || !pcl_isfinite (xyz_source->points[point_i].z))
00141 continue;
00142
00143 std::vector<int> nn_indices (1);
00144 std::vector<float> nn_distances (1);
00145 if (!tree->nearestKSearch (xyz_source->points[point_i], 1, nn_indices, nn_distances))
00146 continue;
00147 size_t point_nn_i = nn_indices.front();
00148
00149 float dist = squaredEuclideanDistance (xyz_source->points[point_i], xyz_target->points[point_nn_i]);
00150 rmse += dist;
00151
00152 output_xyzi->points[point_i].x = xyz_source->points[point_i].x;
00153 output_xyzi->points[point_i].y = xyz_source->points[point_i].y;
00154 output_xyzi->points[point_i].z = xyz_source->points[point_i].z;
00155 output_xyzi->points[point_i].intensity = dist;
00156 }
00157 rmse = sqrtf (rmse / static_cast<float> (xyz_source->points.size ()));
00158
00159 }
00160 else if (correspondence_type == "nnplane")
00161 {
00162
00163
00164 PointCloud<Normal>::Ptr normals_target (new PointCloud<Normal> ());
00165 fromPCLPointCloud2 (*cloud_target, *normals_target);
00166
00167 KdTreeFLANN<PointXYZ>::Ptr tree (new KdTreeFLANN<PointXYZ> ());
00168 tree->setInputCloud (xyz_target);
00169
00170 for (size_t point_i = 0; point_i < xyz_source->points.size (); ++ point_i)
00171 {
00172 if (!pcl_isfinite (xyz_source->points[point_i].x) || !pcl_isfinite (xyz_source->points[point_i].y) || !pcl_isfinite (xyz_source->points[point_i].z))
00173 continue;
00174
00175 std::vector<int> nn_indices (1);
00176 std::vector<float> nn_distances (1);
00177 if (!tree->nearestKSearch (xyz_source->points[point_i], 1, nn_indices, nn_distances))
00178 continue;
00179 size_t point_nn_i = nn_indices.front();
00180
00181 Eigen::Vector3f normal_target = normals_target->points[point_nn_i].getNormalVector3fMap (),
00182 point_source = xyz_source->points[point_i].getVector3fMap (),
00183 point_target = xyz_target->points[point_nn_i].getVector3fMap ();
00184
00185 float dist = normal_target.dot (point_source - point_target);
00186 rmse += dist * dist;
00187
00188 output_xyzi->points[point_i].x = xyz_source->points[point_i].x;
00189 output_xyzi->points[point_i].y = xyz_source->points[point_i].y;
00190 output_xyzi->points[point_i].z = xyz_source->points[point_i].z;
00191 output_xyzi->points[point_i].intensity = dist * dist;
00192 }
00193 rmse = sqrtf (rmse / static_cast<float> (xyz_source->points.size ()));
00194 }
00195 else
00196 {
00197
00198 return;
00199 }
00200
00201 toPCLPointCloud2 (*output_xyzi, output);
00202
00203
00204 print_highlight ("RMSE Error: %f\n", rmse);
00205 }
00206
00207 void
00208 saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)
00209 {
00210 TicToc tt;
00211 tt.tic ();
00212
00213
00214
00215 pcl::io::savePCDFile (filename, output);
00216
00217
00218 }
00219
00220
00221 int
00222 main (int argc, char** argv)
00223 {
00224
00225
00226 if (argc < 4)
00227 {
00228 printHelp (argc, argv);
00229 return (-1);
00230 }
00231
00232
00233 std::vector<int> p_file_indices;
00234 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00235 if (p_file_indices.size () != 3)
00236 {
00237 print_error ("Need two input PCD files and one output PCD file to continue.\n");
00238 return (-1);
00239 }
00240
00241
00242 std::string correspondence_type = default_correspondence_type;
00243 parse_argument (argc, argv, "-correspondence", correspondence_type);
00244
00245
00246 pcl::PCLPointCloud2::Ptr cloud_source (new pcl::PCLPointCloud2 ());
00247 if (!loadCloud (argv[p_file_indices[0]], *cloud_source))
00248 return (-1);
00249
00250 pcl::PCLPointCloud2::Ptr cloud_target (new pcl::PCLPointCloud2 ());
00251 if (!loadCloud (argv[p_file_indices[1]], *cloud_target))
00252 return (-1);
00253
00254 pcl::PCLPointCloud2 output;
00255
00256 compute (cloud_source, cloud_target, output, correspondence_type);
00257
00258
00259 saveCloud (argv[p_file_indices[2]], output);
00260 }