WhiteBlackGrid.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *  Software License Agreement (BSD License)
00003 *  Copyright (c) 2013, Intelligent Robotics Lab, DLUT.
00004 *  All rights reserved.
00005 *  Author:Intelligent Robotics Lab, DLUT.
00006 *  Redistribution and use in source and binary forms, with or without
00007 *  modification, are permitted provided that the following conditions
00008 *  are met:
00009 *
00010 *   * Redistributions of source code must retain the above copyright
00011 *     notice, this list of conditions and the following disclaimer.
00012 *   * Redistributions in binary form must reproduce the above
00013 *     copyright notice, this list of conditions and the following
00014 *     disclaimer in the documentation and/or other materials provided
00015 *     with the distribution.
00016 *   * Neither the name of the Intelligent Robotics Lab nor the names of its
00017 *     contributors may be used to endorse or promote products derived
00018 *     from this software without specific prior written permission.
00019 *
00020 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 *  POSSIBILITY OF SUCH DAMAGE.
00032 *********************************************************************/
00033 #include "WhiteBlackGrid.h"
00034 
00035 CWhiteBlackGrid::CWhiteBlackGrid (void)
00036 {
00037   scene_cnt_ = 0;
00038   m_scan_mode_ = 1;
00039 
00040 }
00041 
00042 CWhiteBlackGrid::~CWhiteBlackGrid (void)
00043 {
00044 }
00045 
00046 void CWhiteBlackGrid::whgRegisterScanMode (bool scan_mode)
00047 {
00048   m_scan_mode_ = scan_mode;
00049 }
00050 
00051 void CWhiteBlackGrid::whgNodeDetect (int _m, int _n, float *_parameters,
00052                                      std::vector < std::vector < CPoint3d > >&laser_data_vec)
00053 {
00054   size_t k_num;
00055   k_num = (size_t) _m *_n;
00056 
00057   //3D points binaryzation .
00058   size_t m, n;
00059   m = _m;
00060   n = _n;
00061   float A = _parameters[0];
00062   float B = _parameters[1];
00063   float C = _parameters[2];
00064   float D = _parameters[3];
00065   bin_vec_.resize (m);
00066   for (size_t p = 0; p < m; p++)
00067   {
00068     bin_vec_[p].resize (n);
00069     for (size_t q = 0; q < n; q++)
00070     {
00071       double d =
00072         abs (laser_data_vec[p][q].x * A + laser_data_vec[p][q].y * B + laser_data_vec[p][q].z * C + D) / sqrt (A * A +
00073                                                                                                                B * B +
00074                                                                                                                C * C);
00075       if (d > 0.15)
00076       {
00077         bin_vec_[p][q] = 0;
00078       }
00079       else
00080         bin_vec_[p][q] = 255;
00081     }
00082   }
00083 
00084   int iChoosed = 0;
00085   bool isFound = false;
00086 
00087   for (size_t i = 0; i < n; i++)
00088   {
00089     for (size_t j = 0; j < m; j++)
00090     {
00091       if (bin_vec_[j][i] == 255)
00092       {
00093         isFound = true;
00094         continue;
00095       }
00096       else
00097       {
00098         isFound = false;
00099         break;
00100       }
00101     }
00102     if (isFound)
00103     {
00104       iChoosed = i;
00105       break;
00106     }
00107   }
00108 
00109   std::vector < int >Bin_ (n - iChoosed);
00110   std::vector < std::vector < int > >BinNew (m);
00111   std::vector < CPoint3d > LaserOne (n - iChoosed);
00112   std::vector < std::vector < CPoint3d > >LaserData_ (m);
00113 
00114   for (size_t j = 0; j < m; j++)
00115   {
00116     for (size_t i = iChoosed, i_ = 0; i < n; i++, i_++)
00117     {
00118       Bin_[i_] = bin_vec_[j][i];
00119       LaserOne[i_] = laser_data_vec[j][i];
00120     }
00121     BinNew[j] = Bin_;
00122     LaserData_[j] = LaserOne;
00123   }
00124   bin_vec_.swap (BinNew);
00125   laser_data_vec.swap (LaserData_);
00126   n = n - iChoosed;
00127   /*ofstream ww("bin_vec_.txt");
00128      if (!ww.is_open())
00129      {
00130      printf("open the file bin_vec_.txt fail\n");
00131      return ;
00132      }
00133      else
00134      printf("open the file bin_vec_.txt ok\n");
00135      for (int i = 0; i < m; i++)
00136      {
00137      for (int j = 0; j < n;j++)
00138      {
00139      ww<<bin_vec_[i][j]<<"  ";
00140      }
00141      ww<<"\n";
00142      }
00143      ww.close(); */
00144 
00145   //Binary matrix processing 
00146   std::vector < BinIndex > centerij;
00147   BinIndex tmpindex;
00148   size_t rem;
00149 
00150   size_t DELTR;
00151   size_t DELTL;
00152 
00153   if (m_scan_mode_)             //pitching scan
00154   {
00155     rem = m % 4;
00156     if (rem != 0)
00157     {
00158       m = m - rem;
00159     }
00160 
00161     rem = n % 5;
00162     if (rem != 0)
00163     {
00164       n = n - rem;
00165     }
00166     DELTR = m / 4;
00167     DELTL = n / 5;
00168   }
00169   else                          //horizontal scan
00170   {
00171     rem = m % 5;
00172     if (rem != 0)
00173     {
00174       m = m - rem;
00175     }
00176 
00177     rem = n % 4;
00178     if (rem != 0)
00179     {
00180       n = n - rem;
00181     }
00182     DELTR = m / 5;
00183     DELTL = n / 4;
00184   }
00185 
00186   std::vector < size_t > rownum;        //save the number of '0' for each row 
00187   rownum.resize (m);
00188   std::vector < size_t > linenum;       //save the number of '0' for each column
00189   linenum.resize (n);
00190   std::vector < size_t > maxindex;
00191   //solution 1
00192   for (size_t p = 0; p < m; p += DELTR)
00193   {
00194     for (size_t q = 0; q < n; q += DELTL)
00195     {
00196       for (size_t j = 0; j < m; j++)
00197       {
00198         rownum[j] = 0;
00199       }
00200       for (size_t i = 0; i < n; i++)
00201       {
00202         linenum[i] = 0;
00203       }
00204 
00205       //get the number of '0' for each row
00206       for (size_t j = p; j < p + DELTR; j++)
00207       {
00208         for (size_t i = q; i < q + DELTL; i++)
00209         {
00210           if ((bin_vec_[j][i] == 0))
00211           {
00212             rownum[j] += 1;
00213           }
00214         }
00215       }
00216       //get the maximum of row number
00217       size_t maxj = p, maxvaluej = 0;
00218       for (size_t j = p; j < p + DELTR; j++)
00219       {
00220         if (rownum[j] >= maxvaluej)
00221         {
00222           maxvaluej = rownum[j];
00223           maxj = j;
00224         }
00225       }
00226       //if there are many maximum of row number
00227       std::vector < size_t > vec_ (0);
00228       maxindex.swap (vec_);
00229       for (size_t j = p; j < p + DELTR; j++)
00230       {
00231         if (rownum[j] == maxvaluej)
00232           maxindex.push_back (j);
00233       }
00234       size_t size_maxj = (size_t) maxindex.size ();
00235       size_t summaxj = 0;
00236       for (size_t k = 0; k < size_maxj; k++)
00237       {
00238         summaxj += maxindex[k];
00239       }
00240       float quo;
00241       size_t avemaxj;
00242       quo = summaxj / size_maxj;
00243       if ((quo - (size_t) quo) < 0.5)
00244         avemaxj = (size_t) quo;
00245       else
00246         avemaxj = (size_t) quo + 1;
00247       //get the number of '0' for each column
00248       for (size_t i = q; i < q + DELTL; i++)
00249       {
00250         for (size_t j = p; j < p + DELTR; j++)
00251         {
00252           if ((bin_vec_[j][i] == 0))
00253           {
00254             linenum[i] += 1;
00255           }
00256         }
00257       }
00258 
00259       //get the maximum of row number
00260       size_t maxi = q, maxvaluei = 0;
00261       for (size_t i = q; i < q + DELTL; i++)
00262       {
00263         if (linenum[i] >= maxvaluei)
00264         {
00265           maxvaluei = linenum[i];
00266           maxi = i;
00267         }
00268       }
00269 
00270       //if there are many maximum of row number
00271       maxindex.clear ();
00272       for (size_t i = q; i < q + DELTL; i++)
00273       {
00274         if (linenum[i] == maxvaluei)
00275           maxindex.push_back (i);
00276       }
00277       size_t size_maxi = (size_t) maxindex.size ();
00278       size_t summaxi = 0;
00279       for (size_t k = 0; k < size_maxi; k++)
00280       {
00281         summaxi += maxindex[k];
00282       }
00283       size_t avemaxi;
00284       quo = summaxi / size_maxi;
00285       if ((quo - (size_t) quo) < 0.5)
00286         avemaxi = (size_t) quo;
00287       else
00288         avemaxi = (size_t) quo + 1;
00289 
00290 
00291 
00292       tmpindex.bin_j = avemaxj;
00293       tmpindex.bin_i = avemaxi;
00294       centerij.push_back (tmpindex);
00295     }
00296   }
00297   /*ofstream m_w("centerij.txt");
00298      if (m_w.is_open())
00299      {
00300      printf("open the file ok\n");
00301      }
00302      else
00303      {
00304      printf("open the file fail\n");
00305      return ;
00306      }
00307      for (int i = 0; i < (int)centerij.size(); i++)
00308      {
00309      m_w<<centerij[i].bin_j<<"  "<<centerij[i].bin_i<<"\n";
00310      //m_w<<laser_data_vec[centerij[i].bin_j][centerij[i].bin_i].x<<"  "<<laser_data_vec[centerij[i].bin_j][centerij[i].bin_i].y<<"  "<<laser_data_vec[centerij[i].bin_j][centerij[i].bin_i].z<<"\n";
00311      }
00312      m_w.close(); */
00313   std::vector < CPoint3d > Node_ (0);
00314   node_vec_.swap (Node_);
00315   if (m_scan_mode_)             //pitching scan
00316   {
00317     for (int k = 0; k < 3; k++)
00318     {
00319       for (int i = 5 * k; i < 5 * k + 4; i++)
00320       {
00321         BinIndex avenode = whgAverageof4index (centerij[i], centerij[i + 1], centerij[i + 5], centerij[i + 6]);
00322         CPoint3d ptmp;
00323         ptmp.x = laser_data_vec[avenode.bin_j][avenode.bin_i].x;
00324         ptmp.y = laser_data_vec[avenode.bin_j][avenode.bin_i].y;
00325         ptmp.z = laser_data_vec[avenode.bin_j][avenode.bin_i].z;
00326         node_vec_.push_back (ptmp);
00327       }
00328     }
00329   }
00330   else                          //horizontal scan
00331   {
00332     for (int k = 0; k < 4; k++)
00333     {
00334       for (int i = 4 * k; i < 4 * k + 3; i++)
00335       {
00336         BinIndex avenode = whgAverageof4index (centerij[i], centerij[i + 1], centerij[i + 4], centerij[i + 5]);
00337         CPoint3d ptmp;
00338         ptmp.x = laser_data_vec[avenode.bin_j][avenode.bin_i].x;
00339         ptmp.y = laser_data_vec[avenode.bin_j][avenode.bin_i].y;
00340         ptmp.z = laser_data_vec[avenode.bin_j][avenode.bin_i].z;
00341         node_vec_.push_back (ptmp);
00342       }
00343     }
00344 
00345   }
00346 }
00347 
00348 // Calculate the average of 4 indexs
00349 BinIndex CWhiteBlackGrid::whgAverageof4index (BinIndex bi1, BinIndex bi2, BinIndex bi3, BinIndex bi4)
00350 {
00351   int av_j, av_i, sum_i = 0, sum_j = 0;
00352   sum_j = bi1.bin_j + bi2.bin_j + bi3.bin_j + bi4.bin_j;
00353   sum_i = bi1.bin_i + bi2.bin_i + bi3.bin_i + bi4.bin_i;
00354   float quoj, quoi;
00355   quoj = sum_j / 4;
00356   if ((quoj - (int) quoj) < 0.5)
00357   {
00358     av_j = (int) quoj;
00359   }
00360   else
00361   {
00362     av_j = (int) quoj + 1;
00363   }
00364 
00365   quoi = sum_i / 4;
00366   if ((quoi - (int) quoi) < 0.5)
00367   {
00368     av_i = (int) quoi;
00369   }
00370   else
00371   {
00372     av_i = (int) quoi + 1;
00373   }
00374   BinIndex tmp;
00375   tmp.bin_j = av_j;
00376   tmp.bin_i = av_i;
00377   return (tmp);
00378 }
00379 
00380 void CWhiteBlackGrid::whgNodeModify (void)      //Revise the corners we detect.
00381 {
00382   int nump = (int) node_vec_.size ();
00383   match_pair_vec_.resize (nump);
00384   for (int i = 0; i < nump; i++)
00385   {
00386     match_pair_vec_[i].x = node_vec_[i].x;
00387     match_pair_vec_[i].y = node_vec_[i].y;
00388     match_pair_vec_[i].z = node_vec_[i].z;
00389   }
00390 
00391   standard_vec_.resize (12);
00392   if (m_scan_mode_)             //pitching scan
00393   {
00394     standard_vec_[0] = CPoint3d (0.75, 0.00, 0);
00395     standard_vec_[1] = CPoint3d (0.50, 0.00, 0);
00396     standard_vec_[2] = CPoint3d (0.25, 0.00, 0);
00397     standard_vec_[3] = CPoint3d (0, 0.00, 0);
00398 
00399     standard_vec_[4] = CPoint3d (0.75, 0.25, 0);
00400     standard_vec_[5] = CPoint3d (0.50, 0.25, 0);
00401     standard_vec_[6] = CPoint3d (0.25, 0.25, 0);
00402     standard_vec_[7] = CPoint3d (0, 0.25, 0);
00403 
00404     standard_vec_[8] = CPoint3d (0.75, 0.50, 0);
00405     standard_vec_[9] = CPoint3d (0.50, 0.50, 0);
00406     standard_vec_[10] = CPoint3d (0.25, 0.50, 0);
00407     standard_vec_[11] = CPoint3d (0, 0.50, 0);
00408   }
00409   else                          //horizontal scan
00410   {
00411     standard_vec_[0] = CPoint3d (0, 0, 0);
00412     standard_vec_[1] = CPoint3d (0, 0.25, 0);
00413     standard_vec_[2] = CPoint3d (0, 0.50, 0);
00414 
00415     standard_vec_[3] = CPoint3d (0.25, 0, 0);
00416     standard_vec_[4] = CPoint3d (0.25, 0.25, 0);
00417     standard_vec_[5] = CPoint3d (0.25, 0.50, 0);
00418 
00419     standard_vec_[6] = CPoint3d (0.50, 0, 0);
00420     standard_vec_[7] = CPoint3d (0.50, 0.25, 0);
00421     standard_vec_[8] = CPoint3d (0.50, 0.50, 0);
00422 
00423     standard_vec_[9] = CPoint3d (0.75, 0, 0);
00424     standard_vec_[10] = CPoint3d (0.75, 0.25, 0);
00425     standard_vec_[11] = CPoint3d (0.75, 0.50, 0);
00426   }
00427   whgCalculateTransformationRT ();      //calculate R £¬t
00428 }
00429 
00430 void CWhiteBlackGrid::whgCalculateTransformationRT (void)       //calculate the R ,t
00431 {
00432   int n = (int) match_pair_vec_.size ();
00433   VectorXd avr_m (3), avr_d (3);        // Centroid vector 3*1
00434   MatrixXd matrix_M (n, 3), matrix_D (n, 3);    // raw matrix n*3
00435   MatrixXd matrix_MM (n, 3), matrix_DD (n, 3);  // 
00436   MatrixXd matrix_S (3, 3);     // parameter matrix of covariance matrices 3*3
00437   MatrixXd matrix_N (4, 4);     // Covariance matrices 4*4
00438   //VectorXd lambda;                                              // eigenvalue
00439   MatrixXd Q;                   // eigenvector
00440   VectorXd vector_q (4);        // quaternion q
00441   VectorXd vector_c;
00442 
00443   MatrixXd matrix_MyR (3, 3);   // Rotation matrix R
00444   VectorXd vector_Myt (3);      // Translation vector t
00445 
00446   for (int i = 0; i < n; i++)
00447   {
00448     matrix_M (i, 0) = match_pair_vec_[i].x;
00449     matrix_M (i, 1) = match_pair_vec_[i].y;
00450     matrix_M (i, 2) = match_pair_vec_[i].z;
00451 
00452     matrix_D (i, 0) = standard_vec_[i].x;
00453     matrix_D (i, 1) = standard_vec_[i].y;
00454     matrix_D (i, 2) = standard_vec_[i].z;
00455   }
00456 
00457   avr_m[0] = 0.0;
00458   avr_m[1] = 0.0;
00459   avr_m[2] = 0.0;
00460 
00461   avr_d[0] = 0.0;
00462   avr_d[1] = 0.0;
00463   avr_d[2] = 0.0;
00464 
00465   for (int i = 0; i < n; i++)
00466   {
00467     avr_m[0] += match_pair_vec_[i].x;
00468     avr_m[1] += match_pair_vec_[i].y;
00469     avr_m[2] += match_pair_vec_[i].z;
00470 
00471     avr_d[0] += standard_vec_[i].x;
00472     avr_d[1] += standard_vec_[i].y;
00473     avr_d[2] += standard_vec_[i].z;
00474   }
00475   avr_m[0] /= n;
00476   avr_m[1] /= n;
00477   avr_m[2] /= n;
00478 
00479   avr_d[0] /= n;
00480   avr_d[1] /= n;
00481   avr_d[2] /= n;
00482 
00483   for (int i = 0; i < n; i++)
00484   {
00485     matrix_MM (i, 0) = matrix_M (i, 0) - avr_m[0];
00486     matrix_MM (i, 1) = matrix_M (i, 1) - avr_m[1];
00487     matrix_MM (i, 2) = matrix_M (i, 2) - avr_m[2];
00488 
00489     matrix_DD (i, 0) = matrix_D (i, 0) - avr_d[0];
00490     matrix_DD (i, 1) = matrix_D (i, 1) - avr_d[1];
00491     matrix_DD (i, 2) = matrix_D (i, 2) - avr_d[2];
00492   }
00493 
00494   for (int i = 0; i < 3; i++)
00495   {
00496     for (int j = 0; j < 3; j++)
00497     {
00498       matrix_S (i, j) = 0.0;
00499     }
00500   }
00501 
00502   for (int i = 0; i < 3; i++)
00503   {
00504     for (int j = 0; j < 3; j++)
00505     {
00506       for (int k = 0; k < n; k++)
00507       {
00508         matrix_S (i, j) += matrix_MM (k, i) * matrix_DD (k, j);
00509       }
00510     }
00511   }
00512   // calculate the matrix_N
00513   matrix_N (0, 0) = matrix_S (0, 0) + matrix_S (1, 1) + matrix_S (2, 2);
00514 
00515   matrix_N (0, 1) = matrix_N (1, 0) = matrix_S (1, 2) - matrix_S (2, 1);
00516   matrix_N (0, 2) = matrix_N (2, 0) = matrix_S (2, 0) - matrix_S (0, 2);
00517   matrix_N (0, 3) = matrix_N (3, 0) = matrix_S (0, 1) - matrix_S (1, 0);
00518 
00519   matrix_N (1, 1) = matrix_S (0, 0) - matrix_S (1, 1) - matrix_S (2, 2);
00520 
00521   matrix_N (1, 2) = matrix_N (2, 1) = matrix_S (0, 1) + matrix_S (1, 0);
00522   matrix_N (1, 3) = matrix_N (3, 1) = matrix_S (2, 0) + matrix_S (0, 2);
00523   matrix_N (3, 2) = matrix_N (2, 3) = matrix_S (1, 2) + matrix_S (2, 1);
00524 
00525   matrix_N (2, 2) = -matrix_S (0, 0) + matrix_S (1, 1) - matrix_S (2, 2);
00526   matrix_N (3, 3) = -matrix_S (0, 0) - matrix_S (1, 1) + matrix_S (2, 2);
00527 
00528 
00529   // calculate the eigenvalue and eigenvector of matrix_N
00530   EigenSolver < MatrixXd > es (matrix_N);
00531   // find the eigenvector of maximum eigenvalue
00532   double lambda[4] = { 0 };
00533   for (int i = 0; i < 4; ++i)
00534   {
00535     lambda[i] = real (es.eigenvalues ()[i]);
00536   }
00537   double max1_ = max (lambda[0], lambda[1]);
00538   double max2_ = max (lambda[2], lambda[3]);
00539   double max_ = max (max1_, max2_);
00540   int j = 0;
00541   for (; j < 4; j++)
00542   {
00543     if (lambda[j] == max_)
00544     {
00545       break;
00546     }
00547   }
00548   for (int i = 0; i < 4; i++)
00549   {
00550     vector_q[i] = real (es.eigenvectors ().col (j)[i]); //get the eigenvector
00551   }
00552 
00553   // calculate the matrix_MyR
00554   matrix_MyR (0, 0) = pow (vector_q[0], 2) + pow (vector_q[1], 2) - pow (vector_q[2], 2) - pow (vector_q[3], 2);
00555   matrix_MyR (0, 1) = 2 * (vector_q[1] * vector_q[2] - vector_q[3] * vector_q[0]);      //
00556   matrix_MyR (0, 2) = 2 * (vector_q[1] * vector_q[3] + vector_q[2] * vector_q[0]);
00557 
00558   matrix_MyR (1, 0) = 2 * (vector_q[1] * vector_q[2] + vector_q[3] * vector_q[0]);
00559   matrix_MyR (1, 1) = pow (vector_q[0], 2) - pow (vector_q[1], 2) + pow (vector_q[2], 2) - pow (vector_q[3], 2);
00560   matrix_MyR (1, 2) = 2 * (vector_q[2] * vector_q[3] - vector_q[1] * vector_q[0]);
00561 
00562   matrix_MyR (2, 0) = 2 * (vector_q[3] * vector_q[1] - vector_q[2] * vector_q[0]);
00563   matrix_MyR (2, 1) = 2 * (vector_q[3] * vector_q[2] + vector_q[1] * vector_q[0]);
00564   matrix_MyR (2, 2) = pow (vector_q[0], 2) - pow (vector_q[1], 2) - pow (vector_q[2], 2) + pow (vector_q[3], 2);
00565 
00566   MatrixXd matrix_MyRR;
00567   matrix_MyRR = matrix_MyR.inverse ();
00568 
00569   // calculate the vector_Myt
00570   vector_c = matrix_MyRR * avr_d;
00571   vector_Myt = avr_m - vector_c;
00572 
00573   whgTransform (matrix_MyRR, vector_Myt, standard_vec_);
00574 
00575   //save these corners
00576   ofstream outf;
00577   char filename[100] = "laserpts.txt";
00578   //sprintf(filename,"laserpts.txt",scene_cnt_);
00579   outf.open (filename);
00580   if (outf.fail ())
00581   {
00582     cout << "can not open file";
00583     return;
00584   }
00585 
00586   for (size_t i = 0; i < standard_vec_.size (); i++)
00587   {
00588     outf.setf (ios::right);
00589     outf.width (8);
00590     outf << standard_vec_[i].x << " " << standard_vec_[i].y << " " << standard_vec_[i].z << endl;
00591   }
00592   scene_cnt_++;
00593 
00594   outf.close ();
00595 
00596 
00597 
00598 }
00599 
00600 void CWhiteBlackGrid::whgTransform (MatrixXd matrix_R, VectorXd vector_t, std::vector < CPoint3d > &laser_point_vec)
00601 {
00602   VectorXd vector_c;
00603   VectorXd vector_d (3);
00604   int n = (int) laser_point_vec.size ();
00605   for (int i = 0; i < n; i++)
00606   {
00607     vector_d[0] = laser_point_vec[i].x;
00608     vector_d[1] = laser_point_vec[i].y;
00609     vector_d[2] = laser_point_vec[i].z;
00610 
00611     // d=R*d+t
00612     vector_c = matrix_R * vector_d;
00613     vector_d = vector_c + vector_t;
00614 
00615     laser_point_vec[i].x = vector_d[0];
00616     laser_point_vec[i].y = vector_d[1];
00617     laser_point_vec[i].z = vector_d[2];
00618   }
00619 }


camera_laser_calibration
Author(s): Zhao Cilang,Yan Fei,Zhuang Yan/zhuang@dlut.edu.cn
autogenerated on Sun Jan 5 2014 11:05:02