Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Friends | List of all members
gnsstk::SRIleastSquares Class Reference

Detailed Description

class SRIleastSquares inherits SRI and implements a general least squares algorithm using SRI, including weighted, linear or linearized, robust and/or sequential algorithms.

At any point the state X and covariance P are related to the SRI by X = inverse(R) * z , P = inverse(R) * inverse(transpose(R)), or R = upper triangular square root (Cholesky decomposition) of the inverse of P, and z = R * X.

Definition at line 71 of file SRIleastSquares.hpp.

#include <SRIleastSquares.hpp>

Inheritance diagram for gnsstk::SRIleastSquares:
Inheritance graph
[legend]

Public Types

using LSFFunc = void(*)(Vector< double > &X, Vector< double > &f, Matrix< double > &P)
 Function to fit. More...
 

Public Member Functions

double conditionNumber ()
 
double convergence ()
 
int dataUpdate (Vector< double > &D, Vector< double > &X, Matrix< double > &Cov, LSFFunc LSF)
 
bool isValid ()
 
int iterations ()
 
SRIleastSquaresoperator= (const SRIleastSquares &right)
 
void reset (const int N=0)
 
Vector< double > solution ()
 
 SRIleastSquares ()
 empty constructor More...
 
 SRIleastSquares (const Matrix< double > &R, const Vector< double > &Z, const Namelist &NL)
 
 SRIleastSquares (const Namelist &NL)
 
 SRIleastSquares (const SRIleastSquares &right)
 
 SRIleastSquares (const unsigned int N)
 
void zeroAll ()
 
- Public Member Functions inherited from gnsstk::SRI
void addAPriori (const Matrix< double > &Cov, const Vector< double > &X)
 
void addAPrioriInformation (const Matrix< double > &ICov, const Vector< double > &X)
 
SRIappend (const SRI &S)
 
void getConditionNumber (double &small, double &big) const
 
std::string getName (const unsigned int in) const
 
Namelist getNames () const
 
Matrix< double > getR () const
 
void getState (Vector< double > &X, int *ptrSingularIndex=NULL) const
 
void getStateAndCovariance (Vector< double > &X, Matrix< double > &C, double *ptrSmall=NULL, double *ptrBig=NULL) const
 
Vector< double > getZ () const
 
unsigned int index (std::string &name)
 
void measurementUpdate (Matrix< double > &Partials, Vector< double > &Data)
 
void measurementUpdate (SparseMatrix< double > &Partials, Vector< double > &Data)
 
void merge (const SRI &S)
 
SRIoperator+= (const Namelist &NL)
 
SRIoperator+= (const SRI &S)
 
SRIoperator= (const SRI &right)
 operator= More...
 
void permute (const Namelist &NL)
 
void Qbump (const unsigned int in, double q=0.0)
 
void reshape (const Namelist &NL)
 
void retriangularize (const Matrix< double > &A)
 
void retriangularize (Matrix< double > RR, Vector< double > ZZ)
 
void setFromCovState (const Matrix< double > &Cov, const Vector< double > &State, const Namelist &NL)
 
bool setName (const unsigned int in, const std::string &label)
 
void shift (const Vector< double > &X0)
 
void shiftZ (const Vector< double > &Z0)
 
unsigned int size () const
 
void split (const Namelist &NL, SRI &S)
 
 SRI ()
 empty constructor More...
 
 SRI (const Matrix< double > &R, const Vector< double > &Z, const Namelist &NL)
 
 SRI (const Namelist &NL)
 
 SRI (const SRI &s)
 copy constructor More...
 
 SRI (const unsigned int N)
 
void stateFix (const std::string &name, double value, double sigma, bool restore)
 
void stateFix (const unsigned int index, double value, double sigma, bool restore)
 
void stateFixAndRemove (const Namelist &drops, const Vector< double > &values)
 
void stateFixAndRemove (const unsigned int index, double value)
 
void transform (const Matrix< double > &invT, const Namelist &NL)
 
void zeroAll (const unsigned int n=0)
 
void zeroOne (const unsigned int n)
 
void zeroState ()
 Zero out (set all elements to zero) the state (Vector Z) only. More...
 

Public Attributes

double convergenceLimit
 limit on the RSS change in solution which produces success More...
 
double divergenceLimit
 upper limit on the RSS change in solution which produces an abort More...
 
bool doLinearize
 
bool doRobust
 
bool doSequential
 
bool doVerbose
 if true, output intermediate results More...
 
bool doWeight
 
int iterationsLimit
 limit on the number of iterations More...
 

Private Member Functions

void defaults ()
 initialization used by constructors - leastSquaresEstimation() only More...
 

