SRI.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 
49 //------------------------------------------------------------------------------------
50 //------------------------------------------------------------------------------------
51 #ifndef CLASS_SQUAREROOTINFORMATION_INCLUDE
52 #define CLASS_SQUAREROOTINFORMATION_INCLUDE
53 
54 //------------------------------------------------------------------------------------
55 // system includes
56 #include <string>
57 // GNSSTk
58 #include "Matrix.hpp"
59 #include "StringUtils.hpp"
60 // geomatics
61 #include "Namelist.hpp"
62 #include "SRIMatrix.hpp"
63 #include "SparseMatrix.hpp"
64 
65 namespace gnsstk
66 {
67 
68  //---------------------------------------------------------------------------------
70  extern const Matrix<double> SRINullMatrix;
71 
73  extern const SparseMatrix<double> SRINullSparseMatrix;
74 
75  //---------------------------------------------------------------------------------
175  class SRI
176  {
177  public:
179  SRI() {}
180 
185  SRI(const unsigned int N);
186 
192  SRI(const Namelist& NL);
193 
202  SRI(const Matrix<double>& R, const Vector<double>& Z, const Namelist& NL);
203 
212  void setFromCovState(const Matrix<double>& Cov,
213  const Vector<double>& State, const Namelist& NL);
214 
216  SRI(const SRI& s);
217 
219  SRI& operator=(const SRI& right);
220 
221  // modify SRIs
222 
233  void permute(const Namelist& NL);
234 
250  void split(const Namelist& NL, SRI& S);
251 
260  SRI& operator+=(const Namelist& NL);
261 
269  void reshape(const Namelist& NL);
270 
278  void merge(const SRI& S) { *this += S; }
279 
287  SRI& operator+=(const SRI& S);
288 
296  friend SRI operator+(const SRI& Sleft, const SRI& Sright);
297 
310  SRI& append(const SRI& S);
311 
317  void zeroOne(const unsigned int n);
318 
325  void zeroAll(const unsigned int n = 0);
326 
328  void zeroState() { Z = 0.0; }
329 
336  void shift(const Vector<double>& X0);
337 
344  void shiftZ(const Vector<double>& Z0);
345 
354  void retriangularize(const Matrix<double>& A);
355 
366 
376  void transform(const Matrix<double>& invT, const Namelist& NL);
377 
391  void Qbump(const unsigned int in, double q = 0.0);
392 
403  void stateFix(const std::string& name, double value,
404  double sigma, bool restore);
405 
416  void stateFix(const unsigned int index, double value,
417  double sigma, bool restore);
418 
428  void stateFixAndRemove(const unsigned int index, double value);
429 
439  void stateFixAndRemove(const Namelist& drops,
440  const Vector<double>& values);
441 
450  void addAPriori(const Matrix<double>& Cov, const Vector<double>& X);
451 
460  void addAPrioriInformation(const Matrix<double>& ICov,
461  const Vector<double>& X);
462 
472  {
473  try
474  {
475  SrifMU(R, Z, Partials, Data);
476  }
477  catch (Exception& me)
478  {
479  GNSSTK_RETHROW(me);
480  }
481  }
482 
492  Vector<double>& Data)
493  {
494  try
495  {
496  SrifMU(R, Z, Partials, Data);
497  }
498  catch (MatrixException& me)
499  {
500  GNSSTK_RETHROW(me);
501  }
502  }
503 
513  void getConditionNumber(double& small, double& big) const;
514 
528  void getState(Vector<double>& X, int *ptrSingularIndex = NULL) const;
529 
546  double *ptrSmall = NULL,
547  double *ptrBig = NULL) const;
548 
549  // member access
554  unsigned int size() const { return R.rows(); }
555 
557  Namelist getNames() const { return names; }
558 
563  std::string getName(const unsigned int in) const
564  {
565  return names.getName(in);
566  }
567 
575  bool setName(const unsigned int in, const std::string& label)
576  {
577  return names.setName(in, label);
578  }
579 
584  unsigned int index(std::string& name)
585  {
586  return names.index(name);
587  }
588 
590  Matrix<double> getR() const { return R; }
591 
593  Vector<double> getZ() const { return Z; }
594 
596  friend std::ostream& operator<<(std::ostream& s, const SRI& );
597 
598  protected:
599  // member data
602 
605 
608 
609  }; // end class SRI
610 
611 } // end namespace gnsstk
612 
613 //------------------------------------------------------------------------------------
614 #endif
gnsstk::SRI::zeroAll
void zeroAll(const unsigned int n=0)
Definition: SRI.cpp:557
gnsstk::SRI::getConditionNumber
void getConditionNumber(double &small, double &big) const
Definition: SRI.cpp:1070
gnsstk::SRINullMatrix
const Matrix< double > SRINullMatrix
constant (empty) Matrix used for default input arguments
Definition: SRI.cpp:69
gnsstk::Namelist::index
int index(const std::string &name) const
Definition: Namelist.cpp:530
gnsstk::SRI::SRI
SRI()
empty constructor
Definition: SRI.hpp:179
gnsstk::SRI::reshape
void reshape(const Namelist &NL)
Definition: SRI.cpp:363
gnsstk::SRI::zeroState
void zeroState()
Zero out (set all elements to zero) the state (Vector Z) only.
Definition: SRI.hpp:328
gnsstk::SRI::operator<<
friend std::ostream & operator<<(std::ostream &s, const SRI &)
output operator
gnsstk::SRI::size
unsigned int size() const
Definition: SRI.hpp:554
gnsstk::SRI::measurementUpdate
void measurementUpdate(SparseMatrix< double > &Partials, Vector< double > &Data)
Definition: SRI.hpp:491
gnsstk::SRI::addAPriori
void addAPriori(const Matrix< double > &Cov, const Vector< double > &X)
Definition: SRI.cpp:1017
gnsstk::SRI::setName
bool setName(const unsigned int in, const std::string &label)
Definition: SRI.hpp:575
StringUtils.hpp
gnsstk::SRI::getName
std::string getName(const unsigned int in) const
Definition: SRI.hpp:563
gnsstk::SRI
Definition: SRI.hpp:175
gnsstk::SRI::getR
Matrix< double > getR() const
Definition: SRI.hpp:590
NULL
#define NULL
Definition: getopt1.c:64
gnsstk::Matrix::rows
size_t rows() const
The number of rows in the matrix.
Definition: Matrix.hpp:165
gnsstk::SRI::R
Matrix< double > R
Information matrix, an upper triangular (square) matrix.
Definition: SRI.hpp:601
gnsstk::SRI::zeroOne
void zeroOne(const unsigned int n)
Definition: SRI.cpp:540
gnsstk::SRI::Qbump
void Qbump(const unsigned int in, double q=0.0)
Definition: SRI.cpp:703
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::SRI::Z
Vector< double > Z
SRI state vector, of length equal to the dimension (row and col) of R.
Definition: SRI.hpp:604
gnsstk::Exception
Definition: Exception.hpp:151
gnsstk::SRI::index
unsigned int index(std::string &name)
Definition: SRI.hpp:584
gnsstk::SRI::permute
void permute(const Namelist &NL)
Definition: SRI.cpp:162
gnsstk::SrifMU
void SrifMU(Matrix< T > &R, Vector< T > &Z, SparseMatrix< T > &A, const unsigned int M)
Definition: SparseMatrix.hpp:2467
gnsstk::SRINullSparseMatrix
const SparseMatrix< double > SRINullSparseMatrix
constant (empty) SparseMatrix used for default input arguments
Definition: SRI.cpp:70
gnsstk::SRI::stateFix
void stateFix(const std::string &name, double value, double sigma, bool restore)
Definition: SRI.cpp:759
gnsstk::Matrix< double >
gnsstk::SRI::transform
void transform(const Matrix< double > &invT, const Namelist &NL)
Definition: SRI.cpp:670
gnsstk::SRI::operator=
SRI & operator=(const SRI &right)
operator=
Definition: SRI.cpp:149
gnsstk::Namelist::getName
std::string getName(const unsigned int in) const
Definition: Namelist.cpp:485
gnsstk::SRI::merge
void merge(const SRI &S)
Definition: SRI.hpp:278
gnsstk::SRI::names
Namelist names
Namelist parallel to R and Z, labelling the elements of the state vector.
Definition: SRI.hpp:607
GNSSTK_RETHROW
#define GNSSTK_RETHROW(exc)
Definition: Exception.hpp:369
gnsstk::Vector< double >
gnsstk::SRI::getZ
Vector< double > getZ() const
Definition: SRI.hpp:593
gnsstk::SRI::measurementUpdate
void measurementUpdate(Matrix< double > &Partials, Vector< double > &Data)
Definition: SRI.hpp:471
gnsstk::SRI::addAPrioriInformation
void addAPrioriInformation(const Matrix< double > &ICov, const Vector< double > &X)
Definition: SRI.cpp:1042
gnsstk::SRI::getNames
Namelist getNames() const
Definition: SRI.hpp:557
Namelist.hpp
gnsstk::SRI::shift
void shift(const Vector< double > &X0)
Definition: SRI.cpp:584
gnsstk::Namelist
Definition: Namelist.hpp:287
gnsstk::SRI::getState
void getState(Vector< double > &X, int *ptrSingularIndex=NULL) const
Definition: SRI.cpp:1097
Matrix.hpp
gnsstk::SRI::shiftZ
void shiftZ(const Vector< double > &Z0)
Definition: SRI.cpp:601
gnsstk::SRI::split
void split(const Namelist &NL, SRI &S)
Definition: SRI.cpp:261
SparseMatrix.hpp
gnsstk::SRI::setFromCovState
void setFromCovState(const Matrix< double > &Cov, const Vector< double > &State, const Namelist &NL)
Definition: SRI.cpp:119
gnsstk::SRI::append
SRI & append(const SRI &S)
Definition: SRI.cpp:399
gnsstk::SRI::stateFixAndRemove
void stateFixAndRemove(const unsigned int index, double value)
Definition: SRI.cpp:811
gnsstk::SparseMatrix
Definition: SparseMatrix.hpp:53
gnsstk::SRI::getStateAndCovariance
void getStateAndCovariance(Vector< double > &X, Matrix< double > &C, double *ptrSmall=NULL, double *ptrBig=NULL) const
Definition: SRI.cpp:1136
gnsstk::SRI::retriangularize
void retriangularize(const Matrix< double > &A)
Definition: SRI.cpp:620
gnsstk::SRI::operator+
friend SRI operator+(const SRI &Sleft, const SRI &Sright)
Definition: SRI.cpp:519
gnsstk::Namelist::setName
bool setName(const unsigned int in, const std::string &name)
Definition: Namelist.cpp:504
SRIMatrix.hpp
gnsstk::SRI::operator+=
SRI & operator+=(const Namelist &NL)
Definition: SRI.cpp:325


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