00001
00002 #include <iostream>
00003 #include <boost/thread/thread.hpp>
00004 #include <boost/program_options.hpp>
00005
00006 #include <ndt_feature_reg/ndt_frame.h>
00007 #include <ndt_feature_reg/ndt_frame_proc.h>
00008 #include <ndt_feature_reg/ndt_frame_viewer.h>
00009
00010 #include <ndt_registration/ndt_matcher_d2d_feature.h>
00011
00012 #include <ndt_map/pointcloud_utils.h>
00013
00014 #include <cv.h>
00015 #include <highgui.h>
00016
00017 #include <pcl/visualization/pcl_visualizer.h>
00018 #include <pcl/io/io.h>
00019 #include <pcl/io/pcd_io.h>
00020 #include <pcl/common/transforms.h>
00021
00022 using namespace ndt_feature_reg;
00023 using namespace pcl;
00024 using namespace cv;
00025 using namespace std;
00026 using namespace lslgeneric;
00027
00028 namespace po = boost::program_options;
00029
00030 inline
00031 std::vector<std::string> split_string(const std::string &str, const std::string &separator)
00032 {
00033 std::string::size_type it = 0;
00034 std::vector<std::string> values;
00035 bool stop = false;
00036 while (!stop)
00037 {
00038 std::string::size_type start = it;
00039 it = str.find(separator, it+1);
00040 if (it == std::string::npos)
00041 {
00042 values.push_back(str.substr(start, std::string::npos));
00043 stop = true;
00044 }
00045 else
00046 {
00047 it++;
00048 values.push_back(str.substr(start, it-start-1));
00049 }
00050 }
00051 return values;
00052 }
00053
00054
00055 vector<pair<string,string> > load_associations(const string &association_file, vector<string> ×tamps, int skip_nb)
00056 {
00057
00058 vector<pair<string, string> > ret;
00059 std::ifstream file(association_file.c_str());
00060 std::string line;
00061 bool skip = false;
00062 int skip_counter = 0;
00063 while(std::getline (file,line))
00064 {
00065 vector<string> splits = split_string(line, std::string(" "));
00066 if (splits.size() < 4)
00067 {
00068 cerr << "couldn't parse : " << line << endl;
00069 continue;
00070 }
00071 if (!skip)
00072 {
00073 ret.push_back(pair<string,string>(splits[1], splits[3]));
00074 timestamps.push_back(splits[0]);
00075 }
00076
00077 if (skip_counter > skip_nb)
00078 {
00079 skip = false;
00080 skip_counter = 0;
00081 }
00082 else
00083 {
00084 skip = true;
00085 skip_counter++;
00086 }
00087 }
00088 return ret;
00089 }
00090
00091
00092
00093
00094 int main(int argc, char** argv)
00095 {
00096 cout << "--------------------------------------------------" << endl;
00097 cout << "Evaluations of f2f registration" << endl;
00098 cout << "--------------------------------------------------" << endl;
00099
00100 string association_name;
00101 string output_name;
00102 string times_name;
00103 double scale, max_inldist_xy, max_inldist_z;
00104 Eigen::Matrix<double,6,1> pose_increment_v;
00105 int nb_ransac;
00106 int nb_points;
00107 size_t support_size;
00108 size_t max_nb_frames;
00109 double max_var;
00110 double current_res;
00111 int delay_vis;
00112 double img_scale;
00113 double detector_thresh;
00114 int skip_nb;
00115 int freiburg_camera_nb;
00116 double max_kp_dist, min_kp_dist;
00117 double trim_factor;
00118 po::options_description desc("Allowed options");
00119 desc.add_options()
00120 ("help", "produce help message")
00121 ("debug", "print debug output")
00122 ("visualize", "visualize the output")
00123 ("association", po::value<string>(&association_name), "association file name (generated by association.py script)")
00124 ("output", po::value<string>(&output_name), "file name of the estimation output (to be used with the evaluation python script)")
00125 ("time_output", po::value<string>(×_name), "file name for saving the per-frame processing time (to be used with the evaluation python script)")
00126 ("scale", po::value<double>(&scale)->default_value(0.0002), "depth scale (depth = scale * pixel value)")
00127 ("max_inldist_xy", po::value<double>(&max_inldist_xy)->default_value(0.02), "max inlier distance in xy related to the camera plane (in meters)")
00128 ("max_inldist_z", po::value<double>(&max_inldist_z)->default_value(0.05), "max inlier distance in z - depth (in meters)")
00129 ("nb_ransac", po::value<int>(&nb_ransac)->default_value(1000), "max number of RANSAC iterations")
00130 ("nb_points", po::value<int>(&nb_points)->default_value(21), "number of surrounding points")
00131 ("support_size", po::value<size_t>(&support_size)->default_value(10), "width of patch around each feature in pixels")
00132 ("max_var", po::value<double>(&max_var)->default_value(0.3), "max variance of ndt cells")
00133 ("current_res", po::value<double>(¤t_res)->default_value(0.2), "resolution of ndt cells if doing full matching")
00134 ("skip_matching", "skip the ndt matching step")
00135 ("match_full", "skip the visual features step and perform only ndt matching")
00136 ("match_no_association", "skip the feature association step and match directly")
00137 ("estimate_di", "don't compute the ndt explicitly but estimate from neighbourhood depth")
00138 ("max_nb_frames", po::value<size_t>(&max_nb_frames)->default_value(10), "max number of frames to be keept in the processing step")
00139 ("delay_vis", po::value<int>(&delay_vis)->default_value(10), "param to opencv function waitKey (if visualize is used)")
00140 ("img_scale", po::value<double>(&img_scale)->default_value(1.), "if the rgb image should be scaled when feature are detected and extracted - mainly to boost the speed")
00141 ("detector_thresh", po::value<double>(&detector_thresh)->default_value(400.), "playaround parameter, used to test different detectorvalues")
00142 ("skip_nb", po::value<int>(&skip_nb)->default_value(0), "how many intermediate frames should be skipped between the registration is runned")
00143 ("old_reg_code", "use the old registration code - for debugging only")
00144 ("freiburg_camera_nb", po::value<int>(&freiburg_camera_nb)->default_value(1), "the camera used for the evaluation 1-> freiburg camera #1, 2-> freiburg camera #2")
00145 ("max_kp_dist", po::value<double>(&max_kp_dist)->default_value(10.), "max distance of keypoints used")
00146 ("min_kp_dist", po::value<double>(&min_kp_dist)->default_value(0.), "min distance of keypoints used")
00147 ("windowed_matching", "limit the search of the keypoint matches to a local region (will not work that good if the skip_nb is large)")
00148 ("trim_factor", po::value<double>(&trim_factor)->default_value(1.), "only utilize the trimfactor number of keypoints with the closest NDT distance - similar idea as in trimmed ICP")
00149 ("non_mean", "if the mean used in NDT matching (including the RANSAC step) are computed direclty from the closest depth image pixel")
00150 ;
00151
00152
00153 po::variables_map vm;
00154 po::store(po::parse_command_line(argc, argv, desc), vm);
00155 po::notify(vm);
00156
00157 if (!vm.count("output") || !vm.count("association"))
00158 {
00159 cout << "Missing association / output file names.\n";
00160 cout << desc << "\n";
00161 return 1;
00162 }
00163 if (vm.count("help"))
00164 {
00165 cout << desc << "\n";
00166 return 1;
00167 }
00168 bool debug = vm.count("debug");
00169 bool visualize = vm.count("visualize");
00170 bool skip_matching = vm.count("skip_matching");
00171 bool match_full = vm.count("match_full");
00172 bool match_no_association = vm.count("match_no_association");
00173 bool estimate_di = vm.count("estimate_di");
00174 bool old_reg_code = vm.count("old_reg_code");
00175 bool windowed_matching = vm.count("windowed_matching");
00176 bool non_mean = vm.count("non_mean");
00177
00178 if (times_name == "")
00179 {
00180 times_name = output_name + ".times";
00181 }
00182
00183 vector<string> timestamps;
00184 vector<pair<string,string> > associations = load_associations(association_name, timestamps, skip_nb);
00185 if (debug)
00186 {
00187 for (size_t i = 0; i < associations.size(); i++)
00188 {
00189 cout << "associations : " << associations[i].first << " <-> " << associations[i].second << endl;
00190 }
00191 cout << "loaded : " << associations.size() << " associations" << endl;
00192 }
00193
00194 double fx, fy, cx, cy, ds;
00195 std::vector<double> dist(5);
00196 switch (freiburg_camera_nb)
00197 {
00198 case 1:
00199 fx = 517.3;
00200 fy = 516.5;
00201 cx = 318.6;
00202 cy = 255.3;
00203 dist[0] = 0.2624;
00204 dist[1] = -0.9531;
00205 dist[2] = -0.0054;
00206 dist[3] = 0.0026;
00207 dist[4] = 1.1633;
00208 ds = 1.035;
00209 break;
00210 case 2:
00211 fx = 520.9;
00212 fy = 521.0;
00213 cx = 325.1;
00214 cy = 249.7;
00215 dist[0] = 0.2312;
00216 dist[1] = -0.7849;
00217 dist[2] = -0.0033;
00218 dist[3] = -0.0001;
00219 dist[4] = 0.9172;
00220 ds = 1.031;
00221 break;
00222 default:
00223 cerr << "unknown camera number : " << freiburg_camera_nb << endl;
00224 return 1;
00225 }
00226
00227
00228 double t1, t2;
00229
00230 lslgeneric::DepthCamera<pcl::PointXYZ> cameraparams(fx,fy,cx,cy,dist,ds*scale,false);
00231
00232 typedef Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> EigenTransform;
00233 std::vector<EigenTransform, Eigen::aligned_allocator<EigenTransform> > transformVector;
00234
00235 std::ofstream file_times(times_name.c_str(), ios::out);
00236 if (!file_times)
00237 {
00238 cerr << "Failed to open times file : " << times_name << endl;
00239 return -1;
00240 }
00241
00242 file_times<<"times = [";
00243
00244
00245 if (old_reg_code)
00246 {
00247 for (size_t i = 1; i < associations.size(); i++)
00248 {
00249 std::cout << "iter " << i << "(" << associations.size() << ")" << std::endl;
00250
00251 NDTFrame *frame1 = new NDTFrame();
00252 frame1->img = cv::imread(associations[i-1].first, 0);
00253 frame1->depth_img = cv::imread(associations[i-1].second, CV_LOAD_IMAGE_ANYDEPTH);
00254 if (i == 1)
00255 cameraparams.setupDepthPointCloudLookUpTable(frame1->depth_img.size());
00256 frame1->cameraParams = cameraparams;
00257 frame1->supportSize = support_size;
00258
00259 NDTFrame *frame2 = new NDTFrame();
00260 frame2->img = cv::imread(associations[i].first, 0);
00261 frame2->depth_img = cv::imread(associations[i].second, CV_LOAD_IMAGE_ANYDEPTH);
00262 frame2->cameraParams = cameraparams;
00263 frame2->supportSize = support_size;
00264
00265 frame1->current_res = current_res;
00266 frame2->current_res = current_res;
00267 NDTFrameProc proc(nb_ransac, max_inldist_xy, max_inldist_z);
00268 proc.detector = cv::FeatureDetector::create("SURF");
00269
00270 proc.img_scale = img_scale;
00271
00272 double t1 = getDoubleTime();
00273 proc.addFrame(frame1);
00274 proc.addFrame(frame2);
00275 proc.processFrames(skip_matching,estimate_di,match_full,match_no_association);
00276 double t2 = getDoubleTime();
00277
00278 if (visualize)
00279 viewKeypointMatches(&proc, delay_vis);
00280
00281 if (i == 1)
00282 transformVector.push_back(proc.transformVector[0]);
00283 transformVector.push_back(proc.transformVector[1]);
00284
00285 file_times << t2-t1 <<", ";
00286
00287
00288
00289 }
00290 }
00291 else
00292 {
00293
00294
00295 NDTFrameProc proc(nb_ransac, max_inldist_xy, max_inldist_z);
00296 proc.detector = cv::FeatureDetector::create("SURF");
00297
00298 proc.img_scale = img_scale;
00299 proc.trim_factor = trim_factor;
00300 proc.non_mean = non_mean;
00301 proc.pe.windowed = windowed_matching;
00302 proc.pe.maxDist = max_kp_dist;
00303 proc.pe.minDist = min_kp_dist;
00304
00305 for (size_t i = 0; i < associations.size(); i++)
00306 {
00307 std::cout << "iter " << i << "(" << associations.size() << ")" << std::endl;
00308 NDTFrame *frame = new NDTFrame();
00309 frame->img = cv::imread(associations[i].first, 0);
00310 frame->depth_img = cv::imread(associations[i].second, CV_LOAD_IMAGE_ANYDEPTH);
00311 frame->supportSize = support_size;
00312 frame->maxVar = max_var;
00313 frame->current_res = current_res;
00314 if (i == 0)
00315 cameraparams.setupDepthPointCloudLookUpTable(frame->depth_img.size());
00316 frame->cameraParams = cameraparams;
00317
00318
00319 double t1 = getDoubleTime();
00320 proc.addFrameIncremental(frame, skip_matching, estimate_di,match_full,match_no_association);
00321 double t2 = getDoubleTime();
00322
00323 if (visualize)
00324 viewKeypointMatches(&proc, delay_vis);
00325
00326
00327 file_times << t2-t1 <<", ";
00328 }
00329 transformVector = proc.transformVector;
00330 }
00331 file_times<<"];\n";
00332
00333
00334 cerr<<"sizes: "<<associations.size()<<" "<<transformVector.size()<<std::endl;
00335 assert(associations.size() == transformVector.size());
00336 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> global_transform;
00337 global_transform.setIdentity();
00338
00339
00340 std::ofstream file(output_name.c_str(), ios::out);
00341 if (!file)
00342 {
00343 cerr << "Failed to create file : " << output_name << endl;
00344 return -1;
00345 }
00346
00347 for (size_t i = 0; i < transformVector.size(); i++)
00348 {
00349 global_transform = global_transform * transformVector[i];
00350 Eigen::Quaternion<double> tmp(global_transform.rotation());
00351 cout << timestamps[i] << " " << global_transform.translation().transpose() << " " << tmp.x() << " " << tmp.y() << " " << tmp.z() << " " << tmp.w() << endl;
00352 file << timestamps[i] << " " << global_transform.translation().transpose() << " " << tmp.x() << " " << tmp.y() << " " << tmp.z() << " " << tmp.w() << endl;
00353 }
00354 file.close();
00355
00356 return 0;
00357 }