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
00065
00066 #define VISMATCH
00067
00068
00069 #include <sys/time.h>
00070 static double mstime()
00071 {
00072 timeval tv;
00073 gettimeofday(&tv,NULL);
00074 long long ts = tv.tv_sec;
00075 ts *= 1000000;
00076 ts += tv.tv_usec;
00077 return (double)ts*.001;
00078 }
00079
00080
00081 char *lreg, *rreg, *dreg;
00082
00083
00084 int getleft(struct dirent const *entry)
00085 {
00086 if (!fnmatch(lreg,entry->d_name,0))
00087 return 1;
00088 return 0;
00089 }
00090
00091 int getright(struct dirent const *entry)
00092 {
00093 if (!fnmatch(rreg,entry->d_name,0))
00094 return 1;
00095 return 0;
00096 }
00097
00098
00099 int getidir(struct dirent const *entry)
00100 {
00101 if (!fnmatch(dreg,entry->d_name,0))
00102 return 1;
00103 return 0;
00104 }
00105
00106
00107
00108
00109 void
00110 drawgraph(const SysSBA &sba, const ros::Publisher &cam_pub, const ros::Publisher &pt_pub, int dec
00111 )
00112 {
00113 visualization_msgs::Marker cammark, ptmark, cstmark;
00114 cammark.header.frame_id = "/pgraph";
00115 cammark.header.stamp = ros::Time();
00116 cammark.ns = "pgraph";
00117 cammark.id = 0;
00118 cammark.action = visualization_msgs::Marker::ADD;
00119 cammark.pose.position.x = 0;
00120 cammark.pose.position.y = 0;
00121 cammark.pose.position.z = 0;
00122 cammark.pose.orientation.x = 0.0;
00123 cammark.pose.orientation.y = 0.0;
00124 cammark.pose.orientation.z = 0.0;
00125 cammark.pose.orientation.w = 1.0;
00126 cammark.scale.x = 0.02;
00127 cammark.scale.y = 0.02;
00128 cammark.scale.z = 0.02;
00129 cammark.color.r = 0.0f;
00130 cammark.color.g = 1.0f;
00131 cammark.color.b = 1.0f;
00132 cammark.color.a = 1.0f;
00133 cammark.lifetime = ros::Duration();
00134 cammark.type = visualization_msgs::Marker::LINE_LIST;
00135
00136 ptmark = cammark;
00137 ptmark.color.r = 1.0f;
00138 ptmark.color.g = 0.0f;
00139 ptmark.color.b = 0.0f;
00140 ptmark.color.a = 0.5f;
00141 ptmark.scale.x = 0.02;
00142 ptmark.scale.y = 0.02;
00143 ptmark.scale.z = 0.02;
00144 ptmark.type = visualization_msgs::Marker::POINTS;
00145
00146 cstmark = cammark;
00147 cstmark.color.r = 1.0f;
00148 cstmark.color.g = 1.0f;
00149 cstmark.color.b = 0.0f;
00150 cstmark.color.a = 1.0f;
00151 cstmark.scale.x = 0.03;
00152 cstmark.scale.y = 0.1;
00153 cstmark.scale.z = 0.1;
00154 cstmark.type = visualization_msgs::Marker::LINE_LIST;
00155
00156
00157
00158 int npts = sba.tracks.size();
00159
00160 cout << "Number of points to draw: " << npts << endl;
00161 if (npts <= 0) return;
00162
00163
00164 ptmark.points.resize(npts/dec+1);
00165 for (int i=0, ii=0; i<npts; i+=dec, ii++)
00166 {
00167 const Vector4d &pt = sba.tracks[i].point;
00168 ptmark.points[ii].x = pt(0);
00169 ptmark.points[ii].y = pt(2);
00170 ptmark.points[ii].z = -pt(1);
00171 }
00172
00173
00174 int ncams = sba.nodes.size();
00175 cammark.points.resize(ncams*6);
00176 for (int i=0, ii=0; i<ncams; i++)
00177 {
00178 const Node &nd = sba.nodes[i];
00179 Vector3d opt;
00180 Matrix<double,3,4> tr;
00181 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00182
00183 cammark.points[ii].x = nd.trans.x();
00184 cammark.points[ii].y = nd.trans.z();
00185 cammark.points[ii++].z = -nd.trans.y();
00186 opt = tr*Vector4d(0,0,0.3,1);
00187 cammark.points[ii].x = opt.x();
00188 cammark.points[ii].y = opt.z();
00189 cammark.points[ii++].z = -opt.y();
00190
00191 cammark.points[ii].x = nd.trans.x();
00192 cammark.points[ii].y = nd.trans.z();
00193 cammark.points[ii++].z = -nd.trans.y();
00194 opt = tr*Vector4d(0.2,0,0,1);
00195 cammark.points[ii].x = opt.x();
00196 cammark.points[ii].y = opt.z();
00197 cammark.points[ii++].z = -opt.y();
00198
00199 cammark.points[ii].x = nd.trans.x();
00200 cammark.points[ii].y = nd.trans.z();
00201 cammark.points[ii++].z = -nd.trans.y();
00202 opt = tr*Vector4d(0,0.1,0,1);
00203 cammark.points[ii].x = opt.x();
00204 cammark.points[ii].y = opt.z();
00205 cammark.points[ii++].z = -opt.y();
00206 }
00207
00208 #if 0
00209
00210 int ncons = spa.p2cons.size();
00211 cstmark.points.resize(ncons*6);
00212
00213 for (int i=0, ii=0; i<ncons; i++)
00214 {
00215 ConP2 &con = spa.p2cons[i];
00216 Node &nd0 = spa.nodes[con.ndr];
00217 Node &nd1 = spa.nodes[con.nd1];
00218
00219 Node &nd = spa.nodes[i];
00220 Vector3d opt;
00221 Matrix<double,3,4> tr;
00222 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00223
00224 cstmark.points[ii].x = nd.trans.x();
00225 cstmark.points[ii].y = nd.trans.z();
00226 cstmark.points[ii++].z = -nd.trans.y();
00227 opt = tr*Vector4d(0,0,0.3,1);
00228 cstmark.points[ii].x = opt.x();
00229 cstmark.points[ii].y = opt.z();
00230 cstmark.points[ii++].z = -opt.y();
00231
00232 cstmark.points[ii].x = nd.trans.x();
00233 cstmark.points[ii].y = nd.trans.z();
00234 cstmark.points[ii++].z = -nd.trans.y();
00235 opt = tr*Vector4d(0.2,0,0,1);
00236 cstmark.points[ii].x = opt.x();
00237 cstmark.points[ii].y = opt.z();
00238 cstmark.points[ii++].z = -opt.y();
00239
00240 cstmark.points[ii].x = nd.trans.x();
00241 cstmark.points[ii].y = nd.trans.z();
00242 cstmark.points[ii++].z = -nd.trans.y();
00243 opt = tr*Vector4d(0,0.1,0,1);
00244 cstmark.points[ii].x = opt.x();
00245 cstmark.points[ii].y = opt.z();
00246 cstmark.points[ii++].z = -opt.y();
00247
00248 #if 0
00249 cstmark.points[ii].x = nd0.trans.x();
00250 cstmark.points[ii].y= nd0.trans.z();
00251 cstmark.points[ii++].z = -nd0.trans.y();
00252 cstmark.points[ii].x = nd1.trans.x();
00253 cstmark.points[ii].y = nd1.trans.z();
00254 cstmark.points[ii++].z = -nd1.trans.y();
00255 #endif
00256 }
00257 #endif // SPA
00258
00259 cam_pub.publish(cammark);
00260 pt_pub.publish(ptmark);
00261
00262 }
00263
00264
00265
00266
00267
00268 int main(int argc, char** argv)
00269 {
00270 if (argc < 8)
00271 {
00272 printf("Args are: <param file> <image dir> <left image file template> <right image file template> "
00273 "<vocab tree file> <vocab weights file> <calonder trees file>\n");
00274 exit(0);
00275 }
00276
00277
00278 fstream fstr;
00279 fstr.open(argv[1],fstream::in);
00280 if (!fstr.is_open())
00281 {
00282 printf("Can't open camera file %s\n",argv[1]);
00283 exit(0);
00284 }
00285 CamParams camp;
00286 fstr >> camp.fx;
00287 fstr >> camp.fy;
00288 fstr >> camp.cx;
00289 fstr >> camp.cy;
00290 fstr >> camp.tx;
00291
00292 cout << "Cam params: " << camp.fx << " " << camp.fy << " " << camp.cx
00293 << " " << camp.cy << " " << camp.tx << endl;
00294
00295
00296
00297 struct dirent **lims, **rims, **dirs;
00298 int nlim, nrim, ndirs;
00299 string dname = argv[2];
00300 if (!dname.compare(dname.size()-1,1,"/"))
00301 dname.erase(dname.size()-1);
00302
00303 string dirfn = dname.substr(dname.rfind("/")+1);
00304 string tdir = dname.substr(0,dname.rfind("/")+1);
00305 cout << "Top directory is " << tdir << endl;
00306 cout << "Search directory name is " << dirfn << endl;
00307 dreg = (char *)dirfn.c_str();
00308
00309 ndirs = scandir(tdir.c_str(),&dirs,getidir,alphasort);
00310 printf("Found %d directories\n", ndirs);
00311 printf("%s\n",dirs[0]->d_name);
00312
00313
00314 vslam::VslamSystem vslam(argv[5], argv[6]);
00315 typedef cv::CalonderDescriptorExtractor<float> Calonder;
00316 vslam.frame_processor_.setFrameDescriptor(new Calonder(argv[7]));
00317
00318
00319 vslam.setKeyDist(0.4);
00320 vslam.setKeyAngle(0.2);
00321 #ifdef HOWARD
00322 vslam.setKeyInliers(300);
00323 #else
00324 vslam.setKeyInliers(300);
00325 #endif
00326 vslam.setHuber(2.0);
00327
00328
00329
00330 vslam.vo_.sba.verbose = false;
00331 vslam.sba_.verbose = false;
00332
00333
00334 ros::init(argc, argv, "VisBundler");
00335 ros::NodeHandle nh ("~");
00336 ros::Publisher pt_pub = nh.advertise<visualization_msgs::Marker>("points", 0);
00337 ros::Publisher cam_pub = nh.advertise<visualization_msgs::Marker>("cameras", 0);
00338 ros::Publisher cst_pub = nh.advertise<visualization_msgs::Marker>("constraints", 0);
00339 ros::Publisher link_pub = nh.advertise<visualization_msgs::Marker>("links", 0);
00340
00341
00342 srand(mstime());
00343
00344
00345 #ifdef VISMATCH
00346 const std::string window_name = "VO tracks";
00347 cv::namedWindow(window_name,0);
00348 cv::Mat display;
00349 #endif
00350
00351 int iter = 0;
00352 lreg = argv[3];
00353 rreg = argv[4];
00354
00355
00356
00357 for (int dd=0; dd<ndirs; dd++)
00358 {
00359 char dir[2048];
00360 sprintf(dir,"%s%s",tdir.c_str(),dirs[dd]->d_name);
00361 printf("Current directory: %s\n", dir);
00362
00363
00364 nlim = scandir(dir,&lims,getleft,alphasort);
00365 printf("Found %d left images\n", nlim);
00366 printf("%s\n",lims[0]->d_name);
00367
00368 nrim = scandir(dir,&rims,getright,alphasort);
00369 printf("Found %d right images\n", nrim);
00370 printf("%s\n",rims[0]->d_name);
00371
00372 if (nlim != nrim)
00373 {
00374 printf("Number of left/right images does not match: %d vs. %d\n", nlim, nrim);
00375 exit(0);
00376 }
00377
00378
00379
00380
00381 for (int ii=0; ii<nlim; iter++, ii++)
00382 {
00383
00384 char fn[2048];
00385 sprintf(fn,"%s/%s",dir,lims[ii]->d_name);
00386 cv::Mat image1 = cv::imread(fn,0);
00387 sprintf(fn,"%s/%s",dir,rims[ii]->d_name);
00388 cv::Mat image1r = cv::imread(fn,0);
00389
00390 #if 0
00391 printf("Image size: %d x %d\n", image1.cols, image1.rows);
00392 printf("Image size: %d x %d\n", image1r.cols, image1r.rows);
00393 #endif
00394
00395 if (image1.rows == 0 || image1r.rows == 0)
00396 exit(0);
00397
00398
00399 bool is_keyframe = vslam.addFrame(camp, image1, image1r);
00400
00401 if (is_keyframe)
00402 {
00404 int n = vslam.sba_.nodes.size();
00405 int np = vslam.sba_.tracks.size();
00406
00407
00408 cout << "drawing with " << n << " nodes and " << np << " points..." << endl << endl;
00409 #if 1
00410 if (n%2 == 0)
00411 drawgraph(vslam.sba_, cam_pub, pt_pub, 1);
00412 #endif
00413
00414
00415 if (n > 10 && n%500 == 0)
00416 {
00417 char fn[1024];
00418 sprintf(fn,"newcollege%d.g2o", n);
00419 sba::writeGraphFile(fn,vslam.sba_);
00420 sprintf(fn,"newcollege%dm.g2o", n);
00421 sba::writeGraphFile(fn,vslam.sba_,true);
00422
00423
00424
00425 }
00426
00427 #if 1
00428 int nnsba = 10;
00429 if (n > 4 && n%nnsba == 0)
00430 {
00431 cout << "Running large SBA" << endl;
00432 vslam.refine();
00433 }
00434 #endif
00435 }
00436
00437 #ifdef VISMATCH
00438
00439 if (1)
00440 {
00441 drawVOtracks(image1, vslam.vo_.frames, display);
00442 cv::imshow(window_name, display);
00443 cv::waitKey(10);
00444 }
00445 #endif
00446
00447 if (!nh.ok())
00448 return 0;
00449 }
00450 }
00451 return 0;
00452 }