run_object.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 
00036 //
00037 // runs a sequence of stereo images into an SBA engine for close-up objects
00038 // visualize in rviz
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 #include <opencv2/legacy/legacy.hpp> 
00059 #include <opencv2/nonfree/nonfree.hpp> 
00060 
00061 using namespace std;
00062 using namespace sba;
00063 using namespace frame_common;
00064 using namespace Eigen;
00065 
00066 // visual output of matches
00067 #define VISMATCH
00068 
00069 // elapsed time in milliseconds
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 // Names of left and right files in directory (with wildcards)
00082 char *lreg, *rreg, *dreg;
00083 
00084 // Filters for scandir
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 // draw the graph on rviz
00110 void
00111 drawgraph(const SysSBA &sba, const ros::Publisher &cam_pub, const ros::Publisher &pt_pub, int dec
00112           /*SysSPA &spa, ros::Publisher &cst_pub, ros::Publisher &link_pub*/)
00113 {
00114   visualization_msgs::Marker cammark, ptmark, cstmark;
00115   cammark.header.frame_id = "/pgraph";
00116   cammark.header.stamp = ros::Time();
00117   cammark.ns = "pgraph";
00118   cammark.id = 0;
00119   cammark.action = visualization_msgs::Marker::ADD;
00120   cammark.pose.position.x = 0;
00121   cammark.pose.position.y = 0;
00122   cammark.pose.position.z = 0;
00123   cammark.pose.orientation.x = 0.0;
00124   cammark.pose.orientation.y = 0.0;
00125   cammark.pose.orientation.z = 0.0;
00126   cammark.pose.orientation.w = 1.0;
00127   cammark.scale.x = 0.001;
00128   cammark.scale.y = 0.001;
00129   cammark.scale.z = 0.001;
00130   cammark.color.r = 0.0f;
00131   cammark.color.g = 1.0f;
00132   cammark.color.b = 1.0f;
00133   cammark.color.a = 1.0f;
00134   cammark.lifetime = ros::Duration();
00135   cammark.type = visualization_msgs::Marker::LINE_LIST;
00136 
00137   ptmark = cammark;
00138   ptmark.color.r = 1.0f;
00139   ptmark.color.g = 0.0f;
00140   ptmark.color.b = 0.0f;
00141   ptmark.color.a = 0.5f;
00142   ptmark.scale.x = 0.002;
00143   ptmark.scale.y = 0.002;
00144   ptmark.scale.z = 0.002;
00145   ptmark.type = visualization_msgs::Marker::POINTS;
00146 
00147   cstmark = cammark;
00148   cstmark.color.r = 1.0f;
00149   cstmark.color.g = 1.0f;
00150   cstmark.color.b = 0.0f;
00151   cstmark.color.a = 1.0f;
00152   cstmark.scale.x = 0.03;
00153   cstmark.scale.y = 0.1;
00154   cstmark.scale.z = 0.1;
00155   cstmark.type = visualization_msgs::Marker::LINE_LIST;
00156 
00157 
00158   // draw points, decimated
00159   int npts = sba.tracks.size();
00160 
00161   cout << "Number of points to draw: " << npts << endl;
00162   if (npts <= 0) return;
00163 
00164 
00165   ptmark.points.resize(npts/dec+1);
00166   for (int i=0, ii=0; i<npts; i+=dec, ii++)
00167     {
00168       const Vector4d &pt = sba.tracks[i].point;
00169       ptmark.points[ii].x = pt(0);
00170       ptmark.points[ii].y = pt(2);
00171       ptmark.points[ii].z = -pt(1);
00172     }
00173 
00174   // draw cameras
00175   int ncams = sba.nodes.size();
00176   cammark.points.resize(ncams*6);
00177   for (int i=0, ii=0; i<ncams; i++)
00178     {
00179       const Node &nd = sba.nodes[i];
00180       Vector3d opt;
00181       Matrix<double,3,4> tr;
00182       transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00183 
00184       cammark.points[ii].x = nd.trans.x();
00185       cammark.points[ii].y = nd.trans.z();
00186       cammark.points[ii++].z = -nd.trans.y();
00187       opt = tr*Vector4d(0,0,0.1,1);
00188       cammark.points[ii].x = opt.x();
00189       cammark.points[ii].y = opt.z();
00190       cammark.points[ii++].z = -opt.y();
00191 
00192       cammark.points[ii].x = nd.trans.x();
00193       cammark.points[ii].y = nd.trans.z();
00194       cammark.points[ii++].z = -nd.trans.y();
00195       opt = tr*Vector4d(0.05,0,0,1);
00196       cammark.points[ii].x = opt.x();
00197       cammark.points[ii].y = opt.z();
00198       cammark.points[ii++].z = -opt.y();
00199 
00200       cammark.points[ii].x = nd.trans.x();
00201       cammark.points[ii].y = nd.trans.z();
00202       cammark.points[ii++].z = -nd.trans.y();
00203       opt = tr*Vector4d(0,0.05,0,1);
00204       cammark.points[ii].x = opt.x();
00205       cammark.points[ii].y = opt.z();
00206       cammark.points[ii++].z = -opt.y();
00207     }
00208 
00209 #if 0
00210   // draw SPA constraints
00211   int ncons = spa.p2cons.size();
00212   cstmark.points.resize(ncons*6);
00213 
00214   for (int i=0, ii=0; i<ncons; i++)
00215     {
00216       ConP2 &con = spa.p2cons[i];
00217       Node &nd0 = spa.nodes[con.ndr];
00218       Node &nd1 = spa.nodes[con.nd1];
00219 
00220       Node &nd = spa.nodes[i];
00221       Vector3d opt;
00222       Matrix<double,3,4> tr;
00223       transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00224 
00225       cstmark.points[ii].x = nd.trans.x();
00226       cstmark.points[ii].y = nd.trans.z();
00227       cstmark.points[ii++].z = -nd.trans.y();
00228       opt = tr*Vector4d(0,0,0.3,1);
00229       cstmark.points[ii].x = opt.x();
00230       cstmark.points[ii].y = opt.z();
00231       cstmark.points[ii++].z = -opt.y();
00232 
00233       cstmark.points[ii].x = nd.trans.x();
00234       cstmark.points[ii].y = nd.trans.z();
00235       cstmark.points[ii++].z = -nd.trans.y();
00236       opt = tr*Vector4d(0.2,0,0,1);
00237       cstmark.points[ii].x = opt.x();
00238       cstmark.points[ii].y = opt.z();
00239       cstmark.points[ii++].z = -opt.y();
00240 
00241       cstmark.points[ii].x = nd.trans.x();
00242       cstmark.points[ii].y = nd.trans.z();
00243       cstmark.points[ii++].z = -nd.trans.y();
00244       opt = tr*Vector4d(0,0.1,0,1);
00245       cstmark.points[ii].x = opt.x();
00246       cstmark.points[ii].y = opt.z();
00247       cstmark.points[ii++].z = -opt.y();
00248 
00249 #if 0
00250       cstmark.points[ii].x = nd0.trans.x();
00251       cstmark.points[ii].y= nd0.trans.z();
00252       cstmark.points[ii++].z = -nd0.trans.y();
00253       cstmark.points[ii].x = nd1.trans.x();
00254       cstmark.points[ii].y = nd1.trans.z();
00255       cstmark.points[ii++].z = -nd1.trans.y();
00256 #endif
00257     }
00258 #endif // SPA
00259 
00260   cam_pub.publish(cammark);
00261   pt_pub.publish(ptmark);
00262   //cst_pub.publish(cstmark);
00263 }
00264 
00265 
00266 
00267 // main loop
00268 
00269 int main(int argc, char** argv)
00270 {
00271   if (argc < 5)
00272     {
00273       printf("Args are: <param file> <image dir> <left image file template> <right image file template> "
00274              "<vocab tree file> <vocab weights file> <calonder trees file>\n");
00275       exit(0);
00276     }
00277 
00278   // get camera parameters, in the form: fx fy cx cy tx
00279   fstream fstr;
00280   fstr.open(argv[1],fstream::in);
00281   if (!fstr.is_open())
00282     {
00283       printf("Can't open camera file %s\n",argv[1]);
00284       exit(0);
00285     }
00286   CamParams camp;
00287   fstr >> camp.fx;
00288   fstr >> camp.fy;
00289   fstr >> camp.cx;
00290   fstr >> camp.cy;
00291   fstr >> camp.tx;
00292 
00293   cout << "Cam params: " << camp.fx << " " << camp.fy << " " << camp.cx
00294        << " " << camp.cy << " " << camp.tx << endl;
00295 
00296 
00297   // set up directories
00298   struct dirent **lims, **rims, **dirs;
00299   int nlim, nrim, ndirs;
00300   string dname = argv[2];
00301   if (!dname.compare(dname.size()-1,1,"/")) // see if slash at end
00302     dname.erase(dname.size()-1);
00303 
00304   string dirfn = dname.substr(dname.rfind("/")+1);
00305   string tdir = dname.substr(0,dname.rfind("/")+1);
00306   cout << "Top directory is " << tdir << endl;
00307   cout << "Search directory name is " << dirfn << endl;
00308   dreg = (char *)dirfn.c_str();
00309 
00310   ndirs = scandir(tdir.c_str(),&dirs,getidir,alphasort);
00311   printf("Found %d directories\n", ndirs);
00312   printf("%s\n",dirs[0]->d_name);
00313 
00314   // set up vslam structures
00315   vslam::VslamSystem vslam(argv[5], argv[6]);
00316   typedef cv::CalonderDescriptorExtractor<float> Calonder;
00317   vslam.frame_processor_.setFrameDescriptor(new Calonder(argv[7]));
00318   vslam.setNDisp(192);
00319   vslam.setPlaceInliers(80);
00320   vslam.setKeyInliers(80);
00321   vslam.setKeyDist(.01);
00322   vslam.setKeyAngle(.005);
00323 
00324 
00325 #if 0
00326   SysSPA spa;                   // SPA system
00327   int spaFrameId = -1;          // current frame of SPA system
00328   int ndi0 = 0;                 // current node of SPA system
00329 #endif
00330   
00331   // set up markers for visualization
00332   ros::init(argc, argv, "VisBundler");
00333   ros::NodeHandle nh ("~");
00334   ros::Publisher pt_pub = nh.advertise<visualization_msgs::Marker>("points", 0);
00335   ros::Publisher cam_pub = nh.advertise<visualization_msgs::Marker>("cameras", 0);
00336   ros::Publisher cst_pub = nh.advertise<visualization_msgs::Marker>("constraints", 0);
00337   ros::Publisher link_pub = nh.advertise<visualization_msgs::Marker>("links", 0);
00338 
00339   // for RANSAC
00340   srand(mstime());
00341 
00342   // window
00343 #ifdef VISMATCH  
00344   const std::string window_name = "VO tracks";
00345   cv::namedWindow(window_name,0);
00346   cv::Mat display;
00347 #endif
00348 
00349   int iter = 0;
00350   lreg = argv[3];
00351   rreg = argv[4];
00352 
00353 
00354   // loop over directories
00355   for (int dd=0; dd<ndirs; dd++)
00356     {
00357       char dir[2048];
00358       sprintf(dir,"%s%s",tdir.c_str(),dirs[dd]->d_name);
00359       printf("Current directory: %s\n", dir);
00360 
00361       // get left/right image file names, sorted
00362       nlim = scandir(dir,&lims,getleft,alphasort);
00363       printf("Found %d left images\n", nlim);
00364       printf("%s\n",lims[0]->d_name);
00365 
00366       nrim = scandir(dir,&rims,getright,alphasort);
00367       printf("Found %d right images\n", nrim);
00368       printf("%s\n",rims[0]->d_name);
00369 
00370       if (nlim != nrim)
00371         {
00372           printf("Number of left/right images does not match: %d vs. %d\n", nlim, nrim);
00373           exit(0);
00374         }
00375 
00376 
00377 
00378       // loop over each stereo pair, adding it to the system
00379       for (int ii=0; ii<nlim; iter++, ii++)
00380         {
00381           // Load images
00382           char fn[2048];
00383           sprintf(fn,"%s/%s",dir,lims[ii]->d_name);
00384           cv::Mat image1 = cv::imread(fn,0);
00385           sprintf(fn,"%s/%s",dir,rims[ii]->d_name);
00386           cv::Mat image1r = cv::imread(fn,0);
00387 
00388 #if 0
00389           printf("Image size: %d x %d\n", image1.cols, image1.rows);
00390           printf("Image size: %d x %d\n", image1r.cols, image1r.rows);
00391 #endif
00392 
00393           if (image1.rows == 0 || image1r.rows == 0)
00394             exit(0);
00395 
00396           // Add stereo pair to the system
00397           bool is_keyframe = vslam.addFrame(camp, image1, image1r);
00398 
00399 
00400           if (is_keyframe)
00401             {
00403               int n = vslam.sba_.nodes.size();
00404               int np = vslam.sba_.tracks.size();
00405 
00406               // draw graph
00407               //              cout << "drawing with " << n << " nodes and " << np << " points..." << endl << endl;
00408 #if 1
00409               if (n%2 == 0)
00410                 drawgraph(vslam.sba_, cam_pub, pt_pub, 1/*, spa, cst_pub, link_pub*/); // every nth point
00411 #endif
00412 
00413               // write file out
00414               if (0 && n > 10 && n%500 == 0)
00415                 {
00416                   char fn[1024];
00417                   sprintf(fn,"newcollege%d", n);
00418                   sba::writeLourakisFile(fn, vslam.sba_);
00419                   vslam.sba_.doSBA(1,1.0e-4,0);
00420                   sba::writeSparseA(fn, vslam.sba_);
00421                 }
00422 
00423 #if 1
00424               int nnsba = 10;
00425               if (n > 4 && n%nnsba == 0)
00426                 {
00427                   cout << "Running large SBA" << endl;
00428                   vslam.refine();
00429                 }
00430 #endif
00431             }
00432 
00433 #ifdef VISMATCH
00434           // Visualize
00435           if (1)
00436             {
00437               drawVOtracks(image1, vslam.vo_.frames, display);
00438               cv::imshow(window_name, display);
00439               cv::waitKey(10);
00440             }
00441 #endif
00442 
00443           if (!nh.ok())
00444             return 0;
00445         }
00446     }
00447   return 0;
00448 }


vslam_system
Author(s): Kurt Konolige, Patrick Mihelich, Helen Oleynikova
autogenerated on Thu Jan 2 2014 12:12:31