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 #include <ros/ros.h>
00038 #include <visualization_msgs/Marker.h>
00039 #include <visualization_msgs/MarkerArray.h>
00040 #include <geometry_msgs/Point.h>
00041
00042 #include "sba/read_spa.h"
00043 #include "sba/sba.h"
00044 #include <sba/sba_file_io.h>
00045 #include "frame_common/frame.h"
00046
00047 #include <iostream>
00048 #include <iomanip>
00049 #include <fstream>
00050 #include <vector>
00051 #include <sys/time.h>
00052
00053 using namespace std;
00054 using namespace Eigen;
00055 using namespace sba;
00056 using namespace frame_common;
00057
00058
00059
00060
00061 long long utime()
00062 {
00063 timeval tv;
00064 gettimeofday(&tv,NULL);
00065 long long ts = tv.tv_sec;
00066 ts *= 1000000;
00067 ts += tv.tv_usec;
00068 return ts;
00069 }
00070
00071 #define SAVE_RESULTS
00072
00073
00074
00075 void
00076 drawgraph(SysSBA &sba, ros::Publisher &cam_pub, ros::Publisher &pt_pub, int dec)
00077 {
00078 visualization_msgs::Marker cammark, ptmark;
00079 cammark.header.frame_id = "/pgraph";
00080 cammark.header.stamp = ros::Time();
00081 cammark.ns = "pgraph";
00082 cammark.id = 0;
00083 cammark.action = visualization_msgs::Marker::ADD;
00084 cammark.pose.position.x = 0;
00085 cammark.pose.position.y = 0;
00086 cammark.pose.position.z = 0;
00087 cammark.pose.orientation.x = 0.0;
00088 cammark.pose.orientation.y = 0.0;
00089 cammark.pose.orientation.z = 0.0;
00090 cammark.pose.orientation.w = 1.0;
00091 cammark.scale.x = 0.02;
00092 cammark.scale.y = 0.02;
00093 cammark.scale.z = 0.02;
00094 cammark.color.r = 0.0f;
00095 cammark.color.g = 1.0f;
00096 cammark.color.b = 1.0f;
00097 cammark.color.a = 1.0f;
00098 cammark.lifetime = ros::Duration();
00099 cammark.type = visualization_msgs::Marker::LINE_LIST;
00100
00101 ptmark = cammark;
00102 ptmark.color.r = 1.0f;
00103 ptmark.color.g = 0.0f;
00104 ptmark.color.b = 0.0f;
00105 ptmark.color.a = 0.5f;
00106 ptmark.scale.x = 0.01;
00107 ptmark.scale.y = 0.01;
00108 ptmark.scale.z = 0.01;
00109 ptmark.type = visualization_msgs::Marker::POINTS;
00110
00111
00112
00113 int npts = sba.tracks.size();
00114 ptmark.points.resize(npts/dec+1);
00115 for (int i=0, ii=0; i<npts; i+=dec, ii++)
00116 {
00117 Vector4d &pt = sba.tracks[i].point;
00118 ptmark.points[ii].x = pt(0);
00119 ptmark.points[ii].y = pt(2);
00120 ptmark.points[ii].z = -pt(1);
00121 }
00122
00123
00124 int ncams = sba.nodes.size();
00125 cammark.points.resize(ncams*6);
00126 for (int i=0, ii=0; i<ncams; i++)
00127 {
00128 Node &nd = sba.nodes[i];
00129 Vector3d opt;
00130 Matrix<double,3,4> tr;
00131 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00132
00133 cammark.points[ii].x = nd.trans.x();
00134 cammark.points[ii].y = nd.trans.z();
00135 cammark.points[ii++].z = -nd.trans.y();
00136 opt = tr*Vector4d(0,0,0.3,1);
00137 cammark.points[ii].x = opt.x();
00138 cammark.points[ii].y = opt.z();
00139 cammark.points[ii++].z = -opt.y();
00140
00141 cammark.points[ii].x = nd.trans.x();
00142 cammark.points[ii].y = nd.trans.z();
00143 cammark.points[ii++].z = -nd.trans.y();
00144 opt = tr*Vector4d(0.1,0,0,1);
00145 cammark.points[ii].x = opt.x();
00146 cammark.points[ii].y = opt.z();
00147 cammark.points[ii++].z = -opt.y();
00148
00149 cammark.points[ii].x = nd.trans.x();
00150 cammark.points[ii].y = nd.trans.z();
00151 cammark.points[ii++].z = -nd.trans.y();
00152 opt = tr*Vector4d(0,0.1,0,1);
00153 cammark.points[ii].x = opt.x();
00154 cammark.points[ii].y = opt.z();
00155 cammark.points[ii++].z = -opt.y();
00156 }
00157
00158 cam_pub.publish(cammark);
00159 pt_pub.publish(ptmark);
00160 }
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170 int main(int argc, char **argv)
00171 {
00172 char *fin;
00173
00174 if (argc < 3)
00175 {
00176 cout << "Arguments are: <cam params> <input filename> [<number of nodes to use>]" << endl;
00177 return -1;
00178 }
00179
00180
00181 int nnodes = 1000000;
00182
00183 if (argc > 3)
00184 nnodes = atoi(argv[3]);
00185
00186 int doiters = 10;
00187 if (argc > 4)
00188 doiters = atoi(argv[4]);
00189
00190 fin = argv[2];
00191
00192
00193 fstream fstr;
00194 fstr.open(argv[1],fstream::in);
00195 if (!fstr.is_open())
00196 {
00197 printf("Can't open camera file %s\n",argv[1]);
00198 exit(0);
00199 }
00200 CamParams camp;
00201 fstr >> camp.fx;
00202 fstr >> camp.fy;
00203 fstr >> camp.cx;
00204 fstr >> camp.cy;
00205 fstr >> camp.tx;
00206
00207 cout << "Cam params: " << camp.fx << " " << camp.fy << " " << camp.cx
00208 << " " << camp.cy << " " << camp.tx << endl;
00209
00210
00211
00212 std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > ntrans;
00213
00214 std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > nqrot;
00215
00216 std::vector< Eigen::Vector2i, Eigen::aligned_allocator<Eigen::Vector2i> > cind;
00217
00218 std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > ctrans;
00219
00220 std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > cqrot;
00221
00222 std::vector< Eigen::Matrix<double,6,6>, Eigen::aligned_allocator<Eigen::Matrix<double,6,6> > > cvar;
00223
00224 std::vector<struct tinfo> tracks;
00225
00226
00227 ReadSPAFile(fin,ntrans,nqrot,cind,ctrans,cqrot,cvar,tracks);
00228
00229 cout << "[ReadSPAFile] Found " << (int)ntrans.size() << " nodes and "
00230 << (int)cind.size() << " constraints, " << (int)tracks.size()
00231 << " projection pairs" << endl;
00232
00233
00234
00235 ros::init(argc, argv, "VisBundler");
00236 ros::NodeHandle n ("~");
00237 ros::Publisher pt_pub = n.advertise<visualization_msgs::Marker>("points", 0);
00238 ros::Publisher cam_pub = n.advertise<visualization_msgs::Marker>("cameras", 0);
00239
00240
00241 SysSBA sba;
00242 Node::initDr();
00243
00244 vector<Frame> frames;
00245 Frame frm;
00246 frm.setCamParams(camp);
00247
00248
00249 for (int i=0; i<(int)ntrans.size(); i++)
00250 {
00251 if (i>=nnodes) break;
00252
00253 Node nd;
00254
00255
00256 Quaternion<double> frq;
00257 frq.coeffs() = nqrot[i];
00258 frq.normalize();
00259 if (frq.w() <= 0.0) frq.coeffs() = -frq.coeffs();
00260 nd.qrot = frq.coeffs();
00261
00262
00263 Vector4d v;
00264 v.head(3) = ntrans[i];
00265 v(3) = 1.0;
00266 nd.trans = v;
00267 nd.setTransform();
00268 nd.setKcam(camp);
00269 nd.setDri();
00270
00271
00272 sba.nodes.push_back(nd);
00273
00274
00275 frames.push_back(frm);
00276 }
00277
00278
00279
00280
00281 std::vector<std::pair<int,int> > pairs;
00282 double ftx = camp.fx * camp.tx;
00283 for (int i=0; i<(int)tracks.size(); i++)
00284 {
00285 tinfo &ti = tracks[i];
00286 if (ti.fn0 >= (int)frames.size() || ti.fn1 >= (int)frames.size())
00287 {
00288 cout << "Bad frame index at track " << i << endl;
00289 return -1;
00290 }
00291 Frame &f0 = frames[ti.fn0];
00292 Frame &f1 = frames[ti.fn1];
00293 Node &nd0 = sba.nodes[ti.fn0];
00294 Node &nd1 = sba.nodes[ti.fn1];
00295 int fpn0 = ti.fpn0;
00296 int fpn1 = ti.fpn1;
00297 if (fpn0 >= (int)f0.kpts.size())
00298 {
00299 f0.kpts.resize(fpn0+1);
00300 f0.ipts.resize(fpn0+1,-1);
00301 f0.pts.resize(fpn0+1);
00302 }
00303 if (fpn1 >= (int)f1.kpts.size())
00304 {
00305 f1.kpts.resize(fpn1+1);
00306 f1.ipts.resize(fpn1+1,-1);
00307 f1.pts.resize(fpn1+1);
00308 }
00309
00310
00311 int pn0 = f0.ipts[fpn0];
00312 int pn1 = f1.ipts[fpn1];
00313 if (pn0 < 0)
00314 f0.ipts[fpn0] = i;
00315 else
00316 pairs.push_back(std::pair<int,int>(pn0,i));
00317 if (pn1 < 0)
00318 f1.ipts[fpn1] = i;
00319 else
00320 pairs.push_back(std::pair<int,int>(pn1,i));
00321
00322
00323
00324 Point pt0(ti.x0,ti.y0,ti.z0,1.0);
00325 Matrix<double,3,4> f2w;
00326 Quaterniond qr;
00327 qr = nd0.qrot;
00328 transformF2W(f2w,nd0.trans,qr);
00329 pt0.head(3) = f2w*pt0;
00330 sba.addPoint(pt0);
00331 Vector2d kp0,kp1;
00332 nd0.project2im(kp0,pt0);
00333
00334 Point pt1(ti.x1,ti.y1,ti.z1,1.0);
00335 qr = nd1.qrot;
00336 transformF2W(f2w,nd1.trans,qr);
00337 pt1.head(3) = f2w*pt1;
00338 nd1.project2im(kp1,pt1);
00339
00340 #if 0
00341 cout << kp0.transpose() << endl;
00342 cout << ti.u0 << " " << ti.v0 << " " << ti.u0-ftx/ti.z0 << endl;
00343 cout << kp1.transpose() << endl;
00344 cout << ti.u1 << " " << ti.v1 << " " << ti.u1-ftx/ti.z1 << endl;
00345 cout << pt0.head(3).transpose() << endl;
00346 cout << pt1.head(3).transpose() << endl << endl;
00347 #endif
00348
00349
00350 int pti = sba.tracks.size() - 1;
00351 Vector3d nkp0(ti.u0,ti.v0,ti.u0-ftx/ti.z0);
00352 sba.addStereoProj(ti.fn0,pti,nkp0);
00353 Vector3d nkp1(ti.u1,ti.v1,ti.u1-ftx/ti.z1);
00354 sba.addStereoProj(ti.fn1,pti,nkp1);
00355 }
00356
00357
00358 cout << "Number of tracks: " << sba.tracks.size() << endl;
00359 cout << "Initial RMS cost per projection: " << sqrt(sba.calcCost()/(double)(sba.tracks.size()*2)) << endl;
00360 sba.printStats();
00361
00362
00363 cout << endl << "drawing..." << endl << endl;
00364 drawgraph(sba,cam_pub,pt_pub,2);
00365 char buf[10];
00366 cin.getline(buf,10);
00367
00368 long long t0,t1;
00369
00370 #if 0
00371 t0 = utime();
00372 sba.doSBA(10,1.0e-4,1);
00373 t1 = utime();
00374 cout << endl << "drawing..." << endl << endl;
00375 drawgraph(sba,cam_pub,pt_pub,2);
00376 cin.getline(buf,10);
00377 #endif
00378
00379
00380 cout << "Found " << pairs.size() << " connected tracks" << endl;
00381 #if 0
00382 for (int i=0; i<(int)pairs.size(); i++)
00383 cout << pairs[i].first << " " << pairs[i].second << endl;
00384 #endif
00385 sba.mergeTracks(pairs);
00386 cout << "Number of tracks: " << sba.tracks.size() << endl;
00387 cout << "Initial RMS cost per projection: " << sqrt(sba.calcCost()/(double)(sba.tracks.size()*2)) << endl;
00388 sba.printStats();
00389
00390
00391 #if 1
00392 sba::writeLourakisFile((char *)"intel", sba);
00393 cout << endl << "Wrote SBA system in Lourakis format" << endl << endl;
00394 #endif
00395
00396
00397 #ifdef SAVE_RESULTS
00398 FILE *fd = fopen("results.txt","a");
00399 #endif
00400
00401
00402 int npts = sba.tracks.size();
00403 double tsize = 0;
00404 for (int i=0; i<npts; i++)
00405 tsize += sba.tracks[i].projections.size();
00406 tsize = tsize/(double)npts;
00407
00408
00409 int ncams = sba.nodes.size();
00410 int nprjs = 0;
00411 MatrixXi conns;
00412 conns.setIdentity(ncams,ncams);
00413 for (int i=0; i<(int)sba.tracks.size(); i++)
00414 {
00415 ProjMap &prjs = sba.tracks[i].projections;
00416 nprjs += prjs.size();
00417 if (prjs.size()>1)
00418 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
00419 {
00420 Proj &prj = itr->second;
00421 for(ProjMap::iterator itr2 = itr; itr2 != prjs.end(); itr2++)
00422 {
00423 Proj &prj2 = itr2->second;
00424 conns(prj.ndi,prj2.ndi) = 1;
00425 conns(prj2.ndi,prj.ndi) = 1;
00426 }
00427 }
00428 }
00429
00430 int tot = 0;
00431 for (int i=0; i<ncams; i++)
00432 for (int j=0; j<ncams; j++)
00433 tot += conns(i,j);
00434 double mfill = (double)tot/(double)(ncams*ncams);
00435
00436 printf("\nCams: %d Avg projs: %0.1f Avg. track size: %0.1f Percent fill: %0.1f\n\n",
00437 ncams, (double)nprjs/(double)ncams, tsize, 100.0*mfill);
00438
00439 #ifdef SAVE_RESULTS
00440 fprintf(fd,"%d %0.1f %0.1f %0.1f ",
00441 ncams, (double)nprjs/(double)ncams, tsize, 100.0*mfill);
00442 #endif
00443
00444 sba.nFixed = 1;
00445 sba.csp.useCholmod = true;
00446
00447 t0 = utime();
00448 sba.doSBA(1,1.0e-4,1);
00449 t1 = utime();
00450
00451 #ifdef SAVE_RESULTS
00452 fprintf(fd,"%0.1f %0.1f %0.1f %0.1f\n",
00453 (sba.t2-sba.t1)*0.001,
00454 (sba.t1-sba.t0)*0.001,
00455 (sba.t3-sba.t2)*0.001,
00456 (t1-t0)*0.001);
00457 fflush(fd);
00458 fclose(fd);
00459 #endif
00460
00461
00462 cout << endl << "drawing..." << endl << endl;
00463 drawgraph(sba,cam_pub,pt_pub,2);
00464 cin.getline(buf,10);
00465
00466
00467 char *name = "intel-sys.txt";
00468 FILE *fn = fopen(name,"w");
00469 if (fn == NULL)
00470 {
00471 cout << "[WriteFile] Can't open file " << name << endl;
00472 return -1;
00473 }
00474 fprintf(fn,"Node poses: node #, trans XYZ, rot XYZW\n");
00475 for (int i=0; i<(int)sba.nodes.size(); i++)
00476 {
00477 Node nd = sba.nodes[i];
00478 fprintf(fn,"%d %f %f %f %f %f %f %f\n", i, nd.trans(0), nd.trans(1), nd.trans(2),
00479 nd.qrot.x(), nd.qrot.y(), nd.qrot.z(), nd.qrot.w());
00480 }
00481 cout << "Wrote node poses to file " << name << endl;
00482
00483
00484 return 0;
00485
00486 #if 0
00487 cout << endl;
00488
00489 cout << "Bad projs (> 100 pix): " << sba.countBad(100.0)
00490 << " Cost without: " << sqrt(sba.calcCost(100.0)/nprjs) << endl;
00491 cout << "Bad projs (> 20 pix): " << sba.countBad(20.0)
00492 << " Cost without: " << sqrt(sba.calcCost(20.0)/nprjs) << endl;
00493 cout << "Bad projs (> 10 pix): " << sba.countBad(10.0)
00494 << " Cost without: " << sqrt(sba.calcCost(10.0)/nprjs) << endl;
00495 int n = sba.removeBad(20.0);
00496 cout << "Removed " << n << " projs with >10px error" << endl;
00497 sba.printStats();
00498 #endif
00499
00500 #if 0
00501 sba.doSBA(2);
00502 sba.setupSys(0.0);
00503 sba.writeSparseA((char *)"A819.venice");
00504 #endif
00505
00506
00507
00508
00509
00510 sba.doSBA(1,1e-3,1);
00511 drawgraph(sba,cam_pub,pt_pub,2);
00512 for (int i=0; i<20; i++)
00513 {
00514 sba.doSBA(1,0.0,1);
00515 drawgraph(sba,cam_pub,pt_pub,2);
00516 }
00517
00518 return 0;
00519 }