SparseMatrix.hpp
Go to the documentation of this file.
1 //==============================================================================
2 //
3 // This file is part of GNSSTk, the ARL:UT GNSS Toolkit.
4 //
5 // The GNSSTk is free software; you can redistribute it and/or modify
6 // it under the terms of the GNU Lesser General Public License as published
7 // by the Free Software Foundation; either version 3.0 of the License, or
8 // any later version.
9 //
10 // The GNSSTk is distributed in the hope that it will be useful,
11 // but WITHOUT ANY WARRANTY; without even the implied warranty of
12 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 // GNU Lesser General Public License for more details.
14 //
15 // You should have received a copy of the GNU Lesser General Public
16 // License along with GNSSTk; if not, write to the Free Software Foundation,
17 // Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110, USA
18 //
19 // This software was developed by Applied Research Laboratories at the
20 // University of Texas at Austin.
21 // Copyright 2004-2022, The Board of Regents of The University of Texas System
22 //
23 //==============================================================================
24 
25 //==============================================================================
26 //
27 // This software was developed by Applied Research Laboratories at the
28 // University of Texas at Austin, under contract to an agency or agencies
29 // within the U.S. Department of Defense. The U.S. Government retains all
30 // rights to use, duplicate, distribute, disclose, or release this software.
31 //
32 // Pursuant to DoD Directive 523024
33 //
34 // DISTRIBUTION STATEMENT A: This software has been approved for public
35 // release, distribution is unlimited.
36 //
37 //==============================================================================
39 
40 #ifndef SPARSE_MATRIX_INCLUDE
41 #define SPARSE_MATRIX_INCLUDE
42 
43 #include <algorithm> // for find,lower_bound
44 #include <map>
45 #include <string>
46 
47 #include "Matrix.hpp"
48 #include "SparseVector.hpp"
49 
50 namespace gnsstk
51 {
52  // forward declarations
53  template <class T> class SparseMatrix;
54 
55  //---------------------------------------------------------------------------
57  template <class T> class SMatProxy
58  {
59  public:
61  SMatProxy(SparseMatrix<T>& SM, unsigned int i, unsigned int j);
62 
65  {
66  assign(rhs);
67  return *this;
68  }
71  {
72  assign(rhs);
73  return *this;
74  }
75 
77  operator T() const;
78 
81  {
82  assign(value() + rhs);
83  return *this;
84  }
85 
88  {
89  assign(value() + rhs);
90  return *this;
91  }
92 
95  {
96  assign(value() - rhs);
97  return *this;
98  }
99 
102  {
103  assign(value() - rhs);
104  return *this;
105  }
106 
109  {
110  assign(value() * rhs);
111  return *this;
112  }
113 
116  {
117  assign(value() * rhs);
118  return *this;
119  }
120 
121  private:
124 
126  unsigned int irow, jcol;
127 
129  T value() const;
130 
132  void assign(T rhs);
133 
134  }; // end class SMatProxy
135 
136  //---------------------------------------------------------------------------
137  // implementation of SMatProxy
138  //---------------------------------------------------------------------------
139  // Default constructor
140  template <class T>
141  SMatProxy<T>::SMatProxy(SparseMatrix<T>& sm, unsigned int i, unsigned int j)
142  : mySM(sm), irow(i), jcol(j)
143  {
144  }
145 
146  //---------------------------------------------------------------------------
147  // get the value of the SparseMatrix at irow, jcol
148  template <class T> T SMatProxy<T>::value() const
149  {
150  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
151  it = mySM.rowsMap.find(irow);
152  if (it != mySM.rowsMap.end())
153  {
154  return it->second[jcol];
155  }
156 
157  return T();
158  }
159 
160  //---------------------------------------------------------------------------
161  // assignment, used by operator=, operator+=, etc
162  template <class T> void SMatProxy<T>::assign(T rhs)
163  {
164  typename std::map<unsigned int, SparseVector<T>>::iterator it;
165  it = mySM.rowsMap.find(irow);
166 
167  // add a new row? only if row is not there, and rhs is not zero
168  if (T(rhs) != T(0) && it == mySM.rowsMap.end())
169  {
170  SparseVector<T> SVrow(mySM.ncols);
171  mySM.rowsMap[irow] = SVrow;
172  it = mySM.rowsMap.find(irow);
173  }
174  // data is zero and row is not there...nothing to do
175  else if (it == mySM.rowsMap.end())
176  {
177  return;
178  }
179 
180  // assign it - let SparseVector::SMatProxy handle r/lvalue
181  // first, do we need to resize the SV?
182  if (it->second.size() < jcol + 1)
183  {
184  it->second.resize(jcol + 1);
185  }
186  it->second[jcol] = rhs;
187 
188  // if row is now empty, remove it
189  if (it->second.datasize() == 0)
190  {
191  mySM.rowsMap.erase(it);
192  }
193  }
194 
195  //---------------------------------------------------------------------------
196  // cast
197  template <class T> SMatProxy<T>::operator T() const
198  {
199  typename std::map<unsigned int, SparseVector<T>>::iterator it;
200  it = mySM.rowsMap.find(irow);
201  if (it == mySM.rowsMap.end())
202  {
203  return T();
204  }
205  else
206  {
207  return it->second[jcol];
208  }
209  }
210 
211  //---------------------------------------------------------------------------
212  //---------------------------------------------------------------------------
213  // friends of class SparseMatrix - must declare friends before the template
214  // class min max
215  template <class T> T min(const SparseMatrix<T>& SM);
216  template <class T> T max(const SparseMatrix<T>& SM);
217  template <class T> T minabs(const SparseMatrix<T>& SM);
218  template <class T> T maxabs(const SparseMatrix<T>& SM);
219  // output
220  template <class T>
221  std::ostream& operator<<(std::ostream& os, const SparseMatrix<T>& SM);
222  // transpose
223  template <class T> SparseMatrix<T> transpose(const SparseMatrix<T>& M);
224  // multiplies
225  template <class T>
227  const SparseMatrix<T>& R);
228  template <class T>
230  const SparseVector<T>& V);
231  template <class T>
233  template <class T>
235  template <class T>
237  const SparseMatrix<T>& R);
238  template <class T>
240  template <class T>
242  template <class T>
244  const SparseMatrix<T>& R);
245  template <class T>
247  template <class T>
249  // concatenation
250  template <class T>
252  template <class T>
254  const SparseMatrix<T>& R);
255  // addition and subtraction
256  template <class T>
258  const SparseMatrix<T>& R);
259  template <class T>
261  template <class T>
263  template <class T>
265  const SparseMatrix<T>& R);
266  template <class T>
268  template <class T>
273  template <class T> SparseMatrix<T> inverse(const SparseMatrix<T>& A);
277  template <class T> SparseMatrix<T> lowerCholesky(const SparseMatrix<T>& A);
281  template <class T> SparseMatrix<T> upperCholesky(const SparseMatrix<T>& A);
285  template <class T>
286  SparseMatrix<T> inverseLT(const SparseMatrix<T>& LT, T *ptrSmall, T *ptrBig);
290  template <class T>
292 
293  // special matrices
294  template <class T>
295  SparseMatrix<T> identSparse(const unsigned int dim);
296 
301  template <class T>
306  template <class T>
311  template <class T>
312  Vector<T> transformDiag(const SparseMatrix<T>& P, const Matrix<T>& C);
313 
317  template <class T>
319 
323  template <class T>
324  void SrifMU(Matrix<T>& R, Vector<T>& Z, SparseMatrix<T>& A,
325  const unsigned int M);
329  template <class T>
330  void SrifMU(Matrix<T>& R, Vector<T>& Z, SparseMatrix<T>& P, Vector<T>& D,
331  const unsigned int M);
332 
333  //---------------------------------------------------------------------------
356  template <class T> class SparseMatrix
357  {
358  public:
359  // lots of friends
361  friend class SMatProxy<T>;
362  // min max
363  friend T min<T>(const SparseMatrix<T>& SM);
364  friend T max<T>(const SparseMatrix<T>& SM);
365  friend T minabs<T>(const SparseMatrix<T>& SM);
366  friend T maxabs<T>(const SparseMatrix<T>& SM);
367  // stream operator
368  friend std::ostream& operator<<<T>(std::ostream& os,
369  const SparseMatrix<T>& S);
370  // transpose
371  friend SparseMatrix<T> transpose<T>(const SparseMatrix<T>& M);
372  // arithmetic
373  friend SparseMatrix<T> operator-
374  <T>(const SparseMatrix<T>& L, const SparseMatrix<T>& R);
375  friend SparseMatrix<T> operator-
376  <T>(const SparseMatrix<T>& L, const Matrix<T>& R);
377  friend SparseMatrix<T> operator-
378  <T>(const Matrix<T>& L, const SparseMatrix<T>& R);
379  friend SparseMatrix<T> operator+
380  <T>(const SparseMatrix<T>& L, const SparseMatrix<T>& R);
381  friend SparseMatrix<T> operator+
382  <T>(const SparseMatrix<T>& L, const Matrix<T>& R);
383  friend SparseMatrix<T> operator+
384  <T>(const Matrix<T>& L, const SparseMatrix<T>& R);
385  // mulitply
386  friend SparseMatrix<T> operator*<T>(const SparseMatrix<T>& L,
387  const SparseMatrix<T>& R);
388  friend SparseVector<T> operator*<T>(const SparseMatrix<T>& L,
389  const SparseVector<T>& V);
390  friend SparseVector<T> operator*<T>(const Matrix<T>& L,
391  const SparseVector<T>& V);
392  friend SparseVector<T> operator*<T>(const SparseMatrix<T>& L,
393  const Vector<T>& V);
394  friend SparseVector<T> operator*<T>(const SparseVector<T>& V,
395  const SparseMatrix<T>& R);
396  friend SparseVector<T> operator*<T>(const SparseVector<T>& V,
397  const Matrix<T>& R);
398  friend SparseVector<T> operator*<T>(const Vector<T>& V,
399  const SparseMatrix<T>& R);
400  friend SparseMatrix<T> operator*<T>(const SparseMatrix<T>& L,
401  const SparseMatrix<T>& R);
402  friend SparseMatrix<T> operator*<T>(const SparseMatrix<T>& L,
403  const Matrix<T>& R);
404  friend SparseMatrix<T> operator*<T>(const Matrix<T>& L,
405  const SparseMatrix<T>& R);
406  // concatenation
407  friend SparseMatrix<T> operator||
408  <T>(const SparseMatrix<T>& L, const Vector<T>& V);
409  friend SparseMatrix<T> operator||
410  <T>(const SparseMatrix<T>& L, const SparseMatrix<T>& R);
411  // inverse (via Gauss-Jordan)
412  friend SparseMatrix<T> inverse<T>(const SparseMatrix<T>& A);
413  // Cholesky
414  friend SparseMatrix<T> lowerCholesky<T>(const SparseMatrix<T>& A);
415  friend SparseMatrix<T> upperCholesky<T>(const SparseMatrix<T>& A);
416  friend SparseMatrix<T> inverseLT<T>(const SparseMatrix<T>& LT,
417  T *ptrSmall, T *ptrBig);
418  friend SparseMatrix<T> inverseViaCholesky<T>(const SparseMatrix<T>& A);
419  // special matrices
420  friend SparseMatrix<T> identSparse<T>(const unsigned int dim);
421 
422  // MT * M
423  friend SparseMatrix<T> transposeTimesMatrix<T>(const SparseMatrix<T>& M);
424  // M * MT
425  friend SparseMatrix<T> matrixTimesTranspose<T>(const SparseMatrix<T>& M);
426  // diag of P * C * PT
427  friend Vector<T> transformDiag<T>(const SparseMatrix<T>& P,
428  const Matrix<T>& C);
429  friend SparseMatrix<T> SparseHouseholder<T>(const SparseMatrix<T>& A);
430  friend void SrifMU<T>(Matrix<T>& R, Vector<T>& Z, SparseMatrix<T>& A,
431  const unsigned int M);
432  friend void SrifMU<T>(Matrix<T>& R, Vector<T>& Z, SparseMatrix<T>& P,
433  Vector<T>& D, const unsigned int M);
434 
436  SparseMatrix() : nrows(0), ncols(0) {}
437 
439  SparseMatrix(unsigned int r, unsigned int c) : nrows(r), ncols(c) {}
440 
447  SparseMatrix(const SparseMatrix<T>& SM, const unsigned int& rind,
448  const unsigned int& cind, const unsigned int& rnum,
449  const unsigned int& cnum);
450 
452  SparseMatrix(const Matrix<T>& M);
453 
454  // TD watch for unintended consequences - cast to Matrix to use some
455  // Matrix::fun
457  operator Matrix<T>() const;
458 
460  inline unsigned int rows() const { return nrows; }
461 
463  inline unsigned int cols() const { return ncols; }
464 
466  inline unsigned int size() const { return nrows * ncols; }
467 
469  inline unsigned int datasize() const
470  {
471  unsigned int n(0);
472  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
473  it = rowsMap.begin();
474  for (; it != rowsMap.end(); ++it)
475  n += it->second.datasize();
476  return n;
477  }
478 
480  inline bool isEmpty() const
481  {
482  return (rowsMap.begin() == rowsMap.end());
483  }
484 
486  inline double density() const
487  {
488  return (double(datasize()) / double(size()));
489  }
490 
492  void resize(const unsigned int newrows, const unsigned int newcols)
493  {
494  typename std::map<unsigned int, SparseVector<T>>::iterator it;
495  if (newrows < nrows)
496  {
497  // lower_bound returns it for first key >= newrows
498  it = rowsMap.lower_bound(newrows);
499  rowsMap.erase(it, rowsMap.end());
500  }
501  if (newcols < ncols)
502  {
503  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
504  {
505  it->second.resize(newcols);
506  }
507  }
508 
509  nrows = newrows;
510  ncols = newcols;
511  }
512 
514  inline void clear() { rowsMap.clear(); }
515 
524  void
525  zeroize(const T tol = static_cast<T>(SparseVector<T>::zeroTolerance));
526 
528  inline bool isFilled(const unsigned int i, const unsigned int j)
529  {
530  typename std::map<unsigned int, SparseVector<T>>::iterator it;
531  it = rowsMap.find(i);
532  return (it != rowsMap.end() && it->second.isFilled(j));
533  }
534 
535  // operators ----------------------------------------------------
537  const SMatProxy<T> operator()(unsigned int i, unsigned int j) const
538  {
539 #ifdef RANGECHECK
540  if (i >= nrows)
541  {
542  GNSSTK_THROW(Exception("row index out of range"));
543  }
544  if (j >= ncols)
545  {
546  GNSSTK_THROW(Exception("col index out of range"));
547  }
548 #endif
549  return SMatProxy<T>(const_cast<SparseMatrix &>(*this), i, j);
550  }
551 
553  SMatProxy<T> operator()(unsigned int i, unsigned int j)
554  {
555 #ifdef RANGECHECK
556  if (i >= nrows)
557  {
558  GNSSTK_THROW(Exception("row index out of range"));
559  }
560  if (j >= ncols)
561  {
562  GNSSTK_THROW(Exception("col index out of range"));
563  }
564 #endif
565  return SMatProxy<T>(*this, i, j);
566  }
567 
568  // output -------------------------------------------------------
570  std::string dump(const int p = 3, bool dosci = false) const
571  {
572  std::ostringstream oss;
573  size_t i;
574  oss << "dim(" << nrows << "," << ncols << "), size " << size()
575  << ", datasize " << datasize() << " :";
576  oss << (dosci ? std::scientific : std::fixed) << std::setprecision(p);
577 
578  // loop over rows
579  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
580  it = rowsMap.begin();
581  if (it == rowsMap.end())
582  {
583  oss << " empty";
584  return oss.str();
585  }
586 
587  for (; it != rowsMap.end(); ++it)
588  {
589  oss << "\n row " << it->first << ": " << it->second.dump(p, dosci);
590  }
591 
592  return oss.str();
593  }
594 
596  void flatten(std::vector<unsigned int>& rows,
597  std::vector<unsigned int>& cols,
598  std::vector<T>& values) const
599  {
600  rows.clear();
601  cols.clear();
602  values.clear();
603 
604  // loop over rows, then columns
605  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
606  typename std::map<unsigned int, T>::const_iterator jt;
607  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
608  {
609  unsigned int row(it->first);
610  for (jt = it->second.vecMap.begin(); jt != it->second.vecMap.end();
611  ++jt)
612  {
613  rows.push_back(row);
614  cols.push_back(jt->first);
615  values.push_back(jt->second);
616  }
617  }
618  }
619 
621  // arithmetic and other operators
626  SparseMatrix<T>& operator*=(const T& value);
630  SparseMatrix<T>& operator/=(const T& value);
631 
632  // unary minus
634  {
635  SparseMatrix<T> toRet(*this);
636  typename std::map<unsigned int, SparseVector<T>>::iterator it;
637  typename std::map<unsigned int, T>::iterator jt;
638  for (it = toRet.rowsMap.begin(); it != toRet.rowsMap.end(); ++it)
639  {
640  for (jt = it->second.vecMap.begin(); jt != it->second.vecMap.end();
641  ++jt)
642  jt->second = -jt->second;
643  }
644  return toRet;
645  }
646 
648  SparseVector<T> rowCopy(const unsigned int i) const;
649 
651  SparseVector<T> colCopy(const unsigned int j) const;
652 
654  SparseVector<T> diagCopy() const;
655 
657  void swapRows(const unsigned int& ii, const unsigned int& jj);
658 
660  void swapCols(const unsigned int ii, const unsigned int jj);
661 
662  private:
664  unsigned int nrows, ncols;
665 
667  std::map<unsigned int, SparseVector<T>> rowsMap;
668 
669  // TD ? obsolete this by always using transpose when you must loop over
670  // columns
676  std::map<unsigned int, std::vector<unsigned int>> columnMap() const
677  {
678  unsigned int j, k;
679  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
680  typename std::map<unsigned int, std::vector<unsigned int>> colMap;
681  typename std::map<unsigned int, std::vector<unsigned int>>::iterator
682  jt;
683 
684  // loop over rows, then columns
685  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
686  {
687 
688  // get all the column indexes for this row
689  std::vector<unsigned int> colIndexes = it->second.getIndexes();
690 
691  // loop over columns, adding each to the colMap
692  for (k = 0; k < colIndexes.size(); k++)
693  {
694  j = colIndexes[k];
695  jt = colMap.find(j);
696  if (jt == colMap.end())
697  { // add a vector for this column
698  std::vector<unsigned int> jvec;
699  colMap[j] = jvec;
700  jt = colMap.find(j);
701  }
702  jt->second.push_back(
703  it->first); // add row index to this col-vector
704  }
705  }
706 
707  // std::ostringstream oss;
708  // for(jt=colMap.begin(); jt!=colMap.end(); ++jt) {
709  // oss << " col " << jt->first << " [";
710  // for(k=0; k<jt->second.size(); k++)
711  // oss << " " << jt->second[k];
712  // oss << "]\n";
713  //}
714  // std::cout << "Column map:\n" << oss.str();
715 
716  return colMap;
717  }
718 
719  }; // end class SparseMatrix
720 
721  //---------------------------------------------------------------------------
722  // implementation of SparseMatrix
723  //---------------------------------------------------------------------------
724  // submatrix constructor
725  template <class T>
727  const unsigned int& rind,
728  const unsigned int& cind,
729  const unsigned int& rnum,
730  const unsigned int& cnum)
731  {
732  if (rnum == 0 || cnum == 0 || rind + rnum > SM.nrows ||
733  cind + cnum > SM.ncols)
734  {
735  GNSSTK_THROW(Exception("Invalid input submatrix c'tor - out of range"));
736  }
737 
738  nrows = rnum;
739  ncols = cnum;
740  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
741  for (it = SM.rowsMap.begin(); it != SM.rowsMap.end(); ++it)
742  {
743  if (it->first < rind)
744  {
745  continue; // skip rows before rind
746  }
747  if (it->first > rind + rnum)
748  {
749  break; // done with rows
750  }
751  SparseVector<T> SV(it->second, cind, cnum); // get sub-vector
752  if (!SV.isEmpty())
753  {
754  rowsMap[it->first] = SV; // add it
755  }
756  }
757  }
758 
759  // constructor from regular Matrix<T>
760  template <class T> SparseMatrix<T>::SparseMatrix(const Matrix<T>& M)
761  {
762  unsigned i, j;
763  nrows = M.rows();
764  ncols = M.cols();
765  for (i = 0; i < nrows; i++)
766  {
767  bool haverow(false); // rather than rowsMap.find() every time
768  for (j = 0; j < ncols; j++)
769  {
770  if (M(i, j) == T(0))
771  {
772  continue; // nothing to do - element(i,j) is zero
773  }
774 
775  // non-zero, must add it
776  if (!haverow)
777  { // add row i
778  SparseVector<T> SVrow(ncols); // 'real' length ncols
779  rowsMap[i] = SVrow;
780  haverow = true;
781  }
782  rowsMap[i].vecMap[j] = M(i, j);
783  }
784  }
785  }
786 
788  template <class T> SparseMatrix<T>::operator Matrix<T>() const
789  {
790  Matrix<T> toRet(nrows, ncols, T(0));
791  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
792  typename std::map<unsigned int, T>::const_iterator jt;
793  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
794  {
795  for (jt = it->second.vecMap.begin(); jt != it->second.vecMap.end();
796  ++jt)
797  {
798  toRet(it->first, jt->first) = jt->second;
799  }
800  }
801 
802  return toRet;
803  }
804 
806  template <class T> void SparseMatrix<T>::zeroize(const T tol)
807  {
808  std::vector<unsigned int> toDelete; // row indexes
809  typename std::map<unsigned int, SparseVector<T>>::iterator it;
810  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
811  {
812  it->second.zeroize(tol);
813 
814  // remove row if its empty - but not inside the iteration loop
815  if (it->second.datasize() == 0)
816  {
817  toDelete.push_back(it->first);
818  }
819  }
820 
821  // now remove the marked rows
822  for (unsigned int i = 0; i < toDelete.size(); i++)
823  {
824  rowsMap.erase(toDelete[i]);
825  }
826  }
827 
829  template <class T> SparseMatrix<T> transpose(const SparseMatrix<T>& M)
830  {
831  SparseMatrix<T> toRet(M.cols(), M.rows());
832 
833  // loop over rows of M = columns of toRet - faster
834  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
835  typename std::map<unsigned int, SparseVector<T>>::iterator jt;
836  for (it = M.rowsMap.begin(); it != M.rowsMap.end(); ++it)
837  {
838  for (unsigned int j = 0; j < M.cols(); j++)
839  {
840  if (it->second.isFilled(j))
841  { // M(i,j)
842  jt = toRet.rowsMap.find(j);
843  if (jt == toRet.rowsMap.end())
844  { // add the row
845  SparseVector<T> rowSV(M.rows());
846  toRet.rowsMap[j] = rowSV;
847  jt = toRet.rowsMap.find(j);
848  }
849  jt->second.vecMap[it->first] = it->second[j];
850  }
851  }
852  }
853 
854  return toRet;
855  }
856 
858  template <class T> T min(const SparseMatrix<T>& SM)
859  {
860  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
861  it = SM.rowsMap.begin();
862  if (it == SM.rowsMap.end())
863  {
864  return T(0);
865  }
866 
867  T value(min(it->second)); // first non-zero row
868  for (++it; it != SM.rowsMap.end(); ++it)
869  { // other rows
870  T rowval(min(it->second));
871  if (rowval < value)
872  {
873  value = rowval;
874  }
875  }
876 
877  return value;
878  }
879 
881  template <class T> T max(const SparseMatrix<T>& SM)
882  {
883  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
884  it = SM.rowsMap.begin();
885  if (it == SM.rowsMap.end())
886  {
887  return T(0);
888  }
889 
890  T value(max(it->second)); // first non-zero row
891  for (++it; it != SM.rowsMap.end(); ++it)
892  { // other rows
893  T rowval(max(it->second));
894  if (rowval > value)
895  {
896  value = rowval;
897  }
898  }
899 
900  return value;
901  }
902 
904  template <class T> T minabs(const SparseMatrix<T>& SM)
905  {
906  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
907  it = SM.rowsMap.begin();
908  if (it == SM.rowsMap.end())
909  {
910  return T(0);
911  }
912 
913  T value(minabs(it->second)); // first non-zero row
914  for (++it; it != SM.rowsMap.end(); ++it)
915  { // other rows
916  T rowval(minabs(it->second));
917  if (rowval < value)
918  {
919  value = rowval;
920  }
921  }
922 
923  return value;
924  }
925 
927  template <class T> T maxabs(const SparseMatrix<T>& SM)
928  {
929  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
930  it = SM.rowsMap.begin();
931  if (it == SM.rowsMap.end())
932  {
933  return T(0);
934  }
935 
936  T value(maxabs(it->second)); // first non-zero row
937  for (++it; it != SM.rowsMap.end(); ++it)
938  { // other rows
939  T rowval(maxabs(it->second));
940  if (rowval > value)
941  {
942  value = rowval;
943  }
944  }
945 
946  return value;
947  }
948 
949  //---------------------------------------------------------------------------------
951  template <class T>
952  std::ostream& operator<<(std::ostream& os, const SparseMatrix<T>& SM)
953  {
954  std::ofstream savefmt;
955  savefmt.copyfmt(os);
956 
957  unsigned int i, j; // the "real" vector row and column index
958  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
959 
960  it = SM.rowsMap.begin();
961  // if(it == SM.rowsMap.end()) { os << "empty"; return os; }
962 
963  for (i = 0; i < SM.nrows; i++)
964  {
965  if (it != SM.rowsMap.end() && i == it->first)
966  {
967  os << std::setw(1) << ' ';
968  os.copyfmt(savefmt);
969  os << it->second; // write the whole row
970  ++it;
971  }
972  else
973  {
974  for (j = 0; j < SM.ncols; j++)
975  { // write a row of '0'
976  os << std::setw(1) << ' ';
977  os.copyfmt(savefmt);
978  os << "0";
979  }
980  }
981  if (i < SM.nrows - 1)
982  {
983  os << "\n";
984  }
985  }
986 
987  return os;
988  }
989 
990  //---------------------------------------------------------------------------
991  // SparseMatrix operators
992  //---------------------------------------------------------------------------
993 
995  template <class T>
997  {
998  try
999  {
1000  if (L.cols() != V.size())
1001  {
1002  GNSSTK_THROW(Exception("Incompatible dimensions op*(SM,SV)"));
1003  }
1004 
1005  SparseVector<T> retSV(L.rows());
1006  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
1007 
1008  // loop over rows of L = rows of answer
1009  for (it = L.rowsMap.begin(); it != L.rowsMap.end(); ++it)
1010  retSV.vecMap[it->first] = dot(it->second, V);
1011 
1012  retSV.zeroize(T(0));
1013  return retSV;
1014  }
1015  catch (Exception& e)
1016  {
1017  GNSSTK_RETHROW(e);
1018  }
1019  }
1020 
1022  template <class T>
1024  {
1025  try
1026  {
1027  if (L.cols() != V.size())
1028  {
1029  GNSSTK_THROW(Exception("Incompatible dimensions op*(M,SV)"));
1030  }
1031 
1032  SparseVector<T> retSV(L.rows());
1033 
1034  // loop over rows of L = rows of answer
1035  for (unsigned int i = 0; i < L.rows(); i++)
1036  {
1037  T sum(0);
1038  // loop over elements of V
1039  typename std::map<unsigned int, T>::const_iterator it;
1040  for (it = V.vecMap.begin(); it != V.vecMap.end(); ++it)
1041  sum += L(i, it->first) * it->second;
1042  retSV.vecMap[i] = sum;
1043  }
1044 
1045  retSV.zeroize(T(0));
1046  return retSV;
1047  }
1048  catch (Exception& e)
1049  {
1050  GNSSTK_RETHROW(e);
1051  }
1052  }
1053 
1055  template <class T>
1057  {
1058  try
1059  {
1060  if (L.cols() != V.size())
1061  {
1062  GNSSTK_THROW(Exception("Incompatible dimensions op*(SM,V)"));
1063  }
1064 
1065  SparseVector<T> retSV(L.rows());
1066  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
1067 
1068  // loop over rows of L = rows of answer
1069  for (it = L.rowsMap.begin(); it != L.rowsMap.end(); ++it)
1070  retSV.vecMap[it->first] = dot(it->second, V);
1071 
1072  retSV.zeroize(T(0));
1073  return retSV;
1074  }
1075  catch (Exception& e)
1076  {
1077  GNSSTK_RETHROW(e);
1078  }
1079  }
1080 
1082  template <class T>
1084  {
1085  if (V.size() != R.rows())
1086  {
1087  GNSSTK_THROW(Exception("Incompatible dimensions op*(SV,SM)"));
1088  }
1089 
1090  SparseVector<T> retSV(R.cols());
1091 
1092  // first build a "column map" for R - vectors (of row-index) for each
1093  // column colMap[column index] = vector of all row indexes, in ascending
1094  // order
1095  std::map<unsigned int, std::vector<unsigned int>>::iterator jt;
1096  std::map<unsigned int, std::vector<unsigned int>> colMap = R.columnMap();
1097 
1098  // loop over columns of R = elements of answer
1099  for (jt = colMap.begin(); jt != colMap.end(); ++jt)
1100  {
1101  T sum(0);
1102  // loop over rows of R and elements of V
1103  for (unsigned int k = 0; k < jt->second.size(); k++)
1104  if (V.isFilled(jt->second[k]))
1105  {
1106  sum += V[jt->second[k]] * R(k, jt->first);
1107  }
1108  if (sum != T(0))
1109  {
1110  retSV.vecMap[jt->first] = sum;
1111  }
1112  }
1113 
1114  return retSV;
1115  }
1116 
1118  template <class T>
1120  {
1121  try
1122  {
1123  if (V.size() != R.rows())
1124  {
1125  GNSSTK_THROW(Exception("Incompatible dimensions op*(SV,M)"));
1126  }
1127 
1128  T sum;
1129  SparseVector<T> retSV(R.cols());
1130 
1131  // loop over columns of R = elements of answer
1132  for (unsigned int j = 0; j < R.cols(); j++)
1133  {
1134  // copy out the whole column as a Vector
1135  Vector<T> colR = R.colCopy(j);
1136  sum = dot(colR, V);
1137  if (sum != T(0))
1138  {
1139  retSV.vecMap[j] = sum;
1140  }
1141  }
1142 
1143  return retSV;
1144  }
1145  catch (Exception& e)
1146  {
1147  GNSSTK_RETHROW(e);
1148  }
1149  }
1150 
1152  template <class T>
1154  {
1155  if (V.size() != R.rows())
1156  {
1157  GNSSTK_THROW(Exception("Incompatible dimensions op*(V,SM)"));
1158  }
1159 
1160  SparseVector<T> retSV(R.cols());
1161 
1162  // first build a "column map" for R - vectors (of row-index) for each
1163  // column colMap[column index] = vector of all row indexes, in ascending
1164  // order
1165  std::map<unsigned int, std::vector<unsigned int>>::iterator jt;
1166  std::map<unsigned int, std::vector<unsigned int>> colMap = R.columnMap();
1167 
1168  // loop over columns of R = elements of answer
1169  for (jt = colMap.begin(); jt != colMap.end(); ++jt)
1170  {
1171  T sum(0);
1172  // loop over rows of R and elements of V
1173  for (unsigned int k = 0; k < jt->second.size(); k++)
1174  sum += V[jt->second[k]] * R(jt->second[k], jt->first);
1175  if (sum != T(0))
1176  {
1177  retSV.vecMap[jt->first] = sum;
1178  }
1179  }
1180 
1181  return retSV;
1182  }
1183 
1185  template <class T>
1187  {
1188  if (L.cols() != R.rows())
1189  {
1190  GNSSTK_THROW(Exception("Incompatible dimensions op*(SM,SM)"));
1191  }
1192 
1193  const unsigned int nr(L.rows()), nc(R.cols());
1194  SparseMatrix<T> retSM(nr, nc); // empty but with correct dimen.
1195  const SparseMatrix<T> RT(transpose(R)); // work with transpose
1196  typename std::map<unsigned int, SparseVector<T>>::const_iterator it, jt;
1197 
1198  // loop over rows of L = rows of retSM
1199  for (it = L.rowsMap.begin(); it != L.rowsMap.end(); ++it)
1200  {
1201  bool haveRow(false); // use to create the row
1202  // loop over rows of RT == columns of R
1203  for (jt = RT.rowsMap.begin(); jt != RT.rowsMap.end(); ++jt)
1204  {
1205  // answer(i,j) = dot product of Lrow and RTrow==Rcol
1206  T d(dot(it->second, jt->second));
1207  if (d != T(0))
1208  {
1209  if (!haveRow)
1210  {
1211  SparseVector<T> row(nc);
1212  retSM.rowsMap[it->first] = row;
1213  haveRow = true;
1214  }
1215  retSM.rowsMap[it->first].vecMap[jt->first] = d;
1216  }
1217  }
1218  }
1219 
1220  return retSM;
1221  }
1222 
1224  template <class T>
1226  {
1227  try
1228  {
1229  if (L.cols() != R.rows())
1230  {
1231  GNSSTK_THROW(Exception("Incompatible dimensions op*(SM,M)"));
1232  }
1233 
1234  const unsigned int nr(L.rows()), nc(R.cols());
1235  SparseMatrix<T> retSM(nr, nc);
1236  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
1237 
1238  // loop over rows of L = rows of answer
1239  for (it = L.rowsMap.begin(); it != L.rowsMap.end(); ++it)
1240  {
1241  bool haveRow(false); // use to create the row
1242  // loop over columns of R = cols of answer
1243  for (unsigned int j = 0; j < R.cols(); j++)
1244  {
1245  Vector<T> colR(R.colCopy(j));
1246  T d(dot(it->second, colR));
1247  if (d != T(0))
1248  {
1249  if (!haveRow)
1250  {
1251  SparseVector<T> row(nc);
1252  retSM.rowsMap[it->first] = row;
1253  haveRow = true;
1254  }
1255  retSM.rowsMap[it->first].vecMap[j] = d;
1256  }
1257  }
1258  }
1259 
1260  return retSM;
1261  }
1262  catch (Exception& e)
1263  {
1264  GNSSTK_RETHROW(e);
1265  }
1266  }
1267 
1269  template <class T>
1271  {
1272  if (L.cols() != R.rows())
1273  {
1274  GNSSTK_THROW(Exception("Incompatible dimensions op*(M,SM)"));
1275  }
1276 
1277  const unsigned int nr(L.rows()), nc(R.cols());
1278  SparseMatrix<T> retSM(nr, nc);
1279  const SparseMatrix<T> RT(transpose(R)); // work with transpose
1280  typename std::map<unsigned int, SparseVector<T>>::const_iterator jt;
1281 
1282  // loop over rows of L = rows of retSM
1283  for (unsigned int i = 0; i < nr; i++)
1284  {
1285  bool haveRow(false); // use to create the row in retSM
1286  const Vector<T> rowL(L.rowCopy(i)); // copy out the row in L
1287 
1288  // loop over rows of RT == columns of R
1289  for (jt = RT.rowsMap.begin(); jt != RT.rowsMap.end(); ++jt)
1290  {
1291  // answer(i,j) = dot product of Lrow and RTrow==Rcol
1292  T d(dot(rowL, jt->second));
1293  if (d != T(0))
1294  {
1295  if (!haveRow)
1296  {
1297  SparseVector<T> row(nc);
1298  retSM.rowsMap[i] = row;
1299  haveRow = true;
1300  }
1301  retSM.rowsMap[i].vecMap[jt->first] = d;
1302  }
1303  }
1304  }
1305 
1306  return retSM;
1307  }
1308 
1309  //---------------------------------------------------------------------------
1310  //---------------------------------------------------------------------------
1312  template <class T>
1314  {
1315  if (L.rows() != V.size())
1316  {
1317  GNSSTK_THROW(Exception("Incompatible dimensions op||(SM,V)"));
1318  }
1319 
1320  SparseMatrix<T> toRet(L);
1321  toRet.ncols++;
1322 
1323  unsigned int i, n(toRet.ncols - 1);
1324  typename std::map<unsigned int, SparseVector<T>>::iterator jt;
1325  for (i = 0; i < V.size(); i++)
1326  {
1327  if (V(i) != T(0))
1328  { // add it
1329  jt = toRet.rowsMap.find(i); // find the row
1330  if (jt == toRet.rowsMap.end())
1331  { // add the row
1332  SparseVector<T> V(toRet.ncols);
1333  toRet.rowsMap[i] = V;
1334  }
1335  toRet.rowsMap[i].vecMap[n] = V(i);
1336  }
1337  }
1338  return toRet;
1339  }
1340 
1341  //---------------------------------------------------------------------------
1342  template <class T>
1344  const SparseMatrix<T>& R)
1345  {
1346  if (L.rows() != R.rows())
1347  {
1348  GNSSTK_THROW(Exception("Incompatible dimensions op||(SM,SM)"));
1349  }
1350 
1351  SparseMatrix<T> toRet(L);
1352  toRet.ncols += R.ncols;
1353 
1354  unsigned int i, N(L.ncols);
1355  typename std::map<unsigned int, SparseVector<T>>::iterator it;
1356  typename std::map<unsigned int, SparseVector<T>>::const_iterator jt;
1357  it = toRet.rowsMap.begin();
1358  jt = R.rowsMap.begin();
1359  while (it != toRet.rowsMap.end() && jt != R.rowsMap.end())
1360  {
1361  if (it->first < jt->first)
1362  { // R has no row here - do nothing
1363  it->second.len += N;
1364  ++it;
1365  }
1366  else if (it->first > jt->first)
1367  { // R has a row where toRet does not
1368  toRet.rowsMap[jt->first] = jt->second;
1369  toRet.rowsMap[jt->first].len += N;
1370  ++jt;
1371  }
1372  else
1373  { // equal indexes - both have rows
1374  it->second.len += N;
1375  typename std::map<unsigned int, T>::const_iterator vt;
1376  for (vt = jt->second.vecMap.begin(); vt != jt->second.vecMap.end();
1377  ++vt)
1378  {
1379  toRet.rowsMap[it->first].vecMap[N + vt->first] = vt->second;
1380  }
1381  ++it;
1382  ++jt;
1383  }
1384  }
1385 
1386  return toRet;
1387  }
1388 
1389  //---------------------------------------------------------------------------
1390  //---------------------------------------------------------------------------
1392  template <class T>
1394  {
1395  if (SM.cols() != cols() || SM.rows() != rows())
1396  {
1397  GNSSTK_THROW(Exception("Incompatible dimensions op-=(SM)"));
1398  }
1399  // std::cout << "SM::op-=(SM)" << std::endl;
1400 
1401  // loop over rows of SM
1402  typename std::map<unsigned int, SparseVector<T>>::const_iterator sit;
1403  for (sit = SM.rowsMap.begin(); sit != SM.rowsMap.end(); ++sit)
1404  {
1405  // find same row in this
1406  if (rowsMap.find(sit->first) == rowsMap.end())
1407  {
1408  rowsMap[sit->first] = -sit->second;
1409  }
1410  else
1411  {
1412  rowsMap[sit->first] -= sit->second;
1413  }
1414  }
1415 
1416  zeroize(T(0));
1417  return *this;
1418  }
1419 
1421  template <class T>
1423  {
1424  if (M.cols() != cols() || M.rows() != rows())
1425  {
1426  GNSSTK_THROW(Exception("Incompatible dimensions op-=(M)"));
1427  }
1428  // std::cout << "SM::op-=(M)" << std::endl;
1429 
1430  // loop over rows of M
1431  for (unsigned int i = 0; i < M.rows(); i++)
1432  {
1433  Vector<T> rowV(M.rowCopy(i));
1434  if (rowsMap.find(i) == rowsMap.end())
1435  {
1436  SparseVector<T> SV(rowV);
1437  rowsMap[i] = -SV;
1438  }
1439  else
1440  {
1441  rowsMap[i] -= rowV;
1442  }
1443  }
1444 
1445  zeroize(T(0));
1446  return *this;
1447  }
1448 
1450  template <class T>
1452  {
1453  if (L.cols() != R.cols() || L.rows() != R.rows())
1454  {
1455  GNSSTK_THROW(Exception("Incompatible dimensions op-(SM,SM)"));
1456  }
1457  // std::cout << "SM::op-(SM,SM)" << std::endl;
1458 
1459  SparseMatrix<T> retSM(L);
1460  retSM -= R; // will zeroize(T(0))
1461 
1462  return retSM;
1463  }
1464 
1466  template <class T>
1468  {
1469  if (L.cols() != R.cols() || L.rows() != R.rows())
1470  {
1471  GNSSTK_THROW(Exception("Incompatible dimensions op-(SM,M)"));
1472  }
1473  // std::cout << "SM::op-(SM,M)" << std::endl;
1474 
1475  SparseMatrix<T> retSM(L);
1476  retSM -= R; // will zeroize(T(0))
1477 
1478  return retSM;
1479  }
1480 
1482  template <class T>
1484  {
1485  if (L.cols() != R.cols() || L.rows() != R.rows())
1486  {
1487  GNSSTK_THROW(Exception("Incompatible dimensions op-(M,SM)"));
1488  }
1489  // std::cout << "SM::op-(M,SM)" << std::endl;
1490 
1491  SparseMatrix<T> retSM(R);
1492  retSM = -retSM;
1493  retSM += L; // will zeroize(T(0))
1494 
1495  return retSM;
1496  }
1497 
1498  //---------------------------------------------------------------------------
1500  template <class T>
1502  {
1503  if (SM.cols() != cols() || SM.rows() != rows())
1504  {
1505  GNSSTK_THROW(Exception("Incompatible dimensions op+=(SM)"));
1506  }
1507  // std::cout << "SM::op+=(SM)" << std::endl;
1508 
1509  // loop over rows of SM
1510  typename std::map<unsigned int, SparseVector<T>>::const_iterator sit;
1511  for (sit = SM.rowsMap.begin(); sit != SM.rowsMap.end(); ++sit)
1512  {
1513  // find same row in this
1514  if (rowsMap.find(sit->first) == rowsMap.end())
1515  {
1516  rowsMap[sit->first] = sit->second;
1517  }
1518  else
1519  {
1520  rowsMap[sit->first] += sit->second;
1521  }
1522  }
1523 
1524  zeroize(T(0));
1525  return *this;
1526  }
1527 
1529  template <class T>
1531  {
1532  if (M.cols() != cols() || M.rows() != rows())
1533  {
1534  GNSSTK_THROW(Exception("Incompatible dimensions op+=(M)"));
1535  }
1536  // std::cout << "SM::op+=(M)" << std::endl;
1537 
1538  // loop over rows of M
1539  for (unsigned int i = 0; i < M.rows(); i++)
1540  {
1541  Vector<T> rowV(M.rowCopy(i));
1542  if (rowsMap.find(i) == rowsMap.end())
1543  {
1544  SparseVector<T> SV(rowV);
1545  rowsMap[i] = SV;
1546  }
1547  else
1548  {
1549  rowsMap[i] += rowV;
1550  }
1551  }
1552 
1553  zeroize(T(0));
1554  return *this;
1555  }
1556 
1557  //---------------------------------------------------------------------------
1559  template <class T>
1561  {
1562  if (value == T(0))
1563  {
1564  rowsMap.clear();
1565  return *this;
1566  }
1567 
1568  // loop over all elements
1569  typename std::map<unsigned int, SparseVector<T>>::iterator it;
1570  typename std::map<unsigned int, T>::iterator vt;
1571  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
1572  {
1573  for (vt = it->second.vecMap.begin(); vt != it->second.vecMap.end();
1574  ++vt)
1575  vt->second *= value;
1576  }
1577 
1578  return *this;
1579  }
1580 
1585  template <class T>
1587  {
1588  if (value == T(0))
1589  {
1590  GNSSTK_THROW(Exception("Divide by zero"));
1591  }
1592 
1593  // loop over all elements
1594  typename std::map<unsigned int, SparseVector<T>>::iterator it;
1595  typename std::map<unsigned int, T>::iterator vt;
1596  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
1597  {
1598  for (vt = it->second.vecMap.begin(); vt != it->second.vecMap.end();
1599  ++vt)
1600  vt->second /= value;
1601  }
1602 
1603  return *this;
1604  }
1605 
1607  template <class T>
1609  {
1610  if (L.cols() != R.cols() || L.rows() != R.rows())
1611  {
1612  GNSSTK_THROW(Exception("Incompatible dimensions op+(SM,SM)"));
1613  }
1614  // std::cout << "SM::op+(SM,SM)" << std::endl;
1615 
1616  SparseMatrix<T> retSM(L);
1617  retSM -= R; // will zeroize(T(0))
1618 
1619  return retSM;
1620  }
1621 
1623  template <class T>
1625  {
1626  if (L.cols() != R.cols() || L.rows() != R.rows())
1627  {
1628  GNSSTK_THROW(Exception("Incompatible dimensions op+(SM,M)"));
1629  }
1630  // std::cout << "SM::op+(SM,M)" << std::endl;
1631 
1632  SparseMatrix<T> retSM(L);
1633  retSM -= R; // will zeroize(T(0))
1634 
1635  return retSM;
1636  }
1637 
1642  template <class T>
1644  {
1645  if (L.cols() != R.cols() || L.rows() != R.rows())
1646  {
1647  GNSSTK_THROW(Exception("Incompatible dimensions op+(M,SM)"));
1648  }
1649  // std::cout << "SM::op+(M,SM)" << std::endl;
1650 
1651  SparseMatrix<T> retSM(L);
1652  retSM -= R; // will zeroize(T(0))
1653 
1654  return retSM;
1655  }
1656 
1657  //---------------------------------------------------------------------------
1658  // row, col and diagonal copy, swap
1659  //---------------------------------------------------------------------------
1661  template <class T>
1662  SparseVector<T> SparseMatrix<T>::rowCopy(const unsigned int i) const
1663  {
1664  SparseVector<T> retSV;
1665  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
1666  it = rowsMap.find(i);
1667  if (it != rowsMap.end())
1668  {
1669  retSV = it->second;
1670  }
1671  return retSV;
1672  }
1673 
1675  template <class T>
1676  SparseVector<T> SparseMatrix<T>::colCopy(const unsigned int j) const
1677  {
1678  SparseVector<T> retSV;
1679 
1680  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
1681  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
1682  { // loop over rows
1683  if (it->second.isFilled(j))
1684  {
1685  retSV.vecMap[it->first] = it->second[j];
1686  }
1687  }
1688  retSV.len = rows();
1689 
1690  return retSV;
1691  }
1692 
1694  template <class T> SparseVector<T> SparseMatrix<T>::diagCopy() const
1695  {
1696  SparseVector<T> retSV;
1697 
1698  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
1699  for (it = rowsMap.begin(); it != rowsMap.end(); ++it)
1700  { // loop over rows
1701  if (it->second.isFilled(it->first))
1702  {
1703  retSV.vecMap[it->first] = it->second[it->first];
1704  }
1705  }
1706  retSV.len = rows();
1707 
1708  return retSV;
1709  }
1710 
1712  template <class T>
1713  void SparseMatrix<T>::swapRows(const unsigned int& ii,
1714  const unsigned int& jj)
1715  {
1716  if (ii >= nrows || jj >= nrows)
1717  {
1718  GNSSTK_THROW(Exception("Invalid indexes"));
1719  }
1720 
1721  typename std::map<unsigned int, SparseVector<T>>::iterator it, jt;
1722  it = rowsMap.find(ii);
1723  jt = rowsMap.find(jj);
1724  if (it == rowsMap.end())
1725  {
1726  if (jt == rowsMap.end())
1727  {
1728  return; // nothing to do
1729  }
1730  else
1731  {
1732  rowsMap[ii] = rowsMap[jj];
1733  rowsMap.erase(jt);
1734  }
1735  }
1736  else
1737  {
1738  if (jt == rowsMap.end())
1739  {
1740  rowsMap[jj] = rowsMap[ii];
1741  rowsMap.erase(it);
1742  }
1743  else
1744  {
1745  SparseVector<T> save(it->second);
1746  rowsMap[ii] = rowsMap[jj];
1747  rowsMap[jj] = save;
1748  }
1749  }
1750  }
1751 
1753  template <class T>
1754  void SparseMatrix<T>::swapCols(const unsigned int ii, const unsigned int jj)
1755  {
1756  if (ii >= ncols || jj >= ncols)
1757  {
1758  GNSSTK_THROW(Exception("Invalid indexes"));
1759  }
1760 
1761  // may not be the fastest, but may be fast enough - tranpose() is fast
1762  SparseMatrix<T> trans(transpose(*this));
1763  trans.swapRows(ii, jj);
1764  *this = transpose(*this);
1765  }
1766 
1767  //---------------------------------------------------------------------------------
1768  // special matrices
1769  //---------------------------------------------------------------------------------
1775  template <class T>
1776  SparseMatrix<T> identSparse(const unsigned int dim)
1777  {
1778  if (dim == 0)
1779  {
1780  return SparseMatrix<T>();
1781  }
1782 
1783  SparseMatrix<T> toRet(dim, dim);
1784  for (unsigned int i = 0; i < dim; i++)
1785  {
1786  SparseVector<T> SV(dim);
1787  SV.vecMap[i] = T(1);
1788  toRet.rowsMap[i] = SV;
1789  }
1790 
1791  return toRet;
1792  }
1793 
1794  //---------------------------------------------------------------------------------
1795  // matrix products and transformations
1796  //---------------------------------------------------------------------------------
1797 
1798  //---------------------------------------------------------------------------------
1799  // SM * transpose(SM)
1800  // NB this is barely faster than just forming SM * transpose(SM)
1801  template <class T>
1803  {
1804  try
1805  {
1806  SparseMatrix<T> toRet(SM.rows(), SM.rows());
1807 
1808  typename std::map<unsigned int, SparseVector<T>>::const_iterator it,
1809  jt;
1810  for (it = SM.rowsMap.begin(); it != SM.rowsMap.end(); ++it)
1811  {
1812  SparseVector<T> Vrow(SM.rows());
1813  toRet.rowsMap[it->first] = Vrow;
1814  for (jt = SM.rowsMap.begin(); jt != SM.rowsMap.end(); ++jt)
1815  {
1816  T d(dot(it->second, jt->second));
1817  if (d != T(0))
1818  {
1819  toRet.rowsMap[it->first][jt->first] = d;
1820  }
1821  }
1822  }
1823 
1824  return toRet;
1825  }
1826  catch (Exception& e)
1827  {
1828  GNSSTK_RETHROW(e);
1829  }
1830  }
1831 
1832  //---------------------------------------------------------------------------------
1833  //---------------------------------------------------------------------------------
1835  template <class T>
1837  {
1838  try
1839  {
1840  if (P.cols() != C.rows() || C.rows() != C.cols())
1841  {
1842  GNSSTK_THROW(Exception("Incompatible dimensions transformDiag()"));
1843  }
1844 
1845  const unsigned int n(P.cols());
1846  typename std::map<unsigned int, SparseVector<T>>::const_iterator jt;
1847  typename std::map<unsigned int, T>::const_iterator vt;
1848 
1849  Vector<T> toRet(P.rows(), T(0));
1850  T sum;
1851 
1852  // loop over rows of P = columns of transpose(P)
1853  for (jt = P.rowsMap.begin(); jt != P.rowsMap.end(); ++jt)
1854  {
1855  unsigned int j = jt->first; // row of P, col of P^T
1856  Vector<T> prod(n, T(0));
1857 
1858  // loop over columns of C up to and including j,
1859  // forming dot product prod(k) = P(rowj) * C(colk)
1860  for (unsigned int k = 0; k < n; k++)
1861  {
1862  sum = T(0);
1863  for (vt = jt->second.vecMap.begin();
1864  vt != jt->second.vecMap.end(); ++vt)
1865  sum += vt->second * C(vt->first, k);
1866  if (sum != T(0))
1867  {
1868  prod(k) = sum;
1869  }
1870  }
1871  toRet(j) = dot(jt->second, prod);
1872  }
1873  return toRet;
1874  }
1875  catch (Exception& e)
1876  {
1877  GNSSTK_RETHROW(e);
1878  }
1879  }
1880 
1881  //---------------------------------------------------------------------------
1882  // inverse (via Gauss-Jordan)
1883  //---------------------------------------------------------------------------
1890  template <class T> SparseMatrix<T> inverse(const SparseMatrix<T>& A)
1891  {
1892  try
1893  {
1894  if (A.rows() != A.cols() || A.rows() == 0)
1895  {
1896  std::ostringstream oss;
1897  oss << "Invalid input dimensions: " << A.rows() << "x" << A.cols();
1898  GNSSTK_THROW(Exception(oss.str()));
1899  }
1900 
1901  unsigned int i, k;
1902  T dtmp;
1903  // T big, small;
1904  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
1905 
1906  // does A have any zero rows?
1907  for (it = A.rowsMap.begin(), i = 0; it != A.rowsMap.end(); i++, ++it)
1908  {
1909  if (i != it->first)
1910  {
1911  std::ostringstream oss;
1912  oss << "Singular matrix - zero row at index " << i << ")";
1913  GNSSTK_THROW(Exception(oss.str()));
1914  }
1915  }
1916 
1917  const unsigned int N(A.rows());
1918  typename std::map<unsigned int, SparseVector<T>>::iterator jt, kt;
1919  typename std::map<unsigned int, T>::iterator vt;
1920  SparseMatrix<T> GJ(A || identSparse<T>(N));
1921 
1922  // std::cout << "\nInitial:\n" << std::scientific
1923  // << std::setprecision(2) << std::setw(10) << GJ <<
1924  // std::endl;
1925 
1926  // loop over rows of work matrix, making lower left triangular = unity
1927  for (jt = GJ.rowsMap.begin(); jt != GJ.rowsMap.end(); ++jt)
1928  {
1929 
1930  // divide row by diagonal element; if diagonal is zero, add another
1931  // row
1932  vt = jt->second.vecMap.find(jt->first); // diagonal element GJ(j,j)
1933  if (vt == jt->second.vecMap.end() || vt->second == T(0))
1934  {
1935  // find a lower row with non-zero element (same col); add to this
1936  // row
1937  for ((kt = jt)++; kt != GJ.rowsMap.end(); ++kt)
1938  {
1939  vt = kt->second.vecMap.find(jt->first); // GJ(k,j)
1940  if (vt == kt->second.vecMap.end() || vt->second == T(0))
1941  {
1942  continue; // nope, its zero
1943  }
1944 
1945  // add the kt row to the jt row
1946  jt->second += kt->second;
1947  break;
1948  }
1949  if (kt == GJ.rowsMap.end())
1950  {
1951  GNSSTK_THROW(Exception("Singular matrix"));
1952  }
1953  }
1954 
1955  dtmp = vt->second;
1956  // are these scales 1/dtmp related to condition number? eigenvalues?
1957  // det? they are close to condition number....
1958  // if(jt == GJ.rowsMap.begin()) big = small = ::fabs(dtmp);
1959  // if(::fabs(dtmp) > big) big = ::fabs(dtmp);
1960  // if(::fabs(dtmp) < small) small = ::fabs(dtmp);
1961 
1962  // normalize the j row
1963  if (dtmp != T(1))
1964  {
1965  jt->second *= T(1) / dtmp;
1966  }
1967 
1968  // std::cout << "\nRow " << jt->first << " scaled with " <<
1969  // std::scientific
1970  // << std::setprecision(2) << T(1)/dtmp << "\n"
1971  // << std::setw(10) << GJ << std::endl;
1972 
1973  // now zero out the column below the j diagonal
1974  for ((kt = jt)++; kt != GJ.rowsMap.end(); ++kt)
1975  {
1976  vt = kt->second.vecMap.find(jt->first); // GJ(k,j)
1977  if (vt == kt->second.vecMap.end() || vt->second == T(0))
1978  {
1979  continue; // already zero
1980  }
1981 
1982  kt->second.addScaledSparseVector(-vt->second, jt->second);
1983  }
1984 
1985  // std::cout << "\nRow " << jt->first << " left-zeroed:\n"
1986  // << std::scientific << std::setprecision(2) << std::setw(10)
1987  // << GJ << std::endl;
1988  }
1989 
1990  // loop over rows of work matrix in reverse order,
1991  // zero-ing out the column above the diag
1992  typename std::map<unsigned int, SparseVector<T>>::reverse_iterator rjt,
1993  rkt;
1994  for (rjt = GJ.rowsMap.rbegin(); rjt != GJ.rowsMap.rend(); ++rjt)
1995  {
1996  // now zero out the column above the j diagonal
1997  for ((rkt = rjt)++; rkt != GJ.rowsMap.rend(); ++rkt)
1998  {
1999  vt = rkt->second.vecMap.find(rjt->first); // GJ(k,j)
2000  if (vt == rkt->second.vecMap.end() || vt->second == T(0))
2001  {
2002  continue; // already zero
2003  }
2004  rkt->second.addScaledSparseVector(-vt->second, rjt->second);
2005  }
2006 
2007  // std::cout << "\nRow " << rjt->first << " right-zeroed:\n"
2008  // << std::scientific << std::setprecision(2) << std::setw(10)
2009  // << GJ << std::endl;
2010  }
2011 
2012  // std::cout << "\nbig and small for this matrix are: "
2013  // << std::scientific << std::setprecision(2)
2014  // << big << " " << small << " with ratio " << big/small <<
2015  // std::endl;
2016 
2017  return (SparseMatrix<T>(GJ, 0, N, N, N));
2018  }
2019  catch (Exception& e)
2020  {
2021  GNSSTK_RETHROW(e);
2022  }
2023  }
2024 
2025  //---------------------------------------------------------------------------
2026  // Factorization, decomposition and other algorithms
2027  //---------------------------------------------------------------------------
2028 
2029  //---------------------------------------------------------------------------------
2030  // Compute Cholesky decomposition of symmetric positive definite matrix using
2031  // Crout algorithm. A = L*L^T where A and L are (nxn) and L is lower
2032  // triangular reads: [ A00 A01 A02 ... A0n ] = [ L00 0 0 0 ... 0 ][ L00
2033  // L10 L20 ... L0n ] [ A10 A11 A12 ... A1n ] = [ L10 L11 0 0 ... 0 ][ 0
2034  // L11 L21 ... L1n ] [ A20 A21 A22 ... A2n ] = [ L20 L21 L22 0 ... 0 ][ 0
2035  // 0 L22 ... L2n ]
2036  // ... ... ...
2037  // [ An0 An1 An2 ... Ann ] = [ Ln0 Ln1 Ln2 0 ... Lnn][ 0 0 0 ... Lnn ]
2038  // but multiplying out gives
2039  // A = [ L00^2
2040  // [ L00*L10 L11^2+L10^2
2041  // [ L00*L20 L11*L21+L10*L20 L22^2+L21^2+L20^2
2042  // ...
2043  // Aii = Lii^2 + sum(k=0,i-1) Lik^2
2044  // Aij = Lij*Ljj + sum(k=0,j-1) Lik*Ljk
2045  // These can be inverted by looping over columns, and filling L from diagonal
2046  // down. So fill L in this way
2047  // d do diagonal element first, then the column below it
2048  // 1d at each row i below the diagonal, save the element^2 in rowSums[i]
2049  // 12d
2050  // 123d
2051  // 123 d
2052  // 123 d
2053  // 123 d
2054  // 123 d
2055  // 123 etc d
2056 
2065  template <class T> SparseMatrix<T> lowerCholesky(const SparseMatrix<T>& A)
2066  {
2067  if (A.rows() != A.cols() || A.rows() == 0)
2068  {
2069  std::ostringstream oss;
2070  oss << "Invalid input dimensions: " << A.rows() << "x" << A.cols();
2071  GNSSTK_THROW(Exception(oss.str()));
2072  }
2073 
2074  const unsigned int n = A.rows();
2075  unsigned int i, j, k;
2076  T d, diag;
2077  SparseMatrix<T> L(n, n); // compute the answer
2078  std::vector<T> rowSums; // keep sum(k=0..j-1)[L(j,k)^2] for each row j
2079  typename std::map<unsigned int, SparseVector<T>>::const_iterator it, jt;
2080  typename std::map<unsigned int, SparseVector<T>>::iterator Lit, Ljt;
2081 
2082  // A must have all rows - a zero row in A means its singular
2083  // create all the rows in L; all exist b/c if any diagonal is 0 ->
2084  // singular fill rowSums vector with zeros
2085  for (it = A.rowsMap.begin(), i = 0; it != A.rowsMap.end(); i++, ++it)
2086  {
2087  if (i != it->first)
2088  {
2089  std::ostringstream oss;
2090  oss << "lowerCholesky() requires positive-definite input:"
2091  << " (zero rows at index " << i << ")";
2092  GNSSTK_THROW(Exception(oss.str()));
2093  }
2094 
2095  SparseVector<T> Vrow(n);
2096  L.rowsMap[i] = Vrow;
2097 
2098  rowSums.push_back(T(0));
2099  }
2100 
2101  // loop over columns of A, at the same time looping over rows of L
2102  // use jt to iterate over the columns of A, keeping count with (column) j
2103  for (jt = A.rowsMap.begin(), Ljt = L.rowsMap.begin();
2104  jt != A.rowsMap.end() && Ljt != L.rowsMap.end(); ++jt, ++Ljt)
2105  {
2106  j = jt->first; // column j (A) or row i (L)
2107 
2108  // compute the j,j diagonal element of L
2109  // start with diagonal of A(j,j)
2110  d = jt->second[j]; // A(j,j)
2111 
2112  // subtract sum(k=0..j-1)[L(j,k)^2]
2113  d -= rowSums[j];
2114 
2115  // d is the eigenvalue - must not be zero
2116  if (d <= T(0))
2117  {
2118  std::ostringstream oss;
2119  oss << "Non-positive eigenvalue " << std::scientific << d
2120  << " at col " << j
2121  << ": lowerCholesky() requires positive-definite input";
2122  GNSSTK_THROW(Exception(oss.str()));
2123  }
2124 
2125  diag = SQRT(d);
2126  L.rowsMap[j].vecMap[j] = diag; // L(j,j)
2127 
2128  // now loop over rows below the diagonal, filling in this column
2129  Lit = Ljt;
2130  it = jt;
2131  for (++Lit, ++it; Lit != L.rowsMap.end(); ++Lit, ++it)
2132  {
2133  i = Lit->first;
2134  d = (it->second.isFilled(j) ? it->second[j] : T(0));
2135  d -= dot_lim(Lit->second, Ljt->second, 0, j);
2136 
2137  if (d != T(0))
2138  {
2139  d /= diag;
2140  Lit->second.vecMap[j] = d;
2141  rowSums[i] += d * d; // save L(i,j)^2 term
2142  }
2143 
2144  } // end loop over rows below the diagonal
2145 
2146  } // end loop over column j of A
2147 
2148  return L;
2149  }
2150 
2151  //---------------------------------------------------------------------------------
2153  template <class T>
2154  SparseMatrix<T> inverseLT(const SparseMatrix<T>& L, T *ptrSmall, T *ptrBig)
2155  {
2156  if (L.rows() != L.cols() || L.rows() == 0)
2157  {
2158  std::ostringstream oss;
2159  oss << "Invalid input dimensions: " << L.rows() << "x" << L.cols();
2160  GNSSTK_THROW(Exception(oss.str()));
2161  }
2162 
2163  const unsigned int n(L.rows());
2164  unsigned int i, j, k;
2165  T big(0), small(0), dum, sum;
2166 
2167  // trick is to fill transpose(inverse) and then transpose at the end
2168  SparseMatrix<T> invLT(L.cols(), L.rows());
2169  typename std::map<unsigned int, SparseVector<T>>::const_iterator it;
2170  typename std::map<unsigned int, SparseVector<T>>::iterator jt;
2171 
2172  // do the diagonal first; this finds singularities and defines all rows in
2173  // InvLT
2174  for (i = 0, it = L.rowsMap.begin(); i < n; ++it, ++i)
2175  {
2176  if (it == L.rowsMap.end() || it->first != i ||
2177  !it->second.isFilled(i) || it->second[i] == T(0))
2178  {
2179  std::ostringstream oss;
2180  oss << "Singular matrix - zero diagonal at row " << i;
2181  GNSSTK_THROW(Exception(oss.str()));
2182  }
2183 
2184  dum = it->second[i];
2185  if (ptrSmall)
2186  {
2187  if (ABS(dum) > big)
2188  {
2189  big = ABS(dum);
2190  }
2191  if (ABS(dum) < small)
2192  {
2193  small = ABS(dum);
2194  }
2195  }
2196 
2197  // create row i and element i,i in the answer
2198  dum = T(1) / dum;
2199  SparseVector<T> SV(L.cols());
2200  SV.vecMap[i] = dum;
2201  invLT.rowsMap[i] = SV;
2202  }
2203 
2204  // loop over rows again, filling in below the diagonal
2205  // (L has all rows present, else its singular above)
2206  // for(i=1; i<n; i++
2207  it = L.rowsMap.begin();
2208  for (++it; it != L.rowsMap.end(); ++it)
2209  {
2210  dum = T(1) / it->second[it->first]; // has to be there, and non-zero
2211  // loop over columns of invL (rows of invLT) before the diagonal
2212  // store results temporarily in a map
2213  std::map<unsigned int, T> tempMap;
2214  // for(j=0; j<i; j++)
2215  for (jt = invLT.rowsMap.begin(); jt != invLT.rowsMap.end(); ++jt)
2216  {
2217  if (jt->first >= it->first)
2218  {
2219  break;
2220  }
2221  // sum=0; for(k=j;k<i;k++) sum += L(i,k)*invLT(j,k)
2222  sum = dot_lim(it->second, jt->second, jt->first, it->first);
2223  // invLT(j,i) = -sum*dum
2224  if (sum != T(0))
2225  {
2226  tempMap[jt->first] = -dum * sum;
2227  }
2228  // jt->second.vecMap[it->first] = -dum*sum;
2229  }
2230  // now move contents of tempMap to invLT
2231  typename std::map<unsigned int, T>::iterator tt = tempMap.begin();
2232  for (; tt != tempMap.end(); ++tt)
2233  invLT.rowsMap[tt->first].vecMap[it->first] =
2234  tt->second; // invLT(j,i)
2235  }
2236 
2237  if (ptrSmall)
2238  {
2239  *ptrSmall = small;
2240  }
2241  if (ptrBig)
2242  {
2243  *ptrBig = big;
2244  }
2245 
2246  return transpose(invLT);
2247  }
2248 
2249  //---------------------------------------------------------------------------------
2262  template <class T> SparseMatrix<T> upperCholesky(const SparseMatrix<T>& A)
2263  {
2264  return transpose(lowerCholesky(A));
2265  }
2266 
2267  //---------------------------------------------------------------------------------
2276  template <class T>
2278  {
2279  try
2280  {
2281  // SparseMatrix<T> L(lowerCholesky(A));
2282  // SparseMatrix<T> Linv(inverseLT(L));
2283  // SparseMatrix<T> Ainv(matrixTimesTranspose(transpose(Linv)));
2284  // return Ainv;
2286  }
2287  catch (Exception& me)
2288  {
2289  me.addText("Called by inverseViaCholesky()");
2290  GNSSTK_RETHROW(me);
2291  }
2292  }
2293 
2294  //---------------------------------------------------------------------------------
2296  template <class T>
2298  {
2299  unsigned int i, j, k;
2300  typename std::map<unsigned int, SparseVector<T>>::iterator jt, kt, it;
2301  typename std::map<unsigned int, T>::iterator vt;
2302 
2303  SparseMatrix<T> AT(
2304  transpose(A)); // perform the algorithm on the transpose
2305 
2306  // loop over rows (columns of input A)
2307  for (j = 0; (j < A.cols() - 1 && j < A.rows() - 1); j++)
2308  {
2309  jt = AT.rowsMap.find(j); // is column j there?
2310  if (jt == AT.rowsMap.end()) // no, so A is already zero below diag
2311  {
2312  continue;
2313  }
2314 
2315  // pull out column j (use only below and including diagonal, ignore
2316  // V(i<j))
2317  SparseVector<T> V(jt->second);
2318  T sum(0);
2319  for (vt = V.vecMap.begin(); vt != V.vecMap.end(); ++vt)
2320  {
2321  if (vt->first < j)
2322  {
2323  continue;
2324  }
2325  sum += vt->second * vt->second;
2326  }
2327  if (sum < T(1.e-20))
2328  {
2329  continue; // col j is already zero below diag
2330  }
2331 
2332  // zero out below diagonal - must remove element
2333  vt = jt->second.vecMap.lower_bound(jt->first);
2334  if (vt != jt->second.vecMap.end())
2335  {
2336  jt->second.vecMap.erase(vt, jt->second.vecMap.end());
2337  }
2338 
2339  sum = SQRT(sum);
2340  vt = V.vecMap.find(j);
2341  if (vt != V.vecMap.end())
2342  {
2343  if (vt->second > T(0))
2344  {
2345  sum = -sum;
2346  }
2347  jt->second[j] = sum; // A(j,j) = sum
2348  vt->second -= sum; // V(j) -= sum
2349  sum = T(1) / (sum * vt->second);
2350  }
2351  else
2352  {
2353  jt->second[j] = sum; // A(j,j) = sum
2354  V.vecMap[j] = -sum; // V(j) -= sum
2355  sum = T(-1) / (sum * sum);
2356  }
2357 
2358  // loop over columns beyond j
2359  kt = jt;
2360  for (++kt; kt != AT.rowsMap.end(); ++kt)
2361  {
2362  T alpha(0);
2363  for (vt = kt->second.vecMap.begin(); vt != kt->second.vecMap.end();
2364  ++vt)
2365  {
2366  if (vt->first < j)
2367  {
2368  continue;
2369  }
2370  i = vt->first;
2371  if (V.isFilled(i)) // alpha += A(i,k)*V(i)
2372  {
2373  alpha += vt->second * V.vecMap[i];
2374  }
2375  }
2376  alpha *= sum;
2377  if (alpha == T(0))
2378  {
2379  continue;
2380  }
2381  // modify column k at and below j
2382  for (i = jt->first; i < AT.cols(); i++)
2383  {
2384  if (!V.isFilled(i))
2385  {
2386  continue;
2387  }
2388  vt = kt->second.vecMap.find(i);
2389  if (vt == kt->second.vecMap.end())
2390  { // create element
2391  kt->second.vecMap[i] = alpha * V.vecMap[i];
2392  }
2393  else
2394  {
2395  kt->second.vecMap[i] += alpha * V.vecMap[i];
2396  }
2397  }
2398  }
2399  }
2400 
2401  return (transpose(AT));
2402  }
2403 
2404  //---------------------------------------------------------------------------------
2405  // This routine uses the Householder algorithm to update the SRI
2406  // state+covariance. Input:
2407  // R a priori SRI matrix (upper triangular, dimension N)
2408  // Z a priori SRI data vector (length N)
2409  // A concatentation of H and D : A = H || D, where
2410  // H Measurement partials, an M by N matrix.
2411  // D Data vector, of length M
2412  // Output: Updated R and Z. H is trashed, but the data vector D
2413  // contains the residuals of fit (D - A*state).
2414  // Return values: SrifMU returns void, but throws exceptions if the input
2415  // matrices
2416  // or vectors have incompatible dimensions.
2417  //
2418  // Measurment noise associated with H and D must be white with unit
2419  // covariance. If necessary, the data can be 'whitened' before calling this
2420  // routine in order to satisfy this requirement. This is done as follows.
2421  // Compute the lower triangular square root of the covariance matrix, L,
2422  // and replace H with inverse(L)*H and D with inverse(L)*D.
2423  //
2424  // The Householder transformation is simply an orthogonal transformation
2425  // designed to make the elements below the diagonal zero. It works by
2426  // explicitly performing the transformation, one column at a time, without
2427  // actually constructing the transformation matrix. The matrix is transformed
2428  // as follows
2429  // [ A(m,n) ] => [ sum a ]
2430  // [ ] => [ 0 A'(m-1,n-1) ]
2431  // after which the same transformation is applied to A' matrix, until A' has
2432  // only one row or column. The transformation that zeros the diagonal below
2433  // the (k,k) element also replaces the (k,k) element and modifies the matrix
2434  // elements for columns >= k and rows >=k, but does not affect the matrix for
2435  // columns < k or rows < k.
2436  // Column k (=0..min(m,n)-1) of the input matrix A(m,n) can be zeroed
2437  // below the diagonal (columns < k have already been so zeroed) as follows:
2438  // let y be the vector equal to column k at the diagonal and below,
2439  // ( so y(j)==A(k+j,k), y(0)==A(k,k), y.size = m-k )
2440  // let sum = -sign(y(0))*|y|,
2441  // define vector u by u(0) = y(0)-sum, u(j)=y(j) for j>0 (j=1..m-k)
2442  // and finally define b = 1/(sum*u(0)).
2443  // Redefine column k with A(k,k)=sum and A(k+j,k)=0, j=1..m, and then for
2444  // each column j > k, (j=k+1..n)
2445  // compute g = b*sum[u(i)*A(k+i,j)], i=0..m-k-1,
2446  // replace A(k+i,j) with A(k+i,j)+g*u(i), for i=0..m-k-1
2447  // Most algorithms don't handle special cases:
2448  // 1. If column k is already zero below the diagonal, but A(k,k)!=0, then
2449  // y=[A(k,k),0,0,...0], sum=-A(k,k), u(0)=2A(k,k), u=[2A(k,k),0,0,...0]
2450  // and b = -1/(2*A(k,k)^2). Then, zeroing column k only changes the sign
2451  // of A(k,k), and for the other columns j>k, g = -A(k,j)/A(k,k) and only
2452  // row k is changed.
2453  // 2. If column k is already zero below the diagonal, AND A(k,k) is zero,
2454  // then y=0,sum=0,u=0 and b is infinite...the transformation is undefined.
2455  // However this column should be skipped (Biermann Appendix VII.B).
2456  //
2457  // Ref: Bierman, G.J. "Factorization Methods for Discrete Sequential
2458  // Estimation," Academic Press, 1977.
2459 
2460 
2466  template <class T>
2468  const unsigned int M)
2469  {
2470  // if necessary, create R and Z
2471  if (A.cols() > 1 && R.rows() == 0 && Z.size() == 0)
2472  {
2473  R = Matrix<double>(A.cols() - 1, A.cols() - 1, 0.0);
2474  Z = Vector<double>(A.cols() - 1, 0.0);
2475  }
2476 
2477  if (A.cols() <= 1 || A.cols() != R.cols() + 1 || Z.size() < R.rows())
2478  {
2479  std::ostringstream oss;
2480  oss << "Invalid input dimensions:\n R has dimension " << R.rows()
2481  << "x" << R.cols() << ",\n Z has length " << Z.size()
2482  << ",\n and A has dimension " << A.rows() << "x" << A.cols();
2483  GNSSTK_THROW(Exception(oss.str()));
2484  }
2485 
2486  const T EPS = T(1.e-20);
2487  const unsigned int m(M == 0 || M > A.rows() ? A.rows() : M), n(R.rows());
2488  const unsigned int np1(n +
2489  1); // if np1 = n, state vector Z is not updated
2490  unsigned int i, j, k;
2491  T dum, delta, beta;
2492  typename std::map<unsigned int, SparseVector<T>>::iterator jt, kt, it;
2493  typename std::map<unsigned int, T>::iterator vt;
2494 
2495  SparseMatrix<T> AT(transpose(A)); // work with the transpose
2496 
2497  for (j = 0; j < n; j++)
2498  { // loop over columns
2499  jt = AT.rowsMap.find(j); // is column j empty?
2500  if (jt ==
2501  AT.rowsMap.end()) // no, so A is already zero below the diagonal
2502  {
2503  continue;
2504  }
2505 
2506  // pull out column j of A; it is entirely below the diagonal
2507  SparseVector<T> Vj(jt->second);
2508  T sum(dot(Vj, Vj));
2509  // T sum(0);
2510  // for(i=0; i<m; i++)
2511  // sum += A(i,j)*A(i,j); // sum of squares of elements in column
2512  // below diag
2513  if (sum < EPS)
2514  {
2515  continue; // sum is positive
2516  }
2517 
2518  dum = R(j, j);
2519  sum += dum * dum; // add diagonal element
2520  sum = (dum > T(0) ? -T(1) : T(1)) * SQRT(sum);
2521  delta = dum - sum;
2522  R(j, j) = sum;
2523 
2524  // if(j+1 > np1) break; // this in case np1 is ever set to n ....
2525 
2526  beta = sum * delta; // beta by construction must be negative
2527  if (beta > -EPS)
2528  {
2529  continue;
2530  }
2531  beta = T(1) / beta;
2532 
2533  kt = jt;
2534  for (k = j + 1; k < np1; k++)
2535  { // columns to right of diagonal (j,j)
2536  SparseVector<T> Vk(m); // will be column k of A
2537 
2538  if (kt->first == k - 1)
2539  {
2540  ++kt; // kt now points to next column -- is it k?
2541  }
2542  if (kt->first != k)
2543  { // no col k - should create a column in A...
2544  AT.rowsMap[k] = Vk;
2545  kt = AT.rowsMap.find(k);
2546  }
2547  else
2548  {
2549  Vk = kt->second; // now Vk is column k of A, perhaps empty
2550  }
2551 
2552  sum = delta * (k == n ? Z(j) : R(j, k));
2553  sum += dot(Vk, Vj);
2554  // for(i=0; i<m; i++)
2555  // sum += A(i,j) * A(i,k);
2556  if (sum == T(0))
2557  {
2558  continue;
2559  }
2560 
2561  sum *= beta;
2562  if (k == n)
2563  {
2564  Z(j) += sum * delta;
2565  }
2566  else
2567  {
2568  R(j, k) += sum * delta;
2569  }
2570 
2571  vt = kt->second.vecMap.begin();
2572  for (i = 0; i < m; i++)
2573  { // loop over rows in column k
2574  // A(i,k) += sum * A(i,j);
2575  if (vt != kt->second.vecMap.end() && vt->first == i)
2576  {
2577  vt->second += sum * Vj.vecMap[i];
2578  ++vt;
2579  }
2580  else
2581  {
2582  kt->second.vecMap[i] = sum * Vj.vecMap[i];
2583  }
2584  }
2585  }
2586  }
2587 
2588  // must put last row of AT (last column of A) back into A - these are
2589  // residuals
2590  jt = AT.rowsMap.find(AT.rows() - 1);
2591  // should never happen
2592  if (jt == AT.rowsMap.end())
2593  {
2594  GNSSTK_THROW(Exception("Failure on last column"));
2595  }
2596 
2597  // put this row, jt->second, into the last column of A
2598  j = A.cols() - 1;
2599  i = 0;
2600  it = A.rowsMap.begin();
2601  vt = jt->second.vecMap.begin();
2602  while (it != A.rowsMap.end() && vt != jt->second.vecMap.end())
2603  {
2604  if (it->first > vt->first)
2605  { // A has no row at index vt->first
2606  SparseVector<T> SV(A.cols());
2607  SV.vecMap[j] = vt->second;
2608  A.rowsMap[vt->first] = SV;
2609  ++vt;
2610  }
2611  else if (vt->first > it->first)
2612  { // resids are missing at this row
2613  ++it;
2614  }
2615  else
2616  { // match - equal indexes
2617  A.rowsMap[vt->first].vecMap[j] = vt->second;
2618  ++it;
2619  ++vt;
2620  }
2621  }
2622 
2623  } // end SrifMU
2624 
2625  //---------------------------------------------------------------------------
2626  template <class T>
2628  const unsigned int M)
2629  {
2630  try
2631  {
2632  SparseMatrix<T> A(P || D);
2633  SrifMU(R, Z, A, M);
2634  // copy residuals out of A into D
2635  D = Vector<T>(A.colCopy(A.cols() - 1));
2636  }
2637  catch (Exception& e)
2638  {
2639  GNSSTK_RETHROW(e);
2640  }
2641  }
2642 
2643  //---------------------------------------------------------------------------
2644  //---------------------------------------------------------------------------
2645 
2646 } // namespace gnsstk
2647 
2648 #endif // define SPARSE_MATRIX_INCLUDE
gnsstk::SparseMatrix::operator+=
SparseMatrix< T > & operator+=(const SparseMatrix< T > &SM)
Matrix addition: SparseMatrix += SparseMatrix.
Definition: SparseMatrix.hpp:1501
gnsstk::SparseVector
forward declarations
Definition: SparseVector.hpp:60
gnsstk::SMatProxy::mySM
SparseMatrix< T > & mySM
reference to the matrix to which this data belongs
Definition: SparseMatrix.hpp:123
gnsstk::transposeTimesMatrix
SparseMatrix< T > transposeTimesMatrix(const SparseMatrix< T > &M)
gnsstk::ConstMatrixBase< T, Matrix< T > >::rowCopy
Vector< T > rowCopy(size_t r, size_t c=0) const
Definition: MatrixBase.hpp:165
gnsstk::SMatProxy::assign
void assign(T rhs)
assign the SparseMatrix element, used by operator=,+=,etc
Definition: SparseMatrix.hpp:162
gnsstk::SparseMatrix::operator*=
SparseMatrix< T > & operator*=(const T &value)
Multiply all elements by a scalar T constant.
Definition: SparseMatrix.hpp:1560
gnsstk::lowerCholesky
SparseMatrix< T > lowerCholesky(const SparseMatrix< T > &A)
Definition: SparseMatrix.hpp:2065
gnsstk::SMatProxy::SMatProxy
SMatProxy(SparseMatrix< T > &SM, unsigned int i, unsigned int j)
constructor
Definition: SparseMatrix.hpp:141
SQRT
#define SQRT(x)
Definition: MathBase.hpp:74
gnsstk::SMatProxy::operator-=
SMatProxy & operator-=(const SMatProxy< T > &rhs)
operator-= for non-const (lvalue)
Definition: SparseMatrix.hpp:94
gnsstk::SparseMatrix::colCopy
SparseVector< T > colCopy(const unsigned int j) const
return col j of this SparseMatrix as a SparseVector
Definition: SparseMatrix.hpp:1676
gnsstk::SparseMatrix::operator-
SparseMatrix< T > operator-() const
Definition: SparseMatrix.hpp:633
gnsstk::dot
T dot(const SparseVector< T > &SL, const SparseVector< T > &SR)
dot (SparseVector, SparseVector)
Definition: SparseVector.hpp:789
gnsstk::operator+
SparseMatrix< T > operator+(const SparseMatrix< T > &L, const SparseMatrix< T > &R)
Matrix addition: SparseMatrix = SparseMatrix + SparseMatrix : copy, += SM.
Definition: SparseMatrix.hpp:1608
gnsstk::SparseVector::zeroize
void zeroize(const T tol=static_cast< T >(zeroTolerance))
Definition: SparseVector.hpp:656
gnsstk::max
T max(const SparseMatrix< T > &SM)
Maximum element - return 0 if empty.
Definition: SparseMatrix.hpp:881
gnsstk::SparseMatrix::size
unsigned int size() const
size of matrix = rows()*cols()
Definition: SparseMatrix.hpp:466
gnsstk::SparseMatrix::isFilled
bool isFilled(const unsigned int i, const unsigned int j)
true if the element (i,j) is non-zero
Definition: SparseMatrix.hpp:528
gnsstk::sum
T sum(const ConstVectorBase< T, BaseClass > &l)
Definition: VectorBaseOperators.hpp:84
gnsstk::Matrix::cols
size_t cols() const
The number of columns in the matrix.
Definition: Matrix.hpp:167
gnsstk::identSparse
SparseMatrix< T > identSparse(const unsigned int dim)
Definition: SparseMatrix.hpp:1776
gnsstk::Matrix::rows
size_t rows() const
The number of rows in the matrix.
Definition: Matrix.hpp:165
gnsstk::SparseMatrix::density
double density() const
density - ratio of number of non-zero element to size()
Definition: SparseMatrix.hpp:486
gnsstk::dot_lim
T dot_lim(const SparseVector< T > &SL, const SparseVector< T > &SR, const unsigned int kb, const unsigned int ke)
dot (SparseVector, SparseVector) but only use indexes k=kb, k<ke
Definition: SparseVector.hpp:820
gnsstk::SparseMatrix::SMatProxy< T >
friend class SMatProxy< T >
Proxy needs access to rowsMap.
Definition: SparseMatrix.hpp:361
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::diag
Matrix< T > diag(const ConstMatrixBase< T, BaseClass > &m)
Definition: MatrixOperators.hpp:414
gnsstk::SparseMatrix::rows
unsigned int rows() const
get number of rows - of the real Matrix, not the data array
Definition: SparseMatrix.hpp:460
gnsstk::maxabs
T maxabs(const SparseMatrix< T > &SM)
Maximum absolute value - return 0 if empty.
Definition: SparseMatrix.hpp:927
gnsstk::Exception
Definition: Exception.hpp:151
gnsstk::SparseVector::resize
void resize(const unsigned int newlen)
resize - remove elements (truncate) and change nominal length len
Definition: SparseVector.hpp:408
gnsstk::SMatProxy::operator+=
SMatProxy & operator+=(T rhs)
operator+= for const (rvalue)
Definition: SparseMatrix.hpp:87
gnsstk::SparseMatrix::operator()
const SMatProxy< T > operator()(unsigned int i, unsigned int j) const
operator() for const, but SMatProxy does all the work
Definition: SparseMatrix.hpp:537
gnsstk::SparseMatrix::resize
void resize(const unsigned int newrows, const unsigned int newcols)
resize - only changes len and removes elements if necessary
Definition: SparseMatrix.hpp:492
gnsstk::SrifMU
void SrifMU(Matrix< T > &R, Vector< T > &Z, SparseMatrix< T > &A, const unsigned int M)
Definition: SparseMatrix.hpp:2467
gnsstk::SMatProxy::value
T value() const
get the value of the SparseMatrix at irow,jcol
Definition: SparseMatrix.hpp:148
gnsstk::SparseVector::isEmpty
bool isEmpty() const
is this SV empty? NB may have to call zeroize() to get a yes.
Definition: SparseVector.hpp:377
gnsstk::SMatProxy
Proxy class for elements of the SparseMatrix (SM).
Definition: SparseMatrix.hpp:57
gnsstk::minabs
T minabs(const SparseMatrix< T > &SM)
Minimum absolute value - return 0 if empty.
Definition: SparseMatrix.hpp:904
gnsstk::SparseMatrix::operator/=
SparseMatrix< T > & operator/=(const T &value)
Definition: SparseMatrix.hpp:1586
gnsstk::SparseVector::vecMap
std::map< unsigned int, T > vecMap
map of index,value pairs; vecMap[index in real vector] = data element
Definition: SparseVector.hpp:512
gnsstk::transpose
SparseMatrix< T > transpose(const SparseMatrix< T > &M)
transpose
Definition: SparseMatrix.hpp:829
gnsstk::SparseMatrix::rowCopy
SparseVector< T > rowCopy(const unsigned int i) const
return row i of this SparseMatrix as a SparseVector
Definition: SparseMatrix.hpp:1662
gnsstk::Matrix
Definition: Matrix.hpp:72
gnsstk::operator*
SparseMatrix< T > operator*(const SparseMatrix< T > &L, const SparseMatrix< T > &R)
Matrix multiply: SparseMatrix = SparseMatrix * SparseMatrix.
Definition: SparseMatrix.hpp:1186
gnsstk::inverseLT
SparseMatrix< T > inverseLT(const SparseMatrix< T > &LT, T *ptrSmall, T *ptrBig)
Compute inverse of lower-triangular SparseMatrix.
Definition: SparseMatrix.hpp:2154
gnsstk::SMatProxy::operator+=
SMatProxy & operator+=(const SMatProxy< T > &rhs)
operator+= for non-const (lvalue)
Definition: SparseMatrix.hpp:80
gnsstk::SMatProxy::jcol
unsigned int jcol
Definition: SparseMatrix.hpp:126
gnsstk::operator<<
std::ostream & operator<<(std::ostream &s, const ObsEpoch &oe) noexcept
Definition: ObsEpochMap.cpp:54
SparseVector.hpp
gnsstk::min
T min(const SparseMatrix< T > &SM)
Maximum element - return 0 if empty.
Definition: SparseMatrix.hpp:858
gnsstk::SparseMatrix::rowsMap
std::map< unsigned int, SparseVector< T > > rowsMap
map of row index, row SparseVector
Definition: SparseMatrix.hpp:667
gnsstk::SMatProxy::irow
unsigned int irow
indexes in mySM for this data
Definition: SparseMatrix.hpp:126
gnsstk::SparseMatrix::diagCopy
SparseVector< T > diagCopy() const
return diagonal of this SparseMatrix as a SparseVector
Definition: SparseMatrix.hpp:1694
gnsstk::beta
double beta(double x, double y)
Definition: SpecialFuncs.cpp:204
gnsstk::SparseMatrix::cols
unsigned int cols() const
get number of columns - of the real Matrix, not the data array
Definition: SparseMatrix.hpp:463
gnsstk::SMatProxy::operator-=
SMatProxy & operator-=(T rhs)
operator-= for const (rvalue)
Definition: SparseMatrix.hpp:101
GNSSTK_RETHROW
#define GNSSTK_RETHROW(exc)
Definition: Exception.hpp:369
gnsstk::upperCholesky
SparseMatrix< T > upperCholesky(const SparseMatrix< T > &A)
Definition: SparseMatrix.hpp:2262
gnsstk::Vector
Definition: Vector.hpp:67
gnsstk::TrackingCode::P
@ P
Legacy GPS precise code.
gnsstk::SparseMatrix::SparseMatrix
SparseMatrix(unsigned int r, unsigned int c)
constructor with dimensions
Definition: SparseMatrix.hpp:439
ABS
#define ABS(x)
Definition: MathBase.hpp:73
gnsstk::SMatProxy::operator*=
SMatProxy & operator*=(const SMatProxy< T > &rhs)
operator*= for non-const (lvalue)
Definition: SparseMatrix.hpp:108
gnsstk::SparseMatrix::flatten
void flatten(std::vector< unsigned int > &rows, std::vector< unsigned int > &cols, std::vector< T > &values) const
Convert to "dump-able" form : 3 parallel vectors; rows, cols, values.
Definition: SparseMatrix.hpp:596
gnsstk::transformDiag
Vector< T > transformDiag(const SparseMatrix< T > &P, const Matrix< T > &C)
Compute diagonal of P*C*P^T, ie diagonal of transform of square Matrix C.
Definition: SparseMatrix.hpp:1836
gnsstk::SparseVector::size
unsigned int size() const
size - of the real Vector, not the data array
Definition: SparseVector.hpp:371
gnsstk::SparseMatrix::swapCols
void swapCols(const unsigned int ii, const unsigned int jj)
swap columns of this SparseMatrix
Definition: SparseMatrix.hpp:1754
gnsstk::operator||
SparseMatrix< T > operator||(const SparseMatrix< T > &L, const Vector< T > &V)
Concatenation SparseMatrix || Vector TD the rest of them...
Definition: SparseMatrix.hpp:1313
gnsstk::Vector::size
size_t size() const
STL size.
Definition: Vector.hpp:207
gnsstk::ConstMatrixBase< T, Matrix< T > >::colCopy
Vector< T > colCopy(size_t c, size_t r=0) const
Definition: MatrixBase.hpp:146
gnsstk::SparseHouseholder
SparseMatrix< T > SparseHouseholder(const SparseMatrix< T > &A)
Householder transformation of a matrix.
Definition: SparseMatrix.hpp:2297
gnsstk::SparseMatrix::operator()
SMatProxy< T > operator()(unsigned int i, unsigned int j)
operator() for non-const, but SMatProxy does all the work
Definition: SparseMatrix.hpp:553
gnsstk::SparseMatrix::nrows
unsigned int nrows
dimensions of the "real" matrix (not the number of data stored)
Definition: SparseMatrix.hpp:664
gnsstk::inverseViaCholesky
SparseMatrix< T > inverseViaCholesky(const SparseMatrix< T > &A)
Definition: SparseMatrix.hpp:2277
gnsstk::SparseMatrix::isEmpty
bool isEmpty() const
is this SM empty? NB may have to call zeroize() to get a yes.
Definition: SparseMatrix.hpp:480
gnsstk::SparseMatrix::datasize
unsigned int datasize() const
datasize - number of non-zero data
Definition: SparseMatrix.hpp:469
gnsstk::SparseVector::isFilled
bool isFilled(const unsigned int i) const
true if the element is non-zero
Definition: SparseVector.hpp:426
gnsstk::Exception::addText
Exception & addText(const std::string &errorText)
Definition: Exception.cpp:133
GNSSTK_THROW
#define GNSSTK_THROW(exc)
Definition: Exception.hpp:366
gnsstk::operator-
SparseMatrix< T > operator-(const SparseMatrix< T > &L, const SparseMatrix< T > &R)
Matrix subtraction: SparseMatrix = SparseMatrix - SparseMatrix.
Definition: SparseMatrix.hpp:1451
Matrix.hpp
gnsstk::SMatProxy::operator=
SMatProxy & operator=(const SMatProxy< T > &rhs)
operator = for non-const (lvalue)
Definition: SparseMatrix.hpp:64
gnsstk::SparseMatrix::zeroize
void zeroize(const T tol=static_cast< T >(SparseVector< T >::zeroTolerance))
zeroize - remove elements that are less than tolerance in abs value
Definition: SparseMatrix.hpp:806
gnsstk::matrixTimesTranspose
SparseMatrix< T > matrixTimesTranspose(const SparseMatrix< T > &M)
Definition: SparseMatrix.hpp:1802
gnsstk::SparseMatrix::SparseMatrix
SparseMatrix()
empty constructor
Definition: SparseMatrix.hpp:436
gnsstk::inverse
SparseMatrix< T > inverse(const SparseMatrix< T > &A)
Definition: SparseMatrix.hpp:1890
gnsstk::SMatProxy::operator=
SMatProxy & operator=(T rhs)
operator = for const (rvalue)
Definition: SparseMatrix.hpp:70
gnsstk::SparseMatrix::dump
std::string dump(const int p=3, bool dosci=false) const
Dump only non-zero values, with indexes (i,value)
Definition: SparseMatrix.hpp:570
gnsstk::SparseMatrix::swapRows
void swapRows(const unsigned int &ii, const unsigned int &jj)
swap rows of this SparseMatrix
Definition: SparseMatrix.hpp:1713
gnsstk::SMatProxy::operator*=
SMatProxy & operator*=(T rhs)
operator*= for const (rvalue)
Definition: SparseMatrix.hpp:115
gnsstk::SparseMatrix::columnMap
std::map< unsigned int, std::vector< unsigned int > > columnMap() const
Definition: SparseMatrix.hpp:676
gnsstk::SparseMatrix::ncols
unsigned int ncols
Definition: SparseMatrix.hpp:664
gnsstk::SparseMatrix
Definition: SparseMatrix.hpp:53
gnsstk::SparseMatrix::clear
void clear()
clear - set all data to 0 (i.e. remove all data); leave dimensions alone
Definition: SparseMatrix.hpp:514
gnsstk::SparseMatrix::operator-=
SparseMatrix< T > & operator-=(const SparseMatrix< T > &SM)
Minimum element - return 0 if empty.
Definition: SparseMatrix.hpp:1393
gnsstk::SparseVector::len
unsigned int len
Definition: SparseVector.hpp:509


gnsstk
Author(s):
autogenerated on Wed Oct 25 2023 02:40:41