SparseVector.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 //==============================================================================
38 
40 
41 #ifndef SPARSE_VECTOR_INCLUDE
42 #define SPARSE_VECTOR_INCLUDE
43 
44 #include "MathBase.hpp" // defines ABS SQRT
45 
46 #include <cstdlib>
47 
48 #include <algorithm> // for find,lower_bound
49 #include <map>
50 #include <sstream>
51 #include <string>
52 #include <vector>
53 
54 #include "Matrix.hpp"
55 #include "Vector.hpp"
56 
57 namespace gnsstk
58 {
60  template <class T> class SparseVector;
61  template <class T> class SparseMatrix;
62 
63  //---------------------------------------------------------------------------
68  template <class T> class SVecProxy
69  {
70  public:
72  SVecProxy(SparseVector<T>& SV, unsigned int index);
73 
76  {
77  assign(rhs);
78  return *this;
79  }
82  {
83  assign(rhs);
84  return *this;
85  }
86 
88  operator T() const;
89 
92  {
93  assign(value() + rhs);
94  return *this;
95  }
96 
99  {
100  assign(value() + rhs);
101  return *this;
102  }
103 
106  {
107  assign(value() - rhs);
108  return *this;
109  }
110 
113  {
114  assign(value() - rhs);
115  return *this;
116  }
117 
120  {
121  assign(value() * rhs);
122  return *this;
123  }
124 
127  {
128  assign(value() * rhs);
129  return *this;
130  }
131 
132  private:
135 
137  unsigned int index;
138 
140  T value() const;
141 
143  void assign(T rhs);
144 
145  }; // end class SVecProxy
146 
147  //---------------------------------------------------------------------------
148  //---------------------------------------------------------------------------
149  // must declare friends before the class
150  // output stream
151  template <class T>
152  std::ostream& operator<<(std::ostream& os, const SparseVector<T>& SV);
153  // operators
154  template <class T> T norm(const SparseVector<T>& SV);
155  template <class T>
156  T cosVec(const SparseVector<T>& S1, const SparseVector<T>& S2);
157  template <class T> T cosVec(const SparseVector<T>& SV, const Vector<T>& V);
158  template <class T> T cosVec(const Vector<T>& V, const SparseVector<T>& SV);
159  template <class T>
160  T dot(const SparseVector<T>& SL, const SparseVector<T>& SR);
161  template <class T>
162  T dot_lim(const SparseVector<T>& SL, const SparseVector<T>& SR,
163  const unsigned int kb, const unsigned int ke);
164  template <class T> T dot(const SparseVector<T>& SL, const Vector<T>& SR);
165  template <class T> T dot(const Vector<T>& SL, const SparseVector<T>& SR);
166  template <class T> T min(const SparseVector<T>& SV);
167  template <class T> T max(const SparseVector<T>& SV);
168  template <class T> T minabs(const SparseVector<T>& SV);
169  template <class T> T maxabs(const SparseVector<T>& SV);
170 
171  // TD? outer product - put in Matrix
172  // addition and subtraction
173  template <class T>
175  const SparseVector<T>& R);
176  template <class T>
178  template <class T>
180  template <class T>
182  const SparseVector<T>& R);
183  template <class T>
185  template <class T>
187  // SparseMatrix
188  template <class T> SparseMatrix<T> transpose(const SparseMatrix<T>& M);
192  template <class T>
194  const SparseMatrix<T>& C);
195  template <class T>
197  const SparseVector<T>& V);
198  template <class T>
200  template <class T>
202  const SparseMatrix<T>& R);
203  template <class T>
205  template <class T>
207  template <class T>
209  template <class T>
211  const SparseMatrix<T>& R);
215  template <class T> SparseMatrix<T> inverse(const SparseMatrix<T>& A);
216 
220  template <class T> SparseMatrix<T> lowerCholesky(const SparseMatrix<T>& A);
221 
225  template <class T>
226  SparseMatrix<T> inverseLT(const SparseMatrix<T>& LT, T *ptrSmall = NULL,
227  T *ptrBig = NULL);
228 
229  // special matrices
230  template <class T>
231  SparseMatrix<T> identSparse(const unsigned int dim);
232 
236  template <class T>
237  Vector<T> transformDiag(const SparseMatrix<T>& P, const Matrix<T>& C);
238 
242  template <class T>
244 
248  template <class T>
249  void SrifMU(Matrix<T>& R, Vector<T>& Z, SparseMatrix<T>& A,
250  const unsigned int M = 0);
251 
255  template <class T>
256  void SrifMU(Matrix<T>& R, Vector<T>& Z, SparseMatrix<T>& P, Vector<T>& D,
257  const unsigned int M = 0);
258 
259  //---------------------------------------------------------------------------
268  template <class T> class SparseVector
269  {
270  public:
272  friend class SVecProxy<T>;
273  friend class SparseMatrix<T>;
274 
276  // output stream operator
277  friend std::ostream& operator<<<T>(std::ostream& os,
278  const SparseVector<T>& S);
279  // operators: norm, cos, etc (dot is member)
280  friend T norm<T>(const SparseVector<T>& SV);
281  friend T cosVec<T>(const SparseVector<T>& S1, const SparseVector<T>& S2);
282  friend T cosVec<T>(const SparseVector<T>& SV, const Vector<T>& V);
283  friend T cosVec<T>(const Vector<T>& V, const SparseVector<T>& SV);
284  friend T dot<T>(const SparseVector<T>& SL, const SparseVector<T>& SR);
285  friend T dot_lim<T>(const SparseVector<T>& SL, const SparseVector<T>& SR,
286  const unsigned int kb, const unsigned int ke);
287  friend T dot<T>(const SparseVector<T>& SL, const Vector<T>& SR);
288  friend T dot<T>(const Vector<T>& SL, const SparseVector<T>& SR);
289  friend T min<T>(const SparseVector<T>& SV);
290  friend T max<T>(const SparseVector<T>& SV);
291  friend T minabs<T>(const SparseVector<T>& SV);
292  friend T maxabs<T>(const SparseVector<T>& SV);
293  // arithmetic
294  friend SparseVector<T> operator-
295  <T>(const SparseVector<T>& L, const SparseVector<T>& R);
296  friend SparseVector<T> operator-
297  <T>(const SparseVector<T>& L, const Vector<T>& R);
298  friend SparseVector<T> operator-
299  <T>(const Vector<T>& L, const SparseVector<T>& R);
300  friend SparseVector<T> operator+
301  <T>(const SparseVector<T>& L, const SparseVector<T>& R);
302  friend SparseVector<T> operator+
303  <T>(const SparseVector<T>& L, const Vector<T>& R);
304  friend SparseVector<T> operator+
305  <T>(const Vector<T>& L, const SparseVector<T>& R);
306  // SparseMatrix
307  friend SparseMatrix<T> transpose<T>(const SparseMatrix<T>& M);
308  friend SparseMatrix<T> transform<T>(const SparseMatrix<T>& M,
309  const SparseMatrix<T>& C);
310  friend SparseVector<T> operator*<T>(const SparseMatrix<T>& L,
311  const SparseVector<T>& V);
312  friend SparseVector<T> operator*<T>(const SparseMatrix<T>& L,
313  const Vector<T>& V);
314  friend SparseMatrix<T> operator*<T>(const SparseMatrix<T>& L,
315  const SparseMatrix<T>& V);
316  friend SparseMatrix<T> operator*<T>(const SparseMatrix<T>& L,
317  const Matrix<T>& R);
318  friend SparseMatrix<T> operator*<T>(const Matrix<T>& L,
319  const SparseMatrix<T>& R);
320  friend SparseMatrix<T> operator||
321  <T>(const SparseMatrix<T>& L, const Vector<T>& V);
322  friend SparseMatrix<T> operator||
323  <T>(const SparseMatrix<T>& L, const SparseMatrix<T>& R);
324  friend SparseMatrix<T> inverse<T>(const SparseMatrix<T>& A);
325  friend SparseMatrix<T> lowerCholesky<T>(const SparseMatrix<T>& A);
326  friend SparseMatrix<T> inverseLT<T>(const SparseMatrix<T>& LT,
327  T *ptrSmall, T *ptrBig);
328  // special matrices
329  friend SparseMatrix<T> identSparse<T>(const unsigned int dim);
330 
331  // diag of P * C * PT
332  friend Vector<T> transformDiag<T>(const SparseMatrix<T>& P,
333  const Matrix<T>& C);
334  // Householder
335  friend SparseMatrix<T> SparseHouseholder<T>(const SparseMatrix<T>& A);
336  friend void SrifMU<T>(Matrix<T>& R, Vector<T>& Z, SparseMatrix<T>& A,
337  const unsigned int M);
338  friend void SrifMU<T>(Matrix<T>& R, Vector<T>& Z, SparseMatrix<T>& P,
339  Vector<T>& D, const unsigned int M);
340 
345  static const double zeroTolerance;
346 
348  SparseVector() : len(0) {}
349 
351  SparseVector(const unsigned int N) : len(N) {}
352 
354  SparseVector(const Vector<T>& V);
355 
362  SparseVector(const SparseVector<T>& SV, const unsigned int& ind,
363  const unsigned int& len);
364 
365  // TD watch for unintended consequences - cast to Vector to use some
366  // Vector::fun
368  operator Vector<T>() const;
369 
371  inline unsigned int size() const { return len; }
372 
374  inline unsigned int datasize() const { return vecMap.size(); }
375 
377  inline bool isEmpty() const
378  {
379  return (vecMap.begin() == vecMap.end());
380  }
381 
383  inline double density() const
384  {
385  return (double(vecMap.size()) / double(len));
386  }
387 
392  inline void truncate(const unsigned int n)
393  {
394  if (n == 0)
395  {
396  vecMap.clear();
397  }
398  else if (n < len)
399  {
400  typename std::map<unsigned int, T>::iterator it;
401  // lower_bound returns it for first key >= newlen
402  it = vecMap.lower_bound(n);
403  vecMap.erase(it, vecMap.end());
404  }
405  }
406 
408  inline void resize(const unsigned int newlen)
409  {
410  truncate(newlen);
411  len = newlen;
412  }
413 
415  inline void clear() { vecMap.clear(); }
416 
423  void zeroize(const T tol = static_cast<T>(zeroTolerance));
424 
426  inline bool isFilled(const unsigned int i) const
427  {
428  return (vecMap.find(i) != vecMap.end());
429  }
430 
431  // operators ----------------------------------------------------
433  const SVecProxy<T> operator[](unsigned int in) const
434  {
435 #ifdef RANGECHECK
436  if (in >= len)
437  {
438  GNSSTK_THROW(Exception("index out of range"));
439  }
440 #endif
441  return SVecProxy<T>(const_cast<SparseVector &>(*this), in);
442  }
443 
445  SVecProxy<T> operator[](unsigned int in)
446  {
447 #ifdef RANGECHECK
448  if (in >= len)
449  {
450  GNSSTK_THROW(Exception("index out of range"));
451  }
452 #endif
453  return SVecProxy<T>(*this, in);
454  }
455 
456  // output -------------------------------------------------------
458  std::string dump(const int p = 3, bool dosci = false) const
459  {
460  std::ostringstream oss;
461  size_t i;
462  oss << "len=" << len << ", N=" << vecMap.size();
463  oss << (dosci ? std::scientific : std::fixed) << std::setprecision(p);
464  typename std::map<unsigned int, T>::const_iterator it = vecMap.begin();
465  for (; it != vecMap.end(); ++it)
466  oss << " " << it->first << "," << it->second; // << ")";
467  return oss.str();
468  }
469 
470  // operations ---------------------------------------------------
472  inline T sum(const SparseVector<T>& SV) const
473  {
474  T tot(0);
475  typename std::map<unsigned int, T>::iterator it = vecMap.begin();
476  for (; it != vecMap.end(); ++it)
477  tot += it->second;
478  return tot;
479  }
480 
481  // arithmetic and other operators
486  SparseVector<T>& operator*=(const T& value);
487  SparseVector<T>& operator/=(const T& value);
488  // special case for use with matrix inverse
489  void addScaledSparseVector(const T& a, const SparseVector<T>& SV);
490 
491  // unary minus
493  {
494  // std::cout << " SV unary minus with len " << len << std::endl;
495  SparseVector<T> toRet(*this);
496  typename std::map<unsigned int, T>::iterator it;
497  for (it = toRet.vecMap.begin(); it != toRet.vecMap.end(); ++it)
498  {
499  toRet.vecMap[it->first] = -toRet.vecMap[it->first];
500  }
501  return toRet;
502  }
503 
504  private:
509  unsigned int len;
510 
512  std::map<unsigned int, T> vecMap;
513 
518  inline std::vector<unsigned int> getIndexes() const
519  {
520  std::vector<unsigned int> vecind;
521  typename std::map<unsigned int, T>::const_iterator it;
522  for (it = vecMap.begin(); it != vecMap.end(); ++it)
523  vecind.push_back(it->first);
524  return vecind;
525  }
526 
527  }; // end class SparseVector
528 
529  //---------------------------------------------------------------------------
530  // implementation of SVecProxy
531  //---------------------------------------------------------------------------
532  // Default constructor
533  template <class T>
535  : mySV(sv), index(i)
536  {
537  }
538 
539  //---------------------------------------------------------------------------
540  // get the value of the SparseVector at index
541  template <class T> T SVecProxy<T>::value() const
542  {
543  typename std::map<unsigned int, T>::iterator it = mySV.vecMap.find(index);
544  if (it != mySV.vecMap.end())
545  {
546  return it->second;
547  }
548  return T(0);
549  }
550 
551  //---------------------------------------------------------------------------
552  // assignment, used by operator=, operator+=, etc
553  template <class T> void SVecProxy<T>::assign(T rhs)
554  {
555  // zero or default - remove from map
556  if (T(rhs) == T(0))
557  {
558  typename std::map<unsigned int, T>::iterator it =
559  mySV.vecMap.find(index);
560  if (it != mySV.vecMap.end())
561  {
562  mySV.vecMap.erase(it);
563  }
564  }
565 
566  // add/replace it in the map
567  else
568  {
569  (static_cast<std::map<unsigned int, T> &>(mySV.vecMap))[index] = rhs;
570  }
571  }
572 
573  //---------------------------------------------------------------------------
574  // cast
575  template <class T> SVecProxy<T>::operator T() const
576  {
577  typename std::map<unsigned int, T>::iterator it = mySV.vecMap.find(index);
578  if (it != mySV.vecMap.end())
579  {
580  return (*it).second;
581  }
582  else
583  {
584  return T(0);
585  }
586  }
587 
588  //---------------------------------------------------------------------------
589  // implementation of SparseVector
590  //---------------------------------------------------------------------------
591  // constructor from regular Vector<T>
592  template <class T> SparseVector<T>::SparseVector(const Vector<T>& V)
593  {
594  len = V.size();
595  for (unsigned int i = 0; i < len; i++)
596  {
597  if (V[i] == T(0))
598  {
599  continue;
600  }
601  // non-zero, must add it
602  vecMap[i] = V[i];
603  }
604  }
605 
606  // subvector constructor
607  // @param SV SparseVector to copy
608  // @param ind starting index for the copy
609  // @param n length of new SparseVector
610  template <class T>
612  const unsigned int& ind, const unsigned int& n)
613  {
614  if (ind + n > SV.len)
615  {
616  GNSSTK_THROW(Exception("Invalid input subvector c'tor - out of range"));
617  }
618  if (n == 0)
619  {
620  return;
621  }
622 
623  len = n;
624  typename std::map<unsigned int, T>::const_iterator it;
625  for (it = SV.vecMap.begin(); it != SV.vecMap.end(); ++it)
626  {
627  if (it->first < ind)
628  {
629  continue; // skip ones before ind
630  }
631  if (it->first > ind + n)
632  {
633  break;
634  }
635  vecMap[it->first - ind] = it->second;
636  }
637  }
638 
639  // cast to Vector<T>
640  template <class T> SparseVector<T>::operator Vector<T>() const
641  {
642  Vector<T> toRet(len, T(0));
643  typename std::map<unsigned int, T>::const_iterator it;
644  for (it = vecMap.begin(); it != vecMap.end(); ++it)
645  {
646  toRet(it->first) = it->second;
647  }
648 
649  return toRet;
650  }
651 
652  // zeroize - remove elements that are less than or equal to tolerance in abs
653  // value Called with a non-zero tolerance only by the user. NB this class and
654  // SparseMatrix call this when constructing a new object, e.g. after matrix
655  // multiply, but ONLY with the tolerance T(0).
656  template <class T> void SparseVector<T>::zeroize(const T tol)
657  {
658  std::vector<unsigned int> toDelete;
659  typename std::map<unsigned int, T>::iterator it;
660 
661  for (it = vecMap.begin(); it != vecMap.end(); ++it)
662  {
663  if (ABS(it->second) <= tol)
664  {
665  toDelete.push_back(it->first);
666  }
667  }
668 
669  for (unsigned int i = 0; i < toDelete.size(); i++)
670  vecMap.erase(toDelete[i]);
671  }
672 
673  // SparseVector stream output operator
674  template <class T>
675  std::ostream& operator<<(std::ostream& os, const SparseVector<T>& SV)
676  {
677  std::ofstream savefmt;
678  savefmt.copyfmt(os);
679 
680  unsigned int i; // the "real" vector index
681  typename std::map<unsigned int, T>::const_iterator it = SV.vecMap.begin();
682  for (i = 0; i < SV.len; i++)
683  {
684  if (i > 0)
685  {
686  os << std::setw(1) << ' ';
687  }
688  os.copyfmt(savefmt);
689  if (it != SV.vecMap.end() && i == it->first)
690  {
691  os << it->second;
692  ++it;
693  }
694  else
695  {
696  os << "0";
697  }
698  }
699 
700  return os;
701  }
702 
703  //---------------------------------------------------------------------------
704  // Norm = sqrt(sum(squares))
705  template <class T> T norm(const SparseVector<T>& SV)
706  {
707  typename std::map<unsigned int, T>::const_iterator it = SV.vecMap.begin();
708  if (it == SV.vecMap.end())
709  {
710  return T(0);
711  }
712 
713  T tn(ABS(it->second)); // cmath/cstdlib makes this valid for std types
714  for (; it != SV.vecMap.end(); ++it)
715  {
716  if (tn > ABS(it->second))
717  {
718  tn *= SQRT(T(1) + (it->second / tn) * (it->second / tn));
719  }
720  else if (tn < ABS(it->second))
721  {
722  tn = ABS(it->second) *
723  SQRT(T(1) + (tn / it->second) * (tn / it->second));
724  }
725  else
726  {
727  tn *= SQRT(T(2));
728  }
729  }
730  return tn;
731  }
732 
733  //---------------------------------------------------------------------------
734  // cosine of angle between two vectors
735  template <class T>
736  T cosVec(const SparseVector<T>& S1, const SparseVector<T>& S2)
737  {
738  T cv;
739  // try in case RANGECHECK is set
740  try
741  {
742  cv = S1.dot(S2);
743  }
744  catch (Exception& e)
745  {
746  GNSSTK_RETHROW(e);
747  }
748 
749  T norm1(norm(S1)), norm2(norm(S2));
750  if (norm1 == T(0) || norm2 == T(0))
751  {
752  GNSSTK_THROW(Exception("zero norm"));
753  }
754 
755  return ((cv / norm1) / norm2);
756  }
757 
758  template <class T> T cosVec(const SparseVector<T>& SV, const Vector<T>& V)
759  {
760  T cv;
761  // try in case RANGECHECK is set
762  try
763  {
764  cv = SV.dot(V);
765  }
766  catch (Exception& e)
767  {
768  GNSSTK_RETHROW(e);
769  }
770 
771  T norm1(norm(SV)), norm2(norm(V));
772  if (norm1 == T(0) || norm2 == T(0))
773  {
774  GNSSTK_THROW(Exception("zero norm"));
775  }
776 
777  return ((cv / norm1) / norm2);
778  }
779 
780  template <class T> T cosVec(const Vector<T>& V, const SparseVector<T>& SV)
781  {
782  return cosVec(SV, V);
783  }
784 
785  //---------------------------------------------------------------------------
786  // dot products
788  template <class T>
789  T dot(const SparseVector<T>& SL, const SparseVector<T>& SR)
790  {
791  if (SL.size() != SR.size())
792  {
793  GNSSTK_THROW(Exception("length mismatch"));
794  }
795  T value(0);
796  typename std::map<unsigned int, T>::const_iterator it = SL.vecMap.begin();
797  typename std::map<unsigned int, T>::const_iterator jt = SR.vecMap.begin();
798  while (it != SL.vecMap.end() && jt != SR.vecMap.end())
799  {
800  if (it->first > jt->first)
801  {
802  ++jt;
803  }
804  else if (jt->first > it->first)
805  {
806  ++it;
807  }
808  else
809  {
810  value += it->second * jt->second;
811  ++it;
812  ++jt;
813  }
814  }
815  return value;
816  }
817 
819  template <class T>
820  T dot_lim(const SparseVector<T>& SL, const SparseVector<T>& SR,
821  const unsigned int kb, const unsigned int ke)
822  {
823  if (SL.size() != SR.size())
824  {
825  GNSSTK_THROW(Exception("length mismatch"));
826  }
827  T value(0);
828  typename std::map<unsigned int, T>::const_iterator it = SL.vecMap.begin();
829  typename std::map<unsigned int, T>::const_iterator jt = SR.vecMap.begin();
830  while (it != SL.vecMap.end() && jt != SR.vecMap.end())
831  {
832  if (it->first >= ke || jt->first >= ke)
833  {
834  break;
835  }
836  if (it->first > jt->first || jt->first < kb)
837  {
838  ++jt;
839  }
840  else if (jt->first > it->first || it->first < kb)
841  {
842  ++it;
843  }
844  else
845  { // equal indexes: it->first == jt->first
846  if (it->first >= kb)
847  {
848  value += it->second * jt->second;
849  }
850  ++it;
851  ++jt;
852  }
853  }
854  return value;
855  }
856 
858  template <class T> T dot(const SparseVector<T>& SL, const Vector<T>& R)
859  {
860  if (SL.size() != R.size())
861  {
862  GNSSTK_THROW(Exception("length mismatch"));
863  }
864  T value(0);
865  typename std::map<unsigned int, T>::const_iterator it;
866  for (it = SL.vecMap.begin(); it != SL.vecMap.end(); ++it)
867  {
868  value += it->second * R[it->first];
869  }
870  return value;
871  }
872 
874  template <class T> T dot(const Vector<T>& L, const SparseVector<T>& SR)
875  {
876  return dot(SR, L);
877  }
878 
879  template <class T> T min(const SparseVector<T>& SV)
880  {
881  typename std::map<unsigned int, T>::const_iterator it = SV.vecMap.begin();
882  if (it == SV.vecMap.end())
883  {
884  return T(0);
885  }
886  T value(it->second);
887  for (++it; it != SV.vecMap.end(); ++it)
888  if (it->second < value)
889  {
890  value = it->second;
891  }
892  return value;
893  }
894 
895  template <class T> T max(const SparseVector<T>& SV)
896  {
897  typename std::map<unsigned int, T>::const_iterator it = SV.vecMap.begin();
898  if (it == SV.vecMap.end())
899  {
900  return T(0);
901  }
902  T value(it->second);
903  for (++it; it != SV.vecMap.end(); ++it)
904  if (it->second > value)
905  {
906  value = it->second;
907  }
908  return value;
909  }
910 
911  template <class T> T minabs(const SparseVector<T>& SV)
912  {
913  typename std::map<unsigned int, T>::const_iterator it = SV.vecMap.begin();
914  if (it == SV.vecMap.end())
915  {
916  return T(0);
917  }
918  T value(ABS(it->second));
919  for (++it; it != SV.vecMap.end(); ++it)
920  if (ABS(it->second) < value)
921  {
922  value = ABS(it->second);
923  }
924  return value;
925  }
926 
927  template <class T> T maxabs(const SparseVector<T>& SV)
928  {
929  typename std::map<unsigned int, T>::const_iterator it = SV.vecMap.begin();
930  if (it == SV.vecMap.end())
931  {
932  return T(0);
933  }
934  T value(ABS(it->second));
935  for (++it; it != SV.vecMap.end(); ++it)
936  if (ABS(it->second) > value)
937  {
938  value = ABS(it->second);
939  }
940  return value;
941  }
942 
943  //---------------------------------------------------------------------------
944  //---------------------------------------------------------------------------
945  // addition and subtraction
946  // member function operator-=(SparseVector)
947  template <class T>
949  {
950  if (len != R.size())
951  {
952  GNSSTK_THROW(Exception("Incompatible dimensions op-=(SV)"));
953  }
954 
955  typename std::map<unsigned int, T>::const_iterator Rit;
956  for (Rit = R.vecMap.begin(); Rit != R.vecMap.end(); ++Rit)
957  {
958  if (vecMap.find(Rit->first) == vecMap.end())
959  {
960  vecMap[Rit->first] = -Rit->second;
961  }
962  else
963  {
964  vecMap[Rit->first] -= Rit->second;
965  }
966  }
967  zeroize(T(0));
968 
969  return *this;
970  }
971 
972  // member function operator-=(Vector)
973  template <class T>
975  {
976  if (len != R.size())
977  {
978  GNSSTK_THROW(Exception("Incompatible dimensions op-=(V)"));
979  }
980 
981  for (unsigned int i = 0; i < R.size(); i++)
982  {
983  if (R[i] == T(0))
984  {
985  continue;
986  }
987 
988  if (vecMap.find(i) == vecMap.end())
989  {
990  vecMap[i] = -R[i];
991  }
992  else
993  {
994  vecMap[i] -= R[i];
995  }
996  }
997  zeroize(T(0));
998 
999  return *this;
1000  }
1001 
1002  // member function operator+=(SparseVector)
1003  template <class T>
1005  {
1006  if (len != R.size())
1007  {
1008  GNSSTK_THROW(Exception("Incompatible dimensions op+=(SV)"));
1009  }
1010 
1011  typename std::map<unsigned int, T>::const_iterator Rit;
1012  for (Rit = R.vecMap.begin(); Rit != R.vecMap.end(); ++Rit)
1013  {
1014  if (vecMap.find(Rit->first) == vecMap.end())
1015  {
1016  vecMap[Rit->first] = Rit->second;
1017  }
1018  else
1019  {
1020  vecMap[Rit->first] += Rit->second;
1021  }
1022  }
1023  zeroize(T(0));
1024 
1025  return *this;
1026  }
1027 
1028  // member function operator+=(Vector)
1029  template <class T>
1031  {
1032  if (len != R.size())
1033  {
1034  GNSSTK_THROW(Exception("Incompatible dimensions op+=(V)"));
1035  }
1036  // std::cout << " op+=(V)" << std::endl;
1037 
1038  for (unsigned int i = 0; i < R.size(); i++)
1039  {
1040  if (R[i] == T(0))
1041  {
1042  continue;
1043  }
1044 
1045  if (vecMap.find(i) == vecMap.end())
1046  {
1047  vecMap[i] = R[i];
1048  }
1049  else
1050  {
1051  vecMap[i] += R[i];
1052  }
1053  }
1054  zeroize(T(0));
1055 
1056  return *this;
1057  }
1058 
1059  // member function ~ op+=(a*SV)
1060  template <class T>
1062  const SparseVector<T>& R)
1063  {
1064  if (a == T(0))
1065  {
1066  return;
1067  }
1068  if (len != R.size())
1069  {
1070  GNSSTK_THROW(
1071  Exception("Incompatible dimensions addScaledSparseVector()"));
1072  }
1073 
1074  for (unsigned int i = 0; i < R.size(); i++)
1075  {
1076  if (R[i] == T(0))
1077  {
1078  continue;
1079  }
1080 
1081  if (vecMap.find(i) == vecMap.end())
1082  {
1083  vecMap[i] = a * R[i];
1084  }
1085  else
1086  {
1087  vecMap[i] += a * R[i];
1088  }
1089  }
1090  zeroize(T(0));
1091  }
1092 
1093  // member function operator*=(scalar)
1094  template <class T>
1096  {
1097  if (value == T(0))
1098  {
1099  resize(0);
1100  }
1101  else
1102  {
1103  typename std::map<unsigned int, T>::iterator it;
1104  for (it = vecMap.begin(); it != vecMap.end(); ++it)
1105  {
1106  it->second *= value;
1107  }
1108  }
1109 
1110  return *this;
1111  }
1112 
1113  // member function operator/=(scalar)
1114  template <class T>
1116  {
1117  if (value == T(0))
1118  {
1119  GNSSTK_THROW(Exception("Divide by zero"));
1120  }
1121 
1122  typename std::map<unsigned int, T>::iterator it;
1123  for (it = vecMap.begin(); it != vecMap.end(); ++it)
1124  {
1125  it->second /= value;
1126  }
1127 
1128  return *this;
1129  }
1130 
1131  // SparseVector = SparseVector - SparseVector
1132  template <class T>
1134  {
1135  if (L.size() != R.size())
1136  {
1137  GNSSTK_THROW(Exception("Incompatible dimensions op-(SV,SV)"));
1138  }
1139 
1140  // std::cout << "Call copy ctor from op-(SV,SV)" << std::endl;
1141  SparseVector<T> retSV(L);
1142  retSV -= R;
1143 
1144  return retSV;
1145  }
1146 
1147  // SparseVector = SparseVector - Vector
1148  template <class T>
1150  {
1151  if (L.size() != R.size())
1152  {
1153  GNSSTK_THROW(Exception("Incompatible dimensions op-(SV,V)"));
1154  }
1155  // std::cout << "Call copy ctor from op-(SV,V)" << std::endl;
1156 
1157  SparseVector<T> retSV(L);
1158  retSV -= R;
1159 
1160  return retSV;
1161  }
1162 
1163  // SparseVector = Vector - SparseVector
1164  template <class T>
1166  {
1167  if (L.size() != R.size())
1168  {
1169  GNSSTK_THROW(Exception("Incompatible dimensions op-(V,SV)"));
1170  }
1171  // std::cout << "Call copy ctor from op-(V,SV)" << std::endl;
1172 
1173  SparseVector<T> retSV(R);
1174  retSV = -retSV;
1175  retSV += L;
1176 
1177  return retSV;
1178  }
1179 
1180  // SparseVector = SparseVector + SparseVector
1181  template <class T>
1183  {
1184  if (L.size() != R.size())
1185  {
1186  GNSSTK_THROW(Exception("Incompatible dimensions op+(SV,SV)"));
1187  }
1188  // std::cout << "Call copy ctor from op+(SV,SV)" << std::endl;
1189 
1190  SparseVector<T> retSV(R);
1191  retSV += L;
1192 
1193  return retSV;
1194  }
1195 
1196  // SparseVector = SparseVector + Vector
1197  template <class T>
1199  {
1200  if (L.size() != R.size())
1201  {
1202  GNSSTK_THROW(Exception("Incompatible dimensions op+(SV,V)"));
1203  }
1204  // std::cout << "Call copy ctor from op+(SV,V)" << std::endl;
1205 
1206  SparseVector<T> retSV(L);
1207  retSV += R;
1208 
1209  return retSV;
1210  }
1211 
1212  // SparseVector = Vector + SparseVector
1213  template <class T>
1215  {
1216  if (L.size() != R.size())
1217  {
1218  GNSSTK_THROW(Exception("Incompatible dimensions op+(V,SV)"));
1219  }
1220  // std::cout << "Call copy ctor from op+(V,SV)" << std::endl;
1221 
1222  SparseVector<T> retSV(R);
1223  retSV += L;
1224 
1225  return retSV;
1226  }
1227 
1228 } // namespace gnsstk
1229 
1230 #endif // define SPARSE_VECTOR_INCLUDE
gnsstk::SparseVector
forward declarations
Definition: SparseVector.hpp:60
gnsstk::SVecProxy::operator-=
SVecProxy & operator-=(const SVecProxy< T > &rhs)
operator-= for non-const (lvalue)
Definition: SparseVector.hpp:105
gnsstk::SparseVector::SparseVector
SparseVector(const unsigned int N)
constructor with length
Definition: SparseVector.hpp:351
gnsstk::SVecProxy::value
T value() const
get the value of the SparseVector at index
Definition: SparseVector.hpp:541
gnsstk::lowerCholesky
SparseMatrix< T > lowerCholesky(const SparseMatrix< T > &A)
Definition: SparseMatrix.hpp:2065
gnsstk::SparseVector::density
double density() const
density - ratio of number of non-zero element to size()
Definition: SparseVector.hpp:383
SQRT
#define SQRT(x)
Definition: MathBase.hpp:74
gnsstk::SparseVector::addScaledSparseVector
void addScaledSparseVector(const T &a, const SparseVector< T > &SV)
Definition: SparseVector.hpp:1061
gnsstk::SparseVector::datasize
unsigned int datasize() const
datasize - number of non-zero data
Definition: SparseVector.hpp:374
gnsstk::SparseVector::SVecProxy< T >
friend class SVecProxy< T >
Proxy needs access to vecMap.
Definition: SparseVector.hpp:272
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::SparseVector::dot
friend T dot(const SparseVector< T > &SL, const SparseVector< T > &SR)
dot (SparseVector, SparseVector)
Definition: SparseVector.hpp:789
gnsstk::max
T max(const SparseMatrix< T > &SM)
Maximum element - return 0 if empty.
Definition: SparseMatrix.hpp:881
gnsstk::SparseVector::operator/=
SparseVector< T > & operator/=(const T &value)
Definition: SparseVector.hpp:1115
gnsstk::SVecProxy::operator=
SVecProxy & operator=(T rhs)
operator = for const (rvalue)
Definition: SparseVector.hpp:81
gnsstk::SVecProxy::operator-=
SVecProxy & operator-=(T rhs)
operator-= for const (rvalue)
Definition: SparseVector.hpp:112
gnsstk::identSparse
SparseMatrix< T > identSparse(const unsigned int dim)
Definition: SparseMatrix.hpp:1776
NULL
#define NULL
Definition: getopt1.c:64
gnsstk::SparseVector::operator*=
SparseVector< T > & operator*=(const T &value)
Definition: SparseVector.hpp:1095
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::SparseVector::zeroTolerance
static const double zeroTolerance
Definition: SparseVector.hpp:345
gnsstk::SVecProxy::operator=
SVecProxy & operator=(const SVecProxy< T > &rhs)
operator = for non-const (lvalue)
Definition: SparseVector.hpp:75
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::maxabs
T maxabs(const SparseMatrix< T > &SM)
Maximum absolute value - return 0 if empty.
Definition: SparseMatrix.hpp:927
gnsstk::SVecProxy::index
unsigned int index
index in mySV for this data
Definition: SparseVector.hpp:137
gnsstk::SVecProxy::SVecProxy
SVecProxy(SparseVector< T > &SV, unsigned int index)
constructor
Definition: SparseVector.hpp:534
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::transform
SparseMatrix< T > transform(const SparseMatrix< T > &M, const SparseMatrix< T > &C)
gnsstk::SrifMU
void SrifMU(Matrix< T > &R, Vector< T > &Z, SparseMatrix< T > &A, const unsigned int M)
Definition: SparseMatrix.hpp:2467
gnsstk::SVecProxy::assign
void assign(T rhs)
assign the SparseVector element, used by operator=,+=,etc
Definition: SparseVector.hpp:553
gnsstk::SparseVector::truncate
void truncate(const unsigned int n)
Definition: SparseVector.hpp:392
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::minabs
T minabs(const SparseMatrix< T > &SM)
Minimum absolute value - return 0 if empty.
Definition: SparseMatrix.hpp:904
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::SVecProxy::operator*=
SVecProxy & operator*=(const SVecProxy< T > &rhs)
operator*= for non-const (lvalue)
Definition: SparseVector.hpp:119
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::SparseVector::dump
std::string dump(const int p=3, bool dosci=false) const
Dump only non-zero values, with indexes (i,value)
Definition: SparseVector.hpp:458
gnsstk::SVecProxy::mySV
SparseVector< T > & mySV
reference to the vector to which this data belongs
Definition: SparseVector.hpp:134
gnsstk::SVecProxy::operator+=
SVecProxy & operator+=(T rhs)
operator+= for const (rvalue)
Definition: SparseVector.hpp:98
gnsstk::inverseLT
SparseMatrix< T > inverseLT(const SparseMatrix< T > &LT, T *ptrSmall, T *ptrBig)
Compute inverse of lower-triangular SparseMatrix.
Definition: SparseMatrix.hpp:2154
gnsstk::operator<<
std::ostream & operator<<(std::ostream &s, const ObsEpoch &oe) noexcept
Definition: ObsEpochMap.cpp:54
gnsstk::min
T min(const SparseMatrix< T > &SM)
Maximum element - return 0 if empty.
Definition: SparseMatrix.hpp:858
gnsstk::cosVec
T cosVec(const SparseVector< T > &S1, const SparseVector< T > &S2)
Definition: SparseVector.hpp:736
GNSSTK_RETHROW
#define GNSSTK_RETHROW(exc)
Definition: Exception.hpp:369
gnsstk::Vector
Definition: Vector.hpp:67
ABS
#define ABS(x)
Definition: MathBase.hpp:73
gnsstk::SparseVector::operator+=
SparseVector< T > & operator+=(const SparseVector< T > &SV)
Definition: SparseVector.hpp:1004
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::SparseVector::operator-=
SparseVector< T > & operator-=(const SparseVector< T > &SV)
Definition: SparseVector.hpp:948
gnsstk::SVecProxy::operator+=
SVecProxy & operator+=(const SVecProxy< T > &rhs)
operator+= for non-const (lvalue)
Definition: SparseVector.hpp:91
gnsstk::SVecProxy
Definition: SparseVector.hpp:68
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::SparseHouseholder
SparseMatrix< T > SparseHouseholder(const SparseMatrix< T > &A)
Householder transformation of a matrix.
Definition: SparseMatrix.hpp:2297
gnsstk::SparseVector::operator-
SparseVector< T > operator-() const
Definition: SparseVector.hpp:492
gnsstk::SparseVector::sum
T sum(const SparseVector< T > &SV) const
Sum of elements.
Definition: SparseVector.hpp:472
gnsstk::SparseVector::getIndexes
std::vector< unsigned int > getIndexes() const
Definition: SparseVector.hpp:518
gnsstk::SparseVector::isFilled
bool isFilled(const unsigned int i) const
true if the element is non-zero
Definition: SparseVector.hpp:426
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
gnsstk::norm
T norm(const SparseVector< T > &SV)
Definition: SparseVector.hpp:705
Matrix.hpp
gnsstk::inverse
SparseMatrix< T > inverse(const SparseMatrix< T > &A)
Definition: SparseMatrix.hpp:1890
MathBase.hpp
gnsstk::SVecProxy::operator*=
SVecProxy & operator*=(T rhs)
operator*= for const (rvalue)
Definition: SparseVector.hpp:126
gnsstk::SparseVector::operator[]
const SVecProxy< T > operator[](unsigned int in) const
operator[] for const, but SVecProxy does all the work
Definition: SparseVector.hpp:433
gnsstk::SparseVector::operator[]
SVecProxy< T > operator[](unsigned int in)
operator[] for non-const, but SVecProxy does all the work
Definition: SparseVector.hpp:445
gnsstk::SparseMatrix
Definition: SparseMatrix.hpp:53
Vector.hpp
gnsstk::SparseVector::SparseVector
SparseVector()
empty constructor
Definition: SparseVector.hpp:348
gnsstk::SparseVector::clear
void clear()
clear - set all data to 0 (i.e. remove all data); leave length alone
Definition: SparseVector.hpp:415
gnsstk::SparseVector::len
unsigned int len
Definition: SparseVector.hpp:509


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