Private Attributes

double conditionNum
 condition number, defined in inversion to get state and covariance More...
 
int numberBatches
 current number of batches seen More...
 
int numberIterations
 current number of iterations More...
 
double rmsConvergence
 RMS change in state, used for convergence test. More...
 
bool valid
 indicates if the filter is valid - set false when singular More...
 
Vector< double > Xsave
 solution X consistent with current information RX=z More...
 

Friends

std::ostream & operator<< (std::ostream &s, const SRIleastSquares &srif)
 output operator More...
 

Additional Inherited Members

- Protected Attributes inherited from gnsstk::SRI
Namelist names
 Namelist parallel to R and Z, labelling the elements of the state vector. More...
 
Matrix< double > R
 Information matrix, an upper triangular (square) matrix. More...
 
Vector< double > Z
 SRI state vector, of length equal to the dimension (row and col) of R. More...
 

Member Typedef Documentation

◆ LSFFunc

using gnsstk::SRIleastSquares::LSFFunc = void (*)(Vector<double>& X, Vector<double>& f, Matrix<double>& P)

Function to fit.

Definition at line 76 of file SRIleastSquares.hpp.

Constructor & Destructor Documentation

◆ SRIleastSquares() [1/5]

gnsstk::SRIleastSquares::SRIleastSquares ( )

empty constructor

Definition at line 61 of file SRIleastSquares.cpp.

◆ SRIleastSquares() [2/5]

gnsstk::SRIleastSquares::SRIleastSquares ( const unsigned int  N)

constructor given the dimension N.

Parameters
Ndimension of the SRIleastSquares.

Definition at line 65 of file SRIleastSquares.cpp.

◆ SRIleastSquares() [3/5]

gnsstk::SRIleastSquares::SRIleastSquares ( const Namelist NL)

constructor given a Namelist; its dimension determines the SRI dimension.

Parameters
NLNamelist for the SRIleastSquares.

Definition at line 75 of file SRIleastSquares.cpp.

◆ SRIleastSquares() [4/5]

gnsstk::SRIleastSquares::SRIleastSquares ( const Matrix< double > &  R,
const Vector< double > &  Z,
const Namelist NL 
)

explicit constructor - throw if the dimensions are inconsistent.

Parameters
RInitial information matrix, an upper triangular matrix of dim N.
ZInitial information data vector, of length N.
NLNamelist for the SRIleastSquares, also of length N.
Exceptions
MatrixExceptionif dimensions are not consistent.

Definition at line 89 of file SRIleastSquares.cpp.

◆ SRIleastSquares() [5/5]

gnsstk::SRIleastSquares::SRIleastSquares ( const SRIleastSquares right)
inline

copy constructor

Parameters
rightSRIleastSquares to be copied

Definition at line 108 of file SRIleastSquares.hpp.

Member Function Documentation

◆ conditionNumber()

double gnsstk::SRIleastSquares::conditionNumber ( )
inline

Get the condition number of the covariance matrix from last calls to leastSquaresEstimation() (Larger means 'closer to singular' except zero means condition number is infinite)

Definition at line 200 of file SRIleastSquares.hpp.

◆ convergence()

double gnsstk::SRIleastSquares::convergence ( )
inline

Get the convergence value found in last call to leastSquaresEstimation()

Returns
the convergence value

Definition at line 193 of file SRIleastSquares.hpp.

◆ dataUpdate()

int gnsstk::SRIleastSquares::dataUpdate ( Vector< double > &  D,
Vector< double > &  X,
Matrix< double > &  Cov,
LSFFunc  LSF 
)

A general least squares update, NOT the SRIF (Kalman) measurement update. Given data and measurement covariance, compute a solution and covariance using the appropriate least squares algorithm.

Parameters
DData vector, length M Input: raw data Output: post-fit residuals
XSolution vector, length N Input: nominal solution X0 (zero when doLinearized is false) Output: final solution
CovCovariance matrix, dimension (N,N) Input: (If doWeight is true) inverse measurement covariance or weight matrix(M,M) Output: Solution covariance matrix (N,N)
LSFPointer to a function which is used to define the equation to be solved. LSF arguments are: X Nominal solution (input) f Values of the equation f(X) (length M) (output) P Partials matrix df/dX evaluated at X (dimension M,N) (output) When doLinearize is false, LSF ignores X and returns the (constant) partials matrix P and zero for f(X).
Exceptions
MatrixExceptionif the input is inconsistent Return values: 0 ok -1 Problem is underdetermined (M<N) // TD – naturalized sol? -2 Problem is singular -3 Algorithm failed to converge -4 Algorithm diverged

Definition at line 271 of file SRIleastSquares.cpp.

◆ defaults()

void gnsstk::SRIleastSquares::defaults ( )
inlineprivate

initialization used by constructors - leastSquaresEstimation() only

Definition at line 243 of file SRIleastSquares.hpp.

◆ isValid()

bool gnsstk::SRIleastSquares::isValid ( )
inline

Return true if the solution is valid, i.e. if the problem is non-singular.

Definition at line 163 of file SRIleastSquares.hpp.

◆ iterations()

int gnsstk::SRIleastSquares::iterations ( )
inline

Get the number of iterations used in last call to leastSquaresEstimation()

Returns
the number of iterations

Definition at line 186 of file SRIleastSquares.hpp.

◆ operator=()

SRIleastSquares & gnsstk::SRIleastSquares::operator= ( const SRIleastSquares right)

operator=

Parameters
rightSRIleastSquares to be copied

Definition at line 111 of file SRIleastSquares.cpp.

◆ reset()

void gnsstk::SRIleastSquares::reset ( const int  N = 0)

reset the computation, i.e. remove all stored information, and optionally change the dimension. If N is not input, the dimension is not changed.

Parameters
Nnew SRIleastSquares dimension (optional).
Exceptions
Exception

Definition at line 628 of file SRIleastSquares.cpp.

◆ solution()

Vector<double> gnsstk::SRIleastSquares::solution ( )
inline

Get the current solution vector

Returns
current solution vector

Definition at line 179 of file SRIleastSquares.hpp.

◆ zeroAll()

void gnsstk::SRIleastSquares::zeroAll ( )

remove all stored information by setting the SRI to zero (does not re-dimension).

Definition at line 616 of file SRIleastSquares.cpp.

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream &  s,
const SRIleastSquares srif 
)
friend

output operator

Member Data Documentation

◆ conditionNum

double gnsstk::SRIleastSquares::conditionNum
private

condition number, defined in inversion to get state and covariance

Definition at line 282 of file SRIleastSquares.hpp.

◆ convergenceLimit

double gnsstk::SRIleastSquares::convergenceLimit

limit on the RSS change in solution which produces success

Definition at line 207 of file SRIleastSquares.hpp.

◆ divergenceLimit

double gnsstk::SRIleastSquares::divergenceLimit

upper limit on the RSS change in solution which produces an abort

Definition at line 210 of file SRIleastSquares.hpp.

◆ doLinearize

bool gnsstk::SRIleastSquares::doLinearize

if true, equation F(X)=D is non-linear, the algorithm will be iterated, and LSF must return partials matrix and F(X). - default is false

Definition at line 236 of file SRIleastSquares.hpp.

◆ doRobust

bool gnsstk::SRIleastSquares::doRobust

if true, weight the equation using robust statistical techniques

  • default is false (NB robust & sequential doesn't make much sense)

Definition at line 223 of file SRIleastSquares.hpp.

◆ doSequential

bool gnsstk::SRIleastSquares::doSequential

if true, save information for a sequential solution - default is false (NB robust & sequential doesn't make much sense)

Definition at line 229 of file SRIleastSquares.hpp.

◆ doVerbose

bool gnsstk::SRIleastSquares::doVerbose

if true, output intermediate results

Definition at line 239 of file SRIleastSquares.hpp.

◆ doWeight

bool gnsstk::SRIleastSquares::doWeight

if true, weight the equation using the inverse of covariance matrix on input - default is false

Definition at line 216 of file SRIleastSquares.hpp.

◆ iterationsLimit

int gnsstk::SRIleastSquares::iterationsLimit

limit on the number of iterations

Definition at line 204 of file SRIleastSquares.hpp.

◆ numberBatches

int gnsstk::SRIleastSquares::numberBatches
private

current number of batches seen

Definition at line 276 of file SRIleastSquares.hpp.

◆ numberIterations

int gnsstk::SRIleastSquares::numberIterations
private

current number of iterations

Definition at line 273 of file SRIleastSquares.hpp.

◆ rmsConvergence

double gnsstk::SRIleastSquares::rmsConvergence
private

RMS change in state, used for convergence test.

Definition at line 279 of file SRIleastSquares.hpp.

◆ valid

bool gnsstk::SRIleastSquares::valid
private

indicates if the filter is valid - set false when singular

Definition at line 270 of file SRIleastSquares.hpp.

◆ Xsave

Vector<double> gnsstk::SRIleastSquares::Xsave
private

solution X consistent with current information RX=z

Definition at line 285 of file SRIleastSquares.hpp.


The documentation for this class was generated from the following files:


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