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/vo.h>
00047 #include <vslam_system/place_recognizer.h>
00048 #include <posest/pe2d.h>
00049 #include <sba/sba.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(SysSBA &sba, SysSPA &spa, ros::Publisher &cam_pub, ros::Publisher &pt_pub, int dec,
00111 ros::Publisher &cst_pub, ros::Publisher &link_pub)
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.2;
00142 ptmark.scale.y = 0.2;
00143 ptmark.scale.z = 0.2;
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.06;
00152 cstmark.scale.y = 0.2;
00153 cstmark.scale.z = 0.2;
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 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
00175
00176 int ncams = sba.nodes.size();
00177 cammark.points.resize(ncams*6);
00178 for (int i=0, ii=0; i<ncams; i++)
00179 {
00180 Node &nd = sba.nodes[i];
00181 Vector3d opt;
00182 Matrix<double,3,4> tr;
00183 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00184
00185 printf("camera transform: %f %f %f\n", nd.trans.x(),
00186 nd.trans.y(), nd.trans.z());
00187 cammark.points[ii].x = nd.trans.x();
00188 cammark.points[ii].y = nd.trans.z();
00189 cammark.points[ii++].z = -nd.trans.y();
00190 opt = tr*Vector4d(0,0,0.3,1);
00191 cammark.points[ii].x = opt.x();
00192 cammark.points[ii].y = opt.z();
00193 cammark.points[ii++].z = -opt.y();
00194
00195 cammark.points[ii].x = nd.trans.x();
00196 cammark.points[ii].y = nd.trans.z();
00197 cammark.points[ii++].z = -nd.trans.y();
00198 opt = tr*Vector4d(0.2,0,0,1);
00199 cammark.points[ii].x = opt.x();
00200 cammark.points[ii].y = opt.z();
00201 cammark.points[ii++].z = -opt.y();
00202
00203 cammark.points[ii].x = nd.trans.x();
00204 cammark.points[ii].y = nd.trans.z();
00205 cammark.points[ii++].z = -nd.trans.y();
00206 opt = tr*Vector4d(0,0.1,0,1);
00207 cammark.points[ii].x = opt.x();
00208 cammark.points[ii].y = opt.z();
00209 cammark.points[ii++].z = -opt.y();
00210 }
00211
00212
00213 int ncons = spa.p2cons.size();
00214 cstmark.points.resize(ncons*6);
00215
00216 for (int i=0, ii=0; i<ncons; i++)
00217 {
00218 ConP2 &con = spa.p2cons[i];
00219 Node &nd0 = spa.nodes[con.ndr];
00220 Node &nd1 = spa.nodes[con.nd1];
00221
00222 Node &nd = spa.nodes[i];
00223 Vector3d opt;
00224 Matrix<double,3,4> tr;
00225 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00226
00227 cstmark.points[ii].x = nd.trans.x();
00228 cstmark.points[ii].y = nd.trans.z();
00229 cstmark.points[ii++].z = -nd.trans.y();
00230 opt = tr*Vector4d(0,0,0.3,1);
00231 cstmark.points[ii].x = opt.x();
00232 cstmark.points[ii].y = opt.z();
00233 cstmark.points[ii++].z = -opt.y();
00234
00235 cstmark.points[ii].x = nd.trans.x();
00236 cstmark.points[ii].y = nd.trans.z();
00237 cstmark.points[ii++].z = -nd.trans.y();
00238 opt = tr*Vector4d(0.2,0,0,1);
00239 cstmark.points[ii].x = opt.x();
00240 cstmark.points[ii].y = opt.z();
00241 cstmark.points[ii++].z = -opt.y();
00242
00243 cstmark.points[ii].x = nd.trans.x();
00244 cstmark.points[ii].y = nd.trans.z();
00245 cstmark.points[ii++].z = -nd.trans.y();
00246 opt = tr*Vector4d(0,0.1,0,1);
00247 cstmark.points[ii].x = opt.x();
00248 cstmark.points[ii].y = opt.z();
00249 cstmark.points[ii++].z = -opt.y();
00250
00251 #if 0
00252 cstmark.points[ii].x = nd0.trans.x();
00253 cstmark.points[ii].y= nd0.trans.z();
00254 cstmark.points[ii++].z = -nd0.trans.y();
00255 cstmark.points[ii].x = nd1.trans.x();
00256 cstmark.points[ii].y = nd1.trans.z();
00257 cstmark.points[ii++].z = -nd1.trans.y();
00258 #endif
00259 }
00260
00261 cam_pub.publish(cammark);
00262 pt_pub.publish(ptmark);
00263 cst_pub.publish(cstmark);
00264
00265 #if 0
00266 cv::namedWindow("1", 1);
00267 cv::waitKey();
00268 #endif
00269 }
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279 double maxdist = 0.5;
00280 double maxang = 10.0;
00281 int mininls = 30;
00282 int ndi = 0;
00283
00284 int main(int argc, char** argv)
00285 {
00286 if (argc < 5)
00287 {
00288 printf("Args are: <param file> <image dir> <left image file template> <right image file template> \n");
00289 exit(0);
00290 }
00291
00292
00293 fstream fstr;
00294 fstr.open(argv[1],fstream::in);
00295 if (!fstr.is_open())
00296 {
00297 printf("Can't open camera file %s\n",argv[1]);
00298 exit(0);
00299 }
00300 CamParams camp;
00301 fstr >> camp.fx;
00302 fstr >> camp.fy;
00303 fstr >> camp.cx;
00304 fstr >> camp.cy;
00305 fstr >> camp.tx;
00306
00307 cout << "Cam params: " << camp.fx << " " << camp.fy << " " << camp.cx
00308 << " " << camp.cy << " " << camp.tx << endl;
00309
00310
00311
00312 struct dirent **lims, **rims, **dirs;
00313 int nlim, nrim, ndirs;
00314 string dname = argv[2];
00315 if (!dname.compare(dname.size()-1,1,"/"))
00316 dname.erase(dname.size()-1);
00317
00318 string dirfn = dname.substr(dname.rfind("/")+1);
00319 string tdir = dname.substr(0,dname.rfind("/")+1);
00320 cout << "Top directory is " << tdir << endl;
00321 cout << "Search directory name is " << dirfn << endl;
00322 dreg = (char *)dirfn.c_str();
00323
00324 ndirs = scandir(tdir.c_str(),&dirs,getidir,alphasort);
00325 printf("Found %d directories\n", ndirs);
00326 printf("%s\n",dirs[0]->d_name);
00327
00328
00329 cout << "Setting up frame processing..." << flush;
00330 FrameProc fp(15);
00331 fp.setFrameDetector(cv::Ptr<cv::FeatureDetector>(new cv::SurfFeatureDetector(200)));
00332 cout << "done" << endl;
00333 vector<Frame, Eigen::aligned_allocator<Frame> > frames;
00334
00335 SysSBA sba;
00336 sba.useCholmod(false);
00337
00338 SysSPA spa;
00339 int spaFrameId = -1;
00340 int ndi0 = 0;
00341
00342
00343 voSt vo(boost::shared_ptr<pe::PoseEstimator>(new pe::PoseEstimator2d), 40,10,mininls,maxdist,maxang);
00344
00345 std::vector<const Frame*> place_matches;
00347 pe::PoseEstimator3d pe(1000,true,10.0,3.0,3.0);
00348 pe.wx = 92;
00349 pe.wy = 48;
00350
00351
00352 ros::init(argc, argv, "VisBundler");
00353 ros::NodeHandle nh ("~");
00354 ros::Publisher pt_pub = nh.advertise<visualization_msgs::Marker>("points", 0);
00355 ros::Publisher cam_pub = nh.advertise<visualization_msgs::Marker>("cameras", 0);
00356 ros::Publisher cst_pub = nh.advertise<visualization_msgs::Marker>("constraints", 0);
00357 ros::Publisher link_pub = nh.advertise<visualization_msgs::Marker>("links", 0);
00358
00359
00360 srand(mstime());
00361
00362
00363 #ifdef VISMATCH
00364 const std::string window_name = "VO tracks";
00365 cv::namedWindow(window_name,0);
00366 cv::Mat display;
00367 #endif
00368
00369 int iter = 0;
00370 lreg = argv[3];
00371 rreg = argv[4];
00372
00373
00374 for (int dd=0; dd<ndirs; dd++)
00375 {
00376 char dir[2048];
00377 sprintf(dir,"%s%s",tdir.c_str(),dirs[dd]->d_name);
00378 printf("Current directory: %s\n", dir);
00379
00380
00381 nlim = scandir(dir,&lims,getleft,alphasort);
00382 printf("Found %d left images\n", nlim);
00383 printf("%s\n",lims[0]->d_name);
00384
00385 nrim = scandir(dir,&rims,getright,alphasort);
00386 printf("Found %d right images\n", nrim);
00387 printf("%s\n",rims[0]->d_name);
00388
00389 if (nlim != nrim)
00390 {
00391 printf("Number of left/right images does not match: %d vs. %d\n", nlim, nrim);
00392 exit(0);
00393 }
00394
00395 const int init_min_frame_count = 5;
00396
00397
00398 bool ret = false;
00399 for (int ii=0; ii<nlim; iter++, ii += ret ? 5 : 1)
00400 {
00401 if(ii > 0 && ii < init_min_frame_count)
00402 {
00403 continue;
00404 }
00405
00406
00407 char fn[2048];
00408 sprintf(fn,"%s/%s",dir,lims[ii]->d_name);
00409 cv::Mat image1 = cv::imread(fn,0);
00410 sprintf(fn,"%s/%s",dir,rims[ii]->d_name);
00411 cv::Mat image1r = cv::imread(fn,0);
00412
00413
00414 if (image1.rows == 0 || image1r.rows == 0)
00415 exit(0);
00416
00417 double t0 = mstime();
00418 Frame f1;
00419 f1.setCamParams(camp);
00420
00421 fp.setMonoFrame(f1,image1);
00422 f1.frameId = sba.nodes.size();
00423
00424 f1.imgRight = cv::Mat();
00425
00426
00427 cout << "calling vo::addFrame" << endl;
00428 ret = vo.addFrame(f1);
00429
00430
00431 if (ret)
00432 {
00433 frames.push_back(f1);
00434 if(frames.size() > 1)
00435 {
00436 Frame& _fs = frames.back();
00437 Frame& _f0 = *(frames.end() - 2);
00438
00439 if(vo.pose_estimator_->getMethod() == pe::PoseEstimator::SFM)
00440 {
00441
00442 cout << "frames.size() " << frames.size() << endl;
00443 frames[0].pts = (vo.frames.end() - 2)->pts;
00444 frames[0].goodPts = (vo.frames.end() - 2)->goodPts;
00445 }
00446
00447 int count = 0;
00448 for(size_t i = 0; i < _f0.goodPts.size(); i++)
00449 {
00450 if(_f0.goodPts[i]) count++;
00451 }
00452 printf("The number of good points: %d\n", count);
00453 }
00454
00455 {
00456 vo.transferLatestFrame(frames,sba);
00457 }
00458 }
00459
00460 if (frames.size() > 1 && vo.pose_estimator_->inliers.size() < mininls)
00461 cout << endl << "******** Bad image match: " << fn << endl << endl;
00462
00463
00464
00465 if (ret)
00466 {
00467 int n = sba.nodes.size();
00468 int np = sba.tracks.size();
00469
00470
00471 cout << "drawing with " << n << " nodes and " << np << " points..." << endl << endl;
00472 #if 1
00473 if (n%2 == 0)
00474 drawgraph(sba,spa,cam_pub,pt_pub,1,cst_pub,link_pub);
00475 #endif
00476
00477 #if 1
00478 int nnsba = 10;
00479 if (n > 4 && n%nnsba == 0)
00480 {
00481 cout << "Running large SBA" << endl;
00482
00483 }
00484 #endif
00485 }
00486
00487 #ifdef VISMATCH
00488
00489 if (ret || 1)
00490 {
00491 drawVOtracks(image1,vo.frames,display);
00492 cv::imshow(window_name, display);
00493 cv::waitKey(10);
00494 }
00495 #endif
00496
00497 if (!nh.ok())
00498 return 0;
00499 }
00500 }
00501 return 0;
00502 }