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
00040
00041 #include <ros/ros.h>
00042 #include <visualization_msgs/Marker.h>
00043 #include <visualization_msgs/MarkerArray.h>
00044 #include <geometry_msgs/Point.h>
00045
00046 #include <vslam_system/vslam.h>
00047 #include <posest/pe3d.h>
00048 #include <sba/sba.h>
00049 #include <sba/sba_file_io.h>
00050 #include <frame_common/frame.h>
00051 #include <boost/shared_ptr.hpp>
00052 #include <cstdio>
00053 #include <fstream>
00054 #include <dirent.h>
00055 #include <fnmatch.h>
00056
00057 #include <opencv/highgui.h>
00058
00059 using namespace std;
00060 using namespace sba;
00061 using namespace frame_common;
00062 using namespace Eigen;
00063 using namespace vslam;
00064 using namespace pcl;
00065
00066
00067 #define VISMATCH
00068
00069
00070 #include <sys/time.h>
00071 static double mstime()
00072 {
00073 timeval tv;
00074 gettimeofday(&tv,NULL);
00075 long long ts = tv.tv_sec;
00076 ts *= 1000000;
00077 ts += tv.tv_usec;
00078 return (double)ts*.001;
00079 }
00080
00081
00082 char *lreg, *rreg, *dreg;
00083
00084
00085 int getleft(struct dirent const *entry)
00086 {
00087 if (!fnmatch(lreg,entry->d_name,0))
00088 return 1;
00089 return 0;
00090 }
00091
00092 int getright(struct dirent const *entry)
00093 {
00094 if (!fnmatch(rreg,entry->d_name,0))
00095 return 1;
00096 return 0;
00097 }
00098
00099
00100 int getidir(struct dirent const *entry)
00101 {
00102 if (!fnmatch(dreg,entry->d_name,0))
00103 return 1;
00104 return 0;
00105 }
00106
00107
00108
00109 void publishRegisteredPointclouds(sba::SysSBA& sba,
00110 std::vector<frame_common::Frame, Eigen::aligned_allocator<frame_common::Frame> >& frames,
00111 ros::Publisher& pub)
00112 {
00113 pcl::PointCloud<pcl::PointXYZRGB> cloud;
00114 pcl::PointCloud<pcl::PointXYZRGB> registered_cloud;
00115
00116 for(size_t i=0; i < frames.size(); i++)
00117 {
00118
00119 if (sba.nodes.size() < i)
00120 break;
00121 if (frames[i].dense_pointcloud.points.size() <= 0)
00122 continue;
00123 Eigen::Quaterniond rot = sba.nodes[i].qrot;
00124 Eigen::Vector3d trans = sba.nodes[i].trans.head<3>();
00125
00126 transformPointCloud<PointXYZRGB>(frames[i].dense_pointcloud, cloud, Vector3f(0,0,0), rot.cast<float>());
00127 transformPointCloud<PointXYZRGB>(cloud, cloud, trans.cast<float>(), Quaternionf(1, 0, 0, 0));
00128
00129 Quaternionf qr = Quaternionf(.5, 0, 0, .5).normalized()*Quaternionf(.5, -.5, .5, -0.5).normalized();
00130 transformPointCloud<PointXYZRGB>(cloud, cloud, Vector3f(0,0,0), qr);
00131
00132 registered_cloud.header = frames[i].dense_pointcloud.header;
00133 registered_cloud += cloud;
00134 }
00135
00136 sensor_msgs::PointCloud2 cloud_out;
00137 pcl::toROSMsg (registered_cloud, cloud_out);
00138 cloud_out.header.frame_id = "/pgraph";
00139 pub.publish (cloud_out);
00140 }
00141
00142
00143
00144
00145 void
00146 drawgraph(const SysSBA &sba, const ros::Publisher &cam_pub, const ros::Publisher &pt_pub,
00147 int dec)
00148 {
00149 visualization_msgs::Marker cammark, ptmark, cstmark;
00150 cammark.header.frame_id = "/pgraph";
00151 cammark.header.stamp = ros::Time();
00152 cammark.ns = "pgraph";
00153 cammark.id = 0;
00154 cammark.action = visualization_msgs::Marker::ADD;
00155 cammark.pose.position.x = 0;
00156 cammark.pose.position.y = 0;
00157 cammark.pose.position.z = 0;
00158 cammark.pose.orientation.x = 0.0;
00159 cammark.pose.orientation.y = 0.0;
00160 cammark.pose.orientation.z = 0.0;
00161 cammark.pose.orientation.w = 1.0;
00162 cammark.scale.x = 0.02;
00163 cammark.scale.y = 0.02;
00164 cammark.scale.z = 0.02;
00165 cammark.color.r = 0.0f;
00166 cammark.color.g = 1.0f;
00167 cammark.color.b = 1.0f;
00168 cammark.color.a = 1.0f;
00169 cammark.lifetime = ros::Duration();
00170 cammark.type = visualization_msgs::Marker::LINE_LIST;
00171
00172 ptmark = cammark;
00173 ptmark.color.r = 1.0f;
00174 ptmark.color.g = 0.0f;
00175 ptmark.color.b = 0.0f;
00176 ptmark.color.a = 0.5f;
00177 ptmark.scale.x = 0.01;
00178 ptmark.scale.y = 0.01;
00179 ptmark.scale.z = 0.01;
00180 ptmark.type = visualization_msgs::Marker::POINTS;
00181
00182 cstmark = cammark;
00183 cstmark.color.r = 1.0f;
00184 cstmark.color.g = 1.0f;
00185 cstmark.color.b = 0.0f;
00186 cstmark.color.a = 1.0f;
00187 cstmark.scale.x = 0.03;
00188 cstmark.scale.y = 0.1;
00189 cstmark.scale.z = 0.1;
00190 cstmark.type = visualization_msgs::Marker::LINE_LIST;
00191
00192
00193
00194 int npts = sba.tracks.size();
00195
00196
00197 if (npts <= 0) return;
00198
00199
00200 ptmark.points.resize(npts/dec+1);
00201 for (int i=0, ii=0; i<npts; i+=dec, ii++)
00202 {
00203 const Vector4d &pt = sba.tracks[i].point;
00204 ptmark.points[ii].x = pt(0);
00205 ptmark.points[ii].y = pt(2);
00206 ptmark.points[ii].z = -pt(1);
00207 }
00208
00209
00210 int ncams = sba.nodes.size();
00211 cammark.points.resize(ncams*6);
00212 for (int i=0, ii=0; i<ncams; i++)
00213 {
00214 const Node &nd = sba.nodes[i];
00215 Vector3d opt;
00216 Matrix<double,3,4> tr;
00217 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00218
00219 cammark.points[ii].x = nd.trans.x();
00220 cammark.points[ii].y = nd.trans.z();
00221 cammark.points[ii++].z = -nd.trans.y();
00222 opt = tr*Vector4d(0,0,0.3,1);
00223 cammark.points[ii].x = opt.x();
00224 cammark.points[ii].y = opt.z();
00225 cammark.points[ii++].z = -opt.y();
00226
00227 cammark.points[ii].x = nd.trans.x();
00228 cammark.points[ii].y = nd.trans.z();
00229 cammark.points[ii++].z = -nd.trans.y();
00230 opt = tr*Vector4d(0.2,0,0,1);
00231 cammark.points[ii].x = opt.x();
00232 cammark.points[ii].y = opt.z();
00233 cammark.points[ii++].z = -opt.y();
00234
00235 cammark.points[ii].x = nd.trans.x();
00236 cammark.points[ii].y = nd.trans.z();
00237 cammark.points[ii++].z = -nd.trans.y();
00238 opt = tr*Vector4d(0,0.1,0,1);
00239 cammark.points[ii].x = opt.x();
00240 cammark.points[ii].y = opt.z();
00241 cammark.points[ii++].z = -opt.y();
00242 }
00243
00244
00245 int num_tracks = sba.tracks.size();
00246 int ii = cammark.points.size();
00247
00248 for (int i=0; i < num_tracks; i++)
00249 {
00250 const ProjMap &prjs = sba.tracks[i].projections;
00251 for (ProjMap::const_iterator itr = prjs.begin(); itr != prjs.end(); itr++)
00252 {
00253 const Proj &prj = (*itr).second;
00254 if (prj.pointPlane)
00255 {
00256 cammark.points.resize(ii+2);
00257 Point pt0 = sba.tracks[i].point;
00258 Vector3d plane_point = prj.plane_point;
00259 Vector3d plane_normal = prj.plane_normal;
00260 Eigen::Vector3d w = pt0.head<3>()-plane_point;
00261
00262 Eigen::Vector3d projpt = pt0.head<3>() - (w.dot(plane_normal))*plane_normal;
00263
00264 Vector3d pt1 = projpt;
00265
00266 cammark.points[ii].x = pt0.x();
00267 cammark.points[ii].y = pt0.z();
00268 cammark.points[ii++].z = -pt0.y();
00269 cammark.points[ii].x = pt1.x();
00270 cammark.points[ii].y = pt1.z();
00271 cammark.points[ii++].z = -pt1.y();
00272 }
00273 }
00274 }
00275
00276
00277 #if 0
00278
00279 int ncons = spa.p2cons.size();
00280 cstmark.points.resize(ncons*6);
00281
00282 for (int i=0, ii=0; i<ncons; i++)
00283 {
00284 ConP2 &con = spa.p2cons[i];
00285 Node &nd0 = spa.nodes[con.ndr];
00286 Node &nd1 = spa.nodes[con.nd1];
00287
00288 Node &nd = spa.nodes[i];
00289 Vector3d opt;
00290 Matrix<double,3,4> tr;
00291 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00292
00293 cstmark.points[ii].x = nd.trans.x();
00294 cstmark.points[ii].y = nd.trans.z();
00295 cstmark.points[ii++].z = -nd.trans.y();
00296 opt = tr*Vector4d(0,0,0.3,1);
00297 cstmark.points[ii].x = opt.x();
00298 cstmark.points[ii].y = opt.z();
00299 cstmark.points[ii++].z = -opt.y();
00300
00301 cstmark.points[ii].x = nd.trans.x();
00302 cstmark.points[ii].y = nd.trans.z();
00303 cstmark.points[ii++].z = -nd.trans.y();
00304 opt = tr*Vector4d(0.2,0,0,1);
00305 cstmark.points[ii].x = opt.x();
00306 cstmark.points[ii].y = opt.z();
00307 cstmark.points[ii++].z = -opt.y();
00308
00309 cstmark.points[ii].x = nd.trans.x();
00310 cstmark.points[ii].y = nd.trans.z();
00311 cstmark.points[ii++].z = -nd.trans.y();
00312 opt = tr*Vector4d(0,0.1,0,1);
00313 cstmark.points[ii].x = opt.x();
00314 cstmark.points[ii].y = opt.z();
00315 cstmark.points[ii++].z = -opt.y();
00316
00317 #if 0
00318 cstmark.points[ii].x = nd0.trans.x();
00319 cstmark.points[ii].y= nd0.trans.z();
00320 cstmark.points[ii++].z = -nd0.trans.y();
00321 cstmark.points[ii].x = nd1.trans.x();
00322 cstmark.points[ii].y = nd1.trans.z();
00323 cstmark.points[ii++].z = -nd1.trans.y();
00324 #endif
00325 }
00326 #endif // SPA
00327
00328 cam_pub.publish(cammark);
00329 pt_pub.publish(ptmark);
00330
00331
00332 }
00333
00334
00335
00336
00337
00338 int main(int argc, char** argv)
00339 {
00340 if (argc < 8)
00341 {
00342 printf("Args are: <param file> <image dir> <left image file template> <right image file template> "
00343 "<vocab tree file> <vocab weights file> <calonder trees file>\n");
00344 exit(0);
00345 }
00346
00347
00348 fstream fstr;
00349 fstr.open(argv[1],fstream::in);
00350 if (!fstr.is_open())
00351 {
00352 printf("Can't open camera file %s\n",argv[1]);
00353 exit(0);
00354 }
00355 CamParams camp;
00356 fstr >> camp.fx;
00357 fstr >> camp.fy;
00358 fstr >> camp.cx;
00359 fstr >> camp.cy;
00360 fstr >> camp.tx;
00361
00362 cout << "Cam params: " << camp.fx << " " << camp.fy << " " << camp.cx
00363 << " " << camp.cy << " " << camp.tx << endl;
00364
00365
00366
00367 struct dirent **lims, **rims, **dirs;
00368 int nlim, nrim, ndirs;
00369 string dname = argv[2];
00370 if (!dname.compare(dname.size()-1,1,"/"))
00371 dname.erase(dname.size()-1);
00372
00373 string dirfn = dname.substr(dname.rfind("/")+1);
00374 string tdir = dname.substr(0,dname.rfind("/")+1);
00375 cout << "Top directory is " << tdir << endl;
00376 cout << "Search directory name is " << dirfn << endl;
00377 dreg = (char *)dirfn.c_str();
00378
00379 ndirs = scandir(tdir.c_str(),&dirs,getidir,alphasort);
00380 printf("Found %d directories\n", ndirs);
00381 printf("%s\n",dirs[0]->d_name);
00382
00383
00384 vslam::VslamSystem vslam(argv[5], argv[6]);
00385 typedef cv::CalonderDescriptorExtractor<float> Calonder;
00386 typedef cv::SiftDescriptorExtractor Sift;
00387
00388 vslam.frame_processor_.setFrameDescriptor(new Calonder(argv[7]));
00389
00390
00391
00392 vslam.setPointcloudProc(boost::shared_ptr<frame_common::PointcloudProc>(new frame_common::PointcloudProc()));
00393
00394 vslam.doPointPlane = false;
00395
00396
00397 vslam.setKeyDist(0.1);
00398 vslam.setKeyAngle(0.05);
00399 vslam.setKeyInliers(200);
00400 vslam.setHuber(40.0);
00401 vslam.vo_.pose_estimator_->wy = 92;
00402 vslam.vo_.pose_estimator_->wx = 92;
00403 vslam.vo_.pose_estimator_->numRansac = 10000;
00404 vslam.vo_.sba.verbose = false;
00405 vslam.sba_.verbose = false;
00406
00407
00408
00409 ros::init(argc, argv, "VisBundler");
00410 ros::NodeHandle nh ("~");
00411 ros::Publisher pt_pub = nh.advertise<visualization_msgs::Marker>("points", 0);
00412 ros::Publisher cam_pub = nh.advertise<visualization_msgs::Marker>("cameras", 0);
00413 ros::Publisher cst_pub = nh.advertise<visualization_msgs::Marker>("constraints", 0);
00414 ros::Publisher link_pub = nh.advertise<visualization_msgs::Marker>("links", 0);
00415 ros::Publisher pc_pub = nh.advertise<sensor_msgs::PointCloud2>("pointcloud", 1);
00416
00417
00418 srand(mstime());
00419
00420
00421 #ifdef VISMATCH
00422 const std::string window_name = "VO tracks";
00423 cv::namedWindow(window_name,0);
00424 cv::Mat display;
00425 #endif
00426
00427 int iter = 0;
00428 lreg = argv[3];
00429 rreg = argv[4];
00430
00431
00432
00433 for (int dd=0; dd<ndirs; dd++)
00434 {
00435 char dir[2048];
00436 sprintf(dir,"%s%s",tdir.c_str(),dirs[dd]->d_name);
00437 printf("Current directory: %s\n", dir);
00438
00439
00440 nlim = scandir(dir,&lims,getleft,alphasort);
00441 printf("Found %d left images\n", nlim);
00442 printf("%s\n",lims[0]->d_name);
00443
00444 nrim = scandir(dir,&rims,getright,alphasort);
00445 printf("Found %d disparity images\n", nrim);
00446 printf("%s\n",rims[0]->d_name);
00447
00448 if (nlim != nrim)
00449 {
00450 printf("Number of left/disparity images does not match: %d vs. %d\n", nlim, nrim);
00451 exit(0);
00452 }
00453
00454
00455
00456
00457 for (int ii=0; ii<nlim; iter++, ii++)
00458 {
00459
00460 char fn[2048];
00461 sprintf(fn,"%s/%s",dir,lims[ii]->d_name);
00462 cv::Mat image1 = cv::imread(fn,0);
00463 sprintf(fn,"%s/%s",dir,rims[ii]->d_name);
00464 cv::Mat image1r = cv::imread(fn,-1);
00465
00466 printf("Image: %s\n", fn);
00467 #if 0
00468 printf("Image size: %d x %d\n", image1.cols, image1.rows);
00469 printf("Image size: %d x %d\n", image1r.cols, image1r.rows);
00470 #endif
00471
00472 if (image1.rows == 0 || image1r.rows == 0)
00473 exit(0);
00474
00475
00476
00477
00478 bool is_keyframe = vslam.addFrame(camp, image1, image1r, 32.0, true);
00479
00480 usleep(10);
00481
00482 if (is_keyframe)
00483 {
00484 vslam.sba_.doSBA(10,1e-4,SBA_SPARSE_CHOLESKY);
00485
00487 int n = vslam.sba_.nodes.size();
00488 int np = vslam.sba_.tracks.size();
00489
00490
00491
00492 #if 1
00493 if (n%1 == 0)
00494 {
00495 drawgraph(vslam.vo_.sba, cam_pub, pt_pub, 1);
00496 publishRegisteredPointclouds(vslam.vo_.sba, vslam.vo_.frames, pc_pub);
00497 drawgraph(vslam.vo_.sba, cam_pub, pt_pub, 1);
00498 publishRegisteredPointclouds(vslam.vo_.sba, vslam.vo_.frames, pc_pub);
00499 for (int i=0; i<5; i++)
00500 {
00501
00502 cout << i << endl;
00503 vslam.vo_.sba.doSBA(1,1.0e-5,0);
00504 drawgraph(vslam.vo_.sba, cam_pub, pt_pub, 1);
00505 publishRegisteredPointclouds(vslam.vo_.sba, vslam.vo_.frames, pc_pub);
00506 drawgraph(vslam.vo_.sba, cam_pub, pt_pub, 1);
00507 publishRegisteredPointclouds(vslam.vo_.sba, vslam.vo_.frames, pc_pub);
00508 }
00509 }
00510 #endif
00511
00512
00513 if (n > 10 && n%500 == 0)
00514 {
00515 char fn[1024];
00516 sprintf(fn,"newcollege%d.g2o", n);
00517 sba::writeGraphFile(fn,vslam.sba_);
00518 sprintf(fn,"newcollege%dm.g2o", n);
00519 sba::writeGraphFile(fn,vslam.sba_,true);
00520
00521
00522
00523 }
00524
00525 #if 1
00526 int nnsba = 10;
00527 if (n > 4 && n%nnsba == 0)
00528 {
00529 cout << "Running large SBA" << endl;
00530 vslam.refine();
00531 }
00532 #endif
00533 }
00534
00535 #ifdef VISMATCH
00536
00537 if (1)
00538 {
00539 drawVOtracks(image1, vslam.vo_.frames, display);
00540 cv::imshow(window_name, display);
00541 cv::waitKey(0);
00542 }
00543 #endif
00544
00545 if (!nh.ok())
00546 return 0;
00547 }
00548 }
00549 return 0;
00550 }