sparse_mat.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012-, Open Perception, 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 copyright holder(s) 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 
00038 #include <pcl/surface/on_nurbs/sparse_mat.h>
00039 
00040 using namespace pcl;
00041 using namespace on_nurbs;
00042 
00043 void
00044 SparseMat::get (std::vector<int> &i, std::vector<int> &j, std::vector<double> &v)
00045 {
00046   std::map<int, std::map<int, double> >::iterator it_row;
00047   std::map<int, double>::iterator it_col;
00048 
00049   i.clear ();
00050   j.clear ();
00051   v.clear ();
00052 
00053   it_row = m_mat.begin ();
00054   while (it_row != m_mat.end ())
00055   {
00056     it_col = it_row->second.begin ();
00057     while (it_col != it_row->second.end ())
00058     {
00059       i.push_back (it_row->first);
00060       j.push_back (it_col->first);
00061       v.push_back (it_col->second);
00062       it_col++;
00063     }
00064     it_row++;
00065   }
00066 
00067 }
00068 
00069 double
00070 SparseMat::get (int i, int j)
00071 {
00072   std::map<int, std::map<int, double> >::iterator it_row;
00073   std::map<int, double>::iterator it_col;
00074 
00075   it_row = m_mat.find (i);
00076   if (it_row == m_mat.end ())
00077     return 0.0;
00078 
00079   it_col = it_row->second.find (j);
00080   if (it_col == it_row->second.end ())
00081     return 0.0;
00082 
00083   return it_col->second;
00084 
00085 }
00086 
00087 void
00088 SparseMat::set (int i, int j, double v)
00089 {
00090 
00091   if (i < 0 || j < 0)
00092   {
00093     printf ("[SparseMat::set] Warning index out of bounds (%d,%d)\n", i, j);
00094     return;
00095   }
00096 
00097   if (v == 0.0)
00098   {
00099     // delete entry
00100 
00101     std::map<int, std::map<int, double> >::iterator it_row;
00102     std::map<int, double>::iterator it_col;
00103 
00104     it_row = m_mat.find (i);
00105     if (it_row == m_mat.end ())
00106       return;
00107 
00108     it_col = it_row->second.find (j);
00109     if (it_col == it_row->second.end ())
00110       return;
00111 
00112     it_row->second.erase (it_col);
00113     if (it_row->second.empty ())
00114     {}
00115     m_mat.erase (it_row);
00116 
00117   }
00118   else
00119   {
00120     // update entry
00121     m_mat[i][j] = v;
00122 
00123   }
00124 
00125 }
00126 
00127 void
00128 SparseMat::deleteRow (int i)
00129 {
00130 
00131   std::map<int, std::map<int, double> >::iterator it_row;
00132 
00133   it_row = m_mat.find (i);
00134   if (it_row != m_mat.end ())
00135     m_mat.erase (it_row);
00136 
00137 }
00138 
00139 void
00140 SparseMat::deleteColumn (int j)
00141 {
00142   std::map<int, std::map<int, double> >::iterator it_row;
00143   std::map<int, double>::iterator it_col;
00144 
00145   it_row = m_mat.begin ();
00146   while (it_row != m_mat.end ())
00147   {
00148     it_col = it_row->second.find (j);
00149     if (it_col != it_row->second.end ())
00150       it_row->second.erase (it_col);
00151     it_row++;
00152   }
00153 
00154 }
00155 
00156 void
00157 SparseMat::size (int &si, int &sj)
00158 {
00159   std::map<int, std::map<int, double> >::iterator it_row;
00160   std::map<int, double>::iterator it_col;
00161 
00162   if (m_mat.empty ())
00163   {
00164     si = 0;
00165     sj = 0;
00166     return;
00167   }
00168 
00169   si = 0;
00170   sj = 0;
00171 
00172   it_row = m_mat.begin ();
00173   while (it_row != m_mat.end ())
00174   {
00175     it_col = it_row->second.end ();
00176     it_col--;
00177     if (sj < ((*it_col).first + 1))
00178       sj = (*it_col).first + 1;
00179 
00180     it_row++;
00181   }
00182 
00183   it_row = m_mat.end ();
00184   it_row--;
00185   si = (*it_row).first + 1;
00186 
00187 }
00188 
00189 int
00190 SparseMat::nonzeros ()
00191 {
00192   std::map<int, std::map<int, double> >::iterator it_row;
00193   int s = 0;
00194 
00195   it_row = m_mat.begin ();
00196   while (it_row != m_mat.end ())
00197   {
00198     s += int (it_row->second.size ());
00199 
00200     it_row++;
00201   }
00202 
00203   return s;
00204 
00205 }
00206 
00207 void
00208 SparseMat::printLong ()
00209 {
00210   std::map<int, std::map<int, double> >::iterator it_row;
00211   std::map<int, double>::iterator it_col;
00212 
00213   int si, sj;
00214   size (si, sj);
00215 
00216   for (int i = 0; i < si; i++)
00217   {
00218     for (int j = 0; j < sj; j++)
00219     {
00220       printf ("%f ", get (i, j));
00221     }
00222     printf ("\n");
00223   }
00224 }
00225 
00226 void
00227 SparseMat::print ()
00228 {
00229   std::map<int, std::map<int, double> >::iterator it_row;
00230   std::map<int, double>::iterator it_col;
00231 
00232   it_row = m_mat.begin ();
00233   while (it_row != m_mat.end ())
00234   {
00235     it_col = it_row->second.begin ();
00236     while (it_col != it_row->second.end ())
00237     {
00238       printf ("[%d,%d] %f ", it_row->first, it_col->first, it_col->second);
00239       it_col++;
00240     }
00241     printf ("\n");
00242     it_row++;
00243   }
00244 }
00245 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:33:37