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 #include <pcl/console/parse.h>
00037 #include <pcl/console/print.h>
00038 #include <pcl/io/pcd_io.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/registration/ndt_2d.h>
00041 #include <pcl/registration/transformation_estimation_lm.h>
00042 #include <pcl/registration/warp_point_rigid_3d.h>
00043
00044 #include <string>
00045 #include <iostream>
00046 #include <fstream>
00047 #include <vector>
00048
00049 typedef pcl::PointXYZ PointType;
00050 typedef pcl::PointCloud<PointType> Cloud;
00051 typedef Cloud::ConstPtr CloudConstPtr;
00052 typedef Cloud::Ptr CloudPtr;
00053
00054
00055 void
00056 selfTest ()
00057 {
00058 CloudPtr model (new Cloud);
00059 model->points.push_back (PointType (1,1,0));
00060 model->points.push_back (PointType (4,4,0));
00061 model->points.push_back (PointType (5,6,0));
00062 model->points.push_back (PointType (3,3,0));
00063 model->points.push_back (PointType (6,7,0));
00064 model->points.push_back (PointType (7,11,0));
00065 model->points.push_back (PointType (12,15,0));
00066 model->points.push_back (PointType (7,12,0));
00067
00068 CloudPtr data (new Cloud);
00069 data->points.push_back (PointType (3,1,0));
00070 data->points.push_back (PointType (7,4,0));
00071 data->points.push_back (PointType (9,6,0));
00072
00073 pcl::console::setVerbosityLevel (pcl::console::L_DEBUG);
00074
00075 pcl::NormalDistributionsTransform2D<PointType, PointType> ndt;
00076
00077 ndt.setMaximumIterations (40);
00078 ndt.setGridCentre (Eigen::Vector2f (0,0));
00079 ndt.setGridExtent (Eigen::Vector2f (20,20));
00080 ndt.setGridStep (Eigen::Vector2f (20,20));
00081 ndt.setOptimizationStepSize (Eigen::Vector3d (0.4,0.4,0.1));
00082 ndt.setTransformationEpsilon (1e-9);
00083
00084 ndt.setInputTarget (model);
00085 ndt.setInputSource (data);
00086
00087 CloudPtr tmp (new Cloud);
00088 ndt.align (*tmp);
00089 std::cout << ndt.getFinalTransformation () << std::endl;
00090 }
00091
00092
00093 int
00094 main (int argc, char **argv)
00095 {
00096 int iter = 10;
00097 double grid_step = 3.0;
00098 double grid_extent = 25.0;
00099 double optim_step = 1.0;
00100
00101 pcl::console::parse_argument (argc, argv, "-i", iter);
00102 pcl::console::parse_argument (argc, argv, "-g", grid_step);
00103 pcl::console::parse_argument (argc, argv, "-e", grid_extent);
00104 pcl::console::parse_argument (argc, argv, "-s", optim_step);
00105
00106 std::vector<int> pcd_indices;
00107 pcd_indices = pcl::console::parse_file_extension_argument (argc, argv, ".pcd");
00108
00109 CloudPtr model (new Cloud);
00110 if (pcl::io::loadPCDFile (argv[pcd_indices[0]], *model) == -1)
00111 {
00112 std::cout << "Could not read file" << std::endl;
00113 return -1;
00114 }
00115 std::cout << argv[pcd_indices[0]] << " width: " << model->width << " height: " << model->height << std::endl;
00116
00117 std::string result_filename (argv[pcd_indices[0]]);
00118 result_filename = result_filename.substr (result_filename.rfind ("/") + 1);
00119 try
00120 {
00121 pcl::io::savePCDFile (result_filename.c_str (), *model);
00122 std::cout << "saving first model to " << result_filename << std::endl;
00123 }
00124 catch(pcl::IOException& e)
00125 {
00126 std::cerr << e.what() << std::endl;
00127 }
00128
00129 Eigen::Matrix4f t (Eigen::Matrix4f::Identity ());
00130
00131 for (size_t i = 1; i < pcd_indices.size (); i++)
00132 {
00133 CloudPtr data (new Cloud);
00134 if (pcl::io::loadPCDFile (argv[pcd_indices[i]], *data) == -1)
00135 {
00136 std::cout << "Could not read file" << std::endl;
00137 return -1;
00138 }
00139 std::cout << argv[pcd_indices[i]] << " width: " << data->width << " height: " << data->height << std::endl;
00140
00141
00142
00143 pcl::NormalDistributionsTransform2D<PointType, PointType> ndt;
00144
00145 ndt.setMaximumIterations (iter);
00146 ndt.setGridCentre (Eigen::Vector2f (15,0));
00147 ndt.setGridExtent (Eigen::Vector2f (grid_extent,grid_extent));
00148 ndt.setGridStep (Eigen::Vector2f (grid_step,grid_step));
00149 ndt.setOptimizationStepSize (optim_step);
00150 ndt.setTransformationEpsilon (1e-5);
00151
00152 ndt.setInputTarget (model);
00153 ndt.setInputSource (data);
00154
00155 CloudPtr tmp (new Cloud);
00156 ndt.align (*tmp);
00157
00158 t = t* ndt.getFinalTransformation ();
00159
00160 pcl::transformPointCloud (*data, *tmp, t);
00161
00162 std::cout << ndt.getFinalTransformation () << std::endl;
00163
00164 *model = *data;
00165
00166 try
00167 {
00168 std::string result_filename (argv[pcd_indices[i]]);
00169 result_filename = result_filename.substr (result_filename.rfind ("/") + 1);
00170 pcl::io::savePCDFileBinary (result_filename.c_str (), *tmp);
00171 std::cout << "saving result to " << result_filename << std::endl;
00172 }
00173 catch(pcl::IOException& e)
00174 {
00175 std::cerr << e.what() << std::endl;
00176 }
00177 }
00178
00179 return 0;
00180 }