Classes | Public Types | Public Member Functions | Protected Types | Protected Attributes | Private Member Functions | List of all members
gnsstk::KalmanFilter Class Referenceabstract

Detailed Description

A base class for implementing Kalman filter using SRIFilter. Define a class with this class as base, implement some or all the virtual functions to define problem.

The derived class MUST overload: virtual int defineInitial() to define initial time and apriori state and cov. virtual int defineMeasurements() to define Partials, Data and MCov. virtual void defineTimestep() to define Phi, G, Rw and Control

The derived class MAY overload this function, which is called between updates, virtual int defineInterim() to output, change the state or anything else. This routine is called at four times: before the measurement update (MU), between the MU and the time update (TU), after the TU, between smoother updates (SU). If it returns >0 output() is called.

The derived class may want to overload the output() routine. The Update routines may be overloaded if necessary (but it shouldn't be).

Note that a "time" is used by the Kalman to index the data and determine how to time update (TU); this need not be a real time, however; it is ONLY required that 0. defineInitial(T0 ...) defines the starting value of T (NB also timeReverse)

  1. ForwardFilter(finalT,dt) defines ending value of T and nominalDT = dt
  2. defineMeasurements(T...) on input, T tells which data (epoch) to get
  3. defineMeasurements(T...) on output, T contains the time of the NEXT data epoch The actual value of T is used only a) it is printed in output(), and b) some implementations will use DT in the TU to compute process noise(s). Otherwise, T could be completely fictional.

How to use the derived class:

  1. Define all the 'define' functions; this constitutes the filter design.
  2. create the filter, using either empty c'tor and Reset(Namelist), or c'tor(NL)
  3. initialize the filter by calling initializeFilter() (calls defineInitial())
  4. call ForwardFilter(finalTime,dt); which increments time by dt and NTU (from 0), until time reaches finalTime. This routine is a loop over time; the loop consists of: KalmanInterim(), which calls defineInterim(1,...) KalmanMeasurementUpdate(), which calls defineMeasurements() to get current time, data, mcov, and partials NB. defineMeasurements() controls the time steps. KalmanInterim(), calling defineInterim(2,...) KalmanTimeUpdate(), which calls defineTimestep() to get Phi,Rw,G,Control KalmanInterim(), calling defineInterim(3,...)
    1. call BackwardFilter(M); this will smooth, starting at the current time down to NTU = M, it will decrement both time and NTU. This calls KalmanInterim(), calling defineInterim(4,...) NB. Smoothing knows nothing about time, but times stored during the forward filter are restored here for output purposes.

Several switches may be used to control the filter. For each there is also a 'set' routine.

  1. setDoOutput(false) turns off the output routine.
  2. setDoInvert(false) stops inversions (compute State and Cov from the SRI) and output during the forward filter. NB. cf. setSRISU for the backward filter.
  3. setSmoother(true) must be called before ForwardFilter() if BackwardFilter() is to be called. This causes the smoothing information to be stored during TUs.
  4. setSRISU(true) causes BackwardFilter() to use the SRIF form of the smoothing algorithm (which requires inversions); otherwise the DM form is used.
  5. setTimeReverse(true) to run in reverse time order.

Definition at line 136 of file KalmanFilter.hpp.

#include <KalmanFilter.hpp>

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

Classes

struct  Smoother_storage_record
 Storage for smoothing algorithm; stored by forward filter, used by SU. More...
 

Public Types

typedef enum gnsstk::KalmanFilter::FilterStageEnum FilterStage
 
enum  FilterStageEnum {
  Unknown = 0, Init, IB1, IB2,
  IB3, TU, MU, SU,
  StageCount
}
 
enum  KalmanMUReturnValuesEnum {
  Process = 0, ProcessThenQuit, SkipThisEpoch, SkipThenQuit,
  QuitImmediately, ReturnCount
}
 
typedef enum gnsstk::KalmanFilter::KalmanMUReturnValuesEnum KalmanReturn
 

Public Member Functions

void BackwardFilter (double M)
 
virtual void BackwardFilter (int M)
 
virtual int defineInitial (double &T0, gnsstk::Vector< double > &X, gnsstk::Matrix< double > &Cov)=0
 
virtual int defineInterim (int which, double Time)
 
virtual KalmanReturn defineMeasurements (double &T, const gnsstk::Vector< double > &X, const gnsstk::Matrix< double > &C, bool useFlag)=0
 
virtual void defineTimestep (double T, double DT, const gnsstk::Vector< double > &State, const gnsstk::Matrix< double > &Cov, bool useFlag)=0
 
virtual void ForwardFilter (double finalT, double DT)
 
gnsstk::Matrix< double > getCovariance ()
 get the covariance (must be non-singular) More...
 
bool getDoInvert ()
 if doInversions, SRIF is inverted at each step, defining State and Cov More...
 
bool getDoOutput ()
 if doOutput, output() is called at each step More...
 
gnsstk::Namelist getNames ()
 get the state namelist More...
 
int getNMU ()
 get number of measurements processed More...
 
gnsstk::SRI getSRI ()
 
gnsstk::Vector< double > getState ()
 get the state (must be non-singular) More...
 
std::string getTag ()
 KF tag is a user-defined string output on each line. More...
 
virtual void initializeFilter ()
 
bool isDryRun ()
 
bool isExtended ()
 if extended, use an extended Kalman (not implemented) More...
 
bool isSingular ()
 true when filter is singular More...
 
bool isSmoother ()
 
bool isSRISU ()
 
bool isTimeReversed ()
 
 KalmanFilter ()
 
 KalmanFilter (const gnsstk::Namelist &NL)
 
virtual int KalmanInterim (int which, double Time)
 
virtual KalmanReturn KalmanMeasurementUpdate (double &T)
 
virtual void KalmanSmootherUpdate ()
 
virtual void KalmanTimeUpdate (double T, double DT)
 
virtual void output (int N)
 
void Reset (const gnsstk::Namelist &NL)
 
void setDoInvert (bool on)
 
void setDoOutput (bool on)
 
void setDryRun (bool t=true)
 if dryRun, do not operate the filter, just print More...
 
void setExtended (bool ext)
 
void setSmoother (bool ext)
 if smoother, save info during forward filter for use by backward filter More...
 
void setSRI (gnsstk::SRI &sri)
 get the filter SRI More...
 
void setSRISU (bool ext)
 if doSRISU use SRIF form of smoother, else DM smoother More...
 
void setTag (std::string tag)
 
void setTimeReverse (bool tr=true)
 if timeReversed, time T decreases during the forward filter More...
 
virtual ~KalmanFilter ()
 destructor More...
 

Protected Types

typedef struct gnsstk::KalmanFilter::Smoother_storage_record SmootherStoreRec
 Storage for smoothing algorithm; stored by forward filter, used by SU. More...
 

Protected Attributes

double big
 
gnsstk::Vector< double > Control
 SRIF vector used internally. More...
 
gnsstk::Matrix< double > Cov
 filter covariance More...
 
gnsstk::Vector< double > Data
 vector defined by defineM() and used in MU More...
 
bool doInversions
 
bool doOutput
 if true, output at each stage using output() routine. NB used inside output() More...
 
bool doSRISU
 
bool dryRun
 
bool extended
 
gnsstk::Matrix< double > G
 SRIF matrix used internally - noise. More...
 
bool inverted
 if true then the SRI has been inverted and State and Cov are valid More...
 
std::string KFtag
 optional tag to put in output (2nd field) More...
 
gnsstk::Matrix< double > MCov
 measurement covariance (defineM() for MU) More...
 
int NMU
 count of measurement updates More...
 
int Nnoise
 Nnoise is there only for the user. More...
 
double nominalDT
 change in time for one TU seconds More...
 
int Nstate
 number of state elements More...
 
int NSU
 count of smoother updates More...
 
int NTU
 count of time updates: ++ in TU, – in SU More...
 
gnsstk::Matrix< double > Partials
 matrix defined by defineM() and used in MU More...
 
gnsstk::Vector< double > PFResid
 post-fit residuals - valid after MU More...
 
gnsstk::Matrix< double > PhiInv
 SRIF matrix used internally - inv state trans. More...
 
gnsstk::Matrix< double > Rw
 SRIF matrix used internally. More...
 
bool singular
 
double small
 condition number at last inversion = b/s More...
 
bool smoother
 
std::map< int, SmootherStoreRecSmootherStore
 
gnsstk::Vector< double > SMResid
 post-smoother residuals - value after SU More...
 
gnsstk::SRIFilter srif
 SRIF. More...
 
FilterStage stage
 current stage of the filter - see enum More...
 
gnsstk::Vector< double > State
 filter state More...
 
double time
 seconds since start More...
 
bool timeReversed
 if true then independent variable "time" decreases More...
 
gnsstk::Vector< double > Zw
 SRIF vector used internally. More...
 

Private Member Functions

void initialize (const gnsstk::Namelist &NL)
 
void Invert (const std::string &msg=std::string())
 

Member Typedef Documentation

◆ FilterStage

◆ KalmanReturn

◆ SmootherStoreRec

Storage for smoothing algorithm; stored by forward filter, used by SU.

Member Enumeration Documentation

◆ FilterStageEnum

Enumerator
Unknown 
Init 
IB1 
IB2 
IB3 
TU 
MU 
SU 
StageCount 

Definition at line 140 of file KalmanFilter.hpp.

◆ KalmanMUReturnValuesEnum

Enumerator
Process 
ProcessThenQuit 
SkipThisEpoch 
SkipThenQuit 
QuitImmediately 
ReturnCount 

Definition at line 154 of file KalmanFilter.hpp.

Constructor & Destructor Documentation

◆ KalmanFilter() [1/2]

gnsstk::KalmanFilter::KalmanFilter ( )
inline
  1. create the filter, using either the empty c'tor followed by Reset(Namelist), or the c'tor(Namelist), giving an initial Namelist for the filter state. empty constructor; Reset() must be called before initializing or filtering

Definition at line 336 of file KalmanFilter.hpp.

◆ KalmanFilter() [2/2]

gnsstk::KalmanFilter::KalmanFilter ( const gnsstk::Namelist NL)
inline

Constructor given an initial Namelist for the filter state

Parameters
NLNamelist of the filter states (determines Nstate)

Definition at line 348 of file KalmanFilter.hpp.

◆ ~KalmanFilter()

virtual gnsstk::KalmanFilter::~KalmanFilter ( )
inlinevirtual

destructor

Definition at line 357 of file KalmanFilter.hpp.

Member Function Documentation

◆ BackwardFilter() [1/2]

void gnsstk::KalmanFilter::BackwardFilter ( double  M)
inline

Backward filter (smoother) with double argument - this is a trick to prevent the user from calling BackwardFilter(time).

Definition at line 563 of file KalmanFilter.hpp.

◆ BackwardFilter() [2/2]

virtual void gnsstk::KalmanFilter::BackwardFilter ( int  M)
inlinevirtual

Backward filter or smoother. Smooth down to NTU==M. Decrements time and NTU Calls defineInterim(4,time) after each smoother update

Parameters
Mvalue of NTU at which to stop the smoother (usually 0)

Definition at line 575 of file KalmanFilter.hpp.

◆ defineInitial()

virtual int gnsstk::KalmanFilter::defineInitial ( double &  T0,
gnsstk::Vector< double > &  X,
gnsstk::Matrix< double > &  Cov 
)
pure virtual

Pure virtual function, to be overloaded and provided by the caller, providing complete apriori information, including initial time T0, and either {state vector X, and covariance Cov} (return 1) or the inverse {inverse covariance*state X, and inverse covariance Cov} (return -1) or no (zero) information (return 0). If non-0 is returned, the matrix must be non-singular. Note that the SRIF was zero-ed by either the constructor or Reset() just before this call, so if no information is added, doInversions should be false.

Parameters
T0initial time
Xinitial state/inv(cov)*state/ignored as return 1/-1/0
Covinitial covariance/inv(cov)/ignored as return 1/-1/0
Returns
1 for state/cov, -1 for information, 0 for nothing provided

Implemented in gnsstk::WNJfilter.

◆ defineInterim()

virtual int gnsstk::KalmanFilter::defineInterim ( int  which,
double  Time 
)
inlinevirtual

Pure virtual function, to be overloaded and provided by the caller, providing This routine is called three times within the ForwardFilter loop: before MU, between MU and TU, and after TU, and once during the BackwardFilter between SUs.

Parameters
which= 1(before MU), 2(between MU and TU), 3(after TU), 4(after SU)
Returns
-1 if this epoch is to be skipped, otherwise return >= 0.

Definition at line 328 of file KalmanFilter.hpp.

◆ defineMeasurements()

virtual KalmanReturn gnsstk::KalmanFilter::defineMeasurements ( double &  T,
const gnsstk::Vector< double > &  X,
const gnsstk::Matrix< double > &  C,
bool  useFlag 
)
pure virtual

Pure virtual function, to be overloaded and provided by the caller, providing members Partials, Data and MCov (M. Covariance) at next data epoch time T. The current time T is passed into this routine; it should redefine T to be the time of the next data epoch. Generally, if T(next) > T(curr) + nominalDT, this routine should return Skip(2) (data will not be used) and save the data until T(next) ~<= T(curr) + DT. if useFlag=false, State and Cov should NOT be used as they may be singular.

Parameters
[in]Tcurrent time, on output time of NEXT set of data
[in]Xcurrent state
[in]Ccurrent covariance
[in]useFlagif false, State and Cov are singular - do not use
Returns
Process (0) process the data, ProcessThenQuit (1) process this data, but then quit SkipThisEpoch (2) skip both this data and output, but don't quit SkipThenQuit (3) skip data and output, and quit QuitImmediately (4) quit immediately without processing or output

Implemented in gnsstk::WNJfilter.

◆ defineTimestep()

virtual void gnsstk::KalmanFilter::defineTimestep ( double  T,
double  DT,
const gnsstk::Vector< double > &  State,
const gnsstk::Matrix< double > &  Cov,
bool  useFlag 
)
pure virtual

Pure virtual function, to be overloaded and provided by the caller, providing members PhiInv,G,Rw,Control, given T,DT,X,Cov at each timestep. if useFlag=false, State and Cov should NOT be used ... may be singular

Parameters
[in]Tcurrent time
[in]DTcurrent timestep
[in]Statecurrent state
[in]Covcurrent covariance
[in]useFlagif false, State and Cov are singular - do not use

Implemented in gnsstk::WNJfilter.

◆ ForwardFilter()

virtual void gnsstk::KalmanFilter::ForwardFilter ( double  finalT,
double  DT 
)
inlinevirtual
  1. forward filter(finalTime,nominalDT). This is main routine; it runs the filter forward to finalTime, using timesteps nominalDT (NB the defineMeasurements() routine controls actual timesteps). This calls defineTimestep() to get propagation matricies at each timestep. It calls defineMeasurements() to get time of the next data, data, mcov, and partials at each timestep. Timing is controlled by defineMeasurements(). It calls defineInterim 3 times, before MU, between MU and TU, and after TU.
    Parameters
    finalTtime at which to stop the filter
    DTnominal timestep

Definition at line 433 of file KalmanFilter.hpp.

◆ getCovariance()

gnsstk::Matrix<double> gnsstk::KalmanFilter::getCovariance ( )
inline

get the covariance (must be non-singular)

Definition at line 952 of file KalmanFilter.hpp.

◆ getDoInvert()

bool gnsstk::KalmanFilter::getDoInvert ( )
inline

if doInversions, SRIF is inverted at each step, defining State and Cov

Definition at line 906 of file KalmanFilter.hpp.

◆ getDoOutput()

bool gnsstk::KalmanFilter::getDoOutput ( )
inline

if doOutput, output() is called at each step

Definition at line 910 of file KalmanFilter.hpp.

◆ getNames()

gnsstk::Namelist gnsstk::KalmanFilter::getNames ( )
inline

get the state namelist

Definition at line 948 of file KalmanFilter.hpp.

◆ getNMU()

int gnsstk::KalmanFilter::getNMU ( )
inline

get number of measurements processed

Definition at line 955 of file KalmanFilter.hpp.

◆ getSRI()

gnsstk::SRI gnsstk::KalmanFilter::getSRI ( )
inline

Definition at line 945 of file KalmanFilter.hpp.

◆ getState()

gnsstk::Vector<double> gnsstk::KalmanFilter::getState ( )
inline

get the state (must be non-singular)

Definition at line 950 of file KalmanFilter.hpp.

◆ getTag()

std::string gnsstk::KalmanFilter::getTag ( )
inline

KF tag is a user-defined string output on each line.

Definition at line 937 of file KalmanFilter.hpp.

◆ initialize()

void gnsstk::KalmanFilter::initialize ( const gnsstk::Namelist NL)
inlineprivate

for internal use in constructors and by Reset. Create SRIF and initialize counters and stores

Definition at line 963 of file KalmanFilter.hpp.

◆ initializeFilter()

virtual void gnsstk::KalmanFilter::initializeFilter ( )
inlinevirtual
  1. initialize the filter; this calls defineInitial() to get the apriori state and covariance (or information)

Definition at line 363 of file KalmanFilter.hpp.

◆ Invert()

void gnsstk::KalmanFilter::Invert ( const std::string &  msg = std::string())
inlineprivate

For internal use to invert the SRIF to get State and Covariance

Definition at line 983 of file KalmanFilter.hpp.

◆ isDryRun()

bool gnsstk::KalmanFilter::isDryRun ( )
inline

Definition at line 934 of file KalmanFilter.hpp.

◆ isExtended()

bool gnsstk::KalmanFilter::isExtended ( )
inline

if extended, use an extended Kalman (not implemented)

Definition at line 914 of file KalmanFilter.hpp.

◆ isSingular()

bool gnsstk::KalmanFilter::isSingular ( )
inline

true when filter is singular

Definition at line 926 of file KalmanFilter.hpp.

◆ isSmoother()

bool gnsstk::KalmanFilter::isSmoother ( )
inline

Definition at line 919 of file KalmanFilter.hpp.

◆ isSRISU()

bool gnsstk::KalmanFilter::isSRISU ( )
inline

Definition at line 923 of file KalmanFilter.hpp.

◆ isTimeReversed()

bool gnsstk::KalmanFilter::isTimeReversed ( )
inline

Definition at line 930 of file KalmanFilter.hpp.

◆ KalmanInterim()

virtual int gnsstk::KalmanFilter::KalmanInterim ( int  which,
double  Time 
)
inlinevirtual

Interim processing.

Returns
defineInterim(), if >0 output() is called, ignored after SU

Definition at line 712 of file KalmanFilter.hpp.

◆ KalmanMeasurementUpdate()

virtual KalmanReturn gnsstk::KalmanFilter::KalmanMeasurementUpdate ( double &  T)
inlinevirtual

Perform the measurement update;

Parameters
[in,out]Tcurrent time(input), time of NEXT data(output)
Returns
Process=0, ProcessThenQuit, quit after this data SkipThisEpoch, skip this data and output SkipThenQuit, skip this data and output, then quit QuitImmediately, quit now

Definition at line 739 of file KalmanFilter.hpp.

◆ KalmanSmootherUpdate()

virtual void gnsstk::KalmanFilter::KalmanSmootherUpdate ( )
inlinevirtual

the smoother update

Definition at line 846 of file KalmanFilter.hpp.

◆ KalmanTimeUpdate()

virtual void gnsstk::KalmanFilter::KalmanTimeUpdate ( double  T,
double  DT 
)
inlinevirtual

the Kalman time update

Parameters
[in]Tcurrent time
[in]DTcurrent timestep

Definition at line 783 of file KalmanFilter.hpp.

◆ output()

virtual void gnsstk::KalmanFilter::output ( int  N)
inlinevirtual

Output at each stage ... the user may override if singular is true, State and Cov may or may not be good

Parameters
Nuser-defined counter that is included on each line after the tag.

Reimplemented in gnsstk::WNJfilter.

Definition at line 632 of file KalmanFilter.hpp.

◆ Reset()

void gnsstk::KalmanFilter::Reset ( const gnsstk::Namelist NL)
inline

Reset or recreate filter - use this after the empty constructor

Parameters
NLNamelist of the filter states (determines Nstate)

Definition at line 354 of file KalmanFilter.hpp.

◆ setDoInvert()

void gnsstk::KalmanFilter::setDoInvert ( bool  on)
inline

Definition at line 907 of file KalmanFilter.hpp.

◆ setDoOutput()

void gnsstk::KalmanFilter::setDoOutput ( bool  on)
inline

Definition at line 911 of file KalmanFilter.hpp.

◆ setDryRun()

void gnsstk::KalmanFilter::setDryRun ( bool  t = true)
inline

if dryRun, do not operate the filter, just print

Definition at line 933 of file KalmanFilter.hpp.

◆ setExtended()

void gnsstk::KalmanFilter::setExtended ( bool  ext)
inline

Definition at line 915 of file KalmanFilter.hpp.

◆ setSmoother()

void gnsstk::KalmanFilter::setSmoother ( bool  ext)
inline

if smoother, save info during forward filter for use by backward filter

Definition at line 918 of file KalmanFilter.hpp.

◆ setSRI()

void gnsstk::KalmanFilter::setSRI ( gnsstk::SRI sri)
inline

get the filter SRI

Definition at line 941 of file KalmanFilter.hpp.

◆ setSRISU()

void gnsstk::KalmanFilter::setSRISU ( bool  ext)
inline

if doSRISU use SRIF form of smoother, else DM smoother

Definition at line 922 of file KalmanFilter.hpp.

◆ setTag()

void gnsstk::KalmanFilter::setTag ( std::string  tag)
inline

Definition at line 938 of file KalmanFilter.hpp.

◆ setTimeReverse()

void gnsstk::KalmanFilter::setTimeReverse ( bool  tr = true)
inline

if timeReversed, time T decreases during the forward filter

Definition at line 929 of file KalmanFilter.hpp.

Member Data Documentation

◆ big

double gnsstk::KalmanFilter::big
protected

Definition at line 217 of file KalmanFilter.hpp.

◆ Control

gnsstk::Vector<double> gnsstk::KalmanFilter::Control
protected

SRIF vector used internally.

Definition at line 232 of file KalmanFilter.hpp.

◆ Cov

gnsstk::Matrix<double> gnsstk::KalmanFilter::Cov
protected

filter covariance

Definition at line 221 of file KalmanFilter.hpp.

◆ Data

gnsstk::Vector<double> gnsstk::KalmanFilter::Data
protected

vector defined by defineM() and used in MU

Definition at line 228 of file KalmanFilter.hpp.

◆ doInversions

bool gnsstk::KalmanFilter::doInversions
protected

if true, invert the SRIF to get State and Covariance whenever SRIF changes. In general it is wise to set this false, then reset to true only when the State is to be used. For example if you need the State Vector in the MU, then set doInversions=true in defineIntermin(1), then set to false in defineM. Inversions are called between all the define...() calls.

Definition at line 177 of file KalmanFilter.hpp.

◆ doOutput

bool gnsstk::KalmanFilter::doOutput
protected

if true, output at each stage using output() routine. NB used inside output()

Definition at line 168 of file KalmanFilter.hpp.

◆ doSRISU

bool gnsstk::KalmanFilter::doSRISU
protected

if true use the SRIF form of the smoother update in the backward filter

Definition at line 187 of file KalmanFilter.hpp.

◆ dryRun

bool gnsstk::KalmanFilter::dryRun
protected

if true, do a "dry run" calling all user-defined func, but none of the SRIF

Definition at line 206 of file KalmanFilter.hpp.

◆ extended

bool gnsstk::KalmanFilter::extended
protected

if true the filter is considered extended; this will zero the state before MU

Definition at line 192 of file KalmanFilter.hpp.

◆ G

gnsstk::Matrix<double> gnsstk::KalmanFilter::G
protected

SRIF matrix used internally - noise.

Definition at line 235 of file KalmanFilter.hpp.

◆ inverted

bool gnsstk::KalmanFilter::inverted
protected

if true then the SRI has been inverted and State and Cov are valid

Definition at line 199 of file KalmanFilter.hpp.

◆ KFtag

std::string gnsstk::KalmanFilter::KFtag
protected

optional tag to put in output (2nd field)

Definition at line 218 of file KalmanFilter.hpp.

◆ MCov

gnsstk::Matrix<double> gnsstk::KalmanFilter::MCov
protected

measurement covariance (defineM() for MU)

Definition at line 229 of file KalmanFilter.hpp.

◆ NMU

int gnsstk::KalmanFilter::NMU
protected

count of measurement updates

Definition at line 209 of file KalmanFilter.hpp.

◆ Nnoise

int gnsstk::KalmanFilter::Nnoise
protected

Nnoise is there only for the user.

Definition at line 212 of file KalmanFilter.hpp.

◆ nominalDT

double gnsstk::KalmanFilter::nominalDT
protected

change in time for one TU seconds

Definition at line 216 of file KalmanFilter.hpp.

◆ Nstate

int gnsstk::KalmanFilter::Nstate
protected

number of state elements

Definition at line 211 of file KalmanFilter.hpp.

◆ NSU

int gnsstk::KalmanFilter::NSU
protected

count of smoother updates

Definition at line 210 of file KalmanFilter.hpp.

◆ NTU

int gnsstk::KalmanFilter::NTU
protected

count of time updates: ++ in TU, – in SU

Definition at line 208 of file KalmanFilter.hpp.

◆ Partials

gnsstk::Matrix<double> gnsstk::KalmanFilter::Partials
protected

matrix defined by defineM() and used in MU

Definition at line 226 of file KalmanFilter.hpp.

◆ PFResid

gnsstk::Vector<double> gnsstk::KalmanFilter::PFResid
protected

post-fit residuals - valid after MU

Definition at line 224 of file KalmanFilter.hpp.

◆ PhiInv

gnsstk::Matrix<double> gnsstk::KalmanFilter::PhiInv
protected

SRIF matrix used internally - inv state trans.

Definition at line 234 of file KalmanFilter.hpp.

◆ Rw

gnsstk::Matrix<double> gnsstk::KalmanFilter::Rw
protected

SRIF matrix used internally.

Definition at line 236 of file KalmanFilter.hpp.

◆ singular

bool gnsstk::KalmanFilter::singular
protected

if true then the SRIF is currently singular (not a problem unless doInversions)

Definition at line 182 of file KalmanFilter.hpp.

◆ small

double gnsstk::KalmanFilter::small
protected

condition number at last inversion = b/s

Definition at line 217 of file KalmanFilter.hpp.

◆ smoother

bool gnsstk::KalmanFilter::smoother
protected

if true the forward filter will save the data needed by the backward filter

Definition at line 197 of file KalmanFilter.hpp.

◆ SmootherStore

std::map<int, SmootherStoreRec> gnsstk::KalmanFilter::SmootherStore
protected

Definition at line 252 of file KalmanFilter.hpp.

◆ SMResid

gnsstk::Vector<double> gnsstk::KalmanFilter::SMResid
protected

post-smoother residuals - value after SU

Definition at line 239 of file KalmanFilter.hpp.

◆ srif

gnsstk::SRIFilter gnsstk::KalmanFilter::srif
protected

SRIF.

Definition at line 222 of file KalmanFilter.hpp.

◆ stage

FilterStage gnsstk::KalmanFilter::stage
protected

current stage of the filter - see enum

Definition at line 214 of file KalmanFilter.hpp.

◆ State

gnsstk::Vector<double> gnsstk::KalmanFilter::State
protected

filter state

Definition at line 220 of file KalmanFilter.hpp.

◆ time

double gnsstk::KalmanFilter::time
protected

seconds since start

Definition at line 215 of file KalmanFilter.hpp.

◆ timeReversed

bool gnsstk::KalmanFilter::timeReversed
protected

if true then independent variable "time" decreases

Definition at line 201 of file KalmanFilter.hpp.

◆ Zw

gnsstk::Vector<double> gnsstk::KalmanFilter::Zw
protected

SRIF vector used internally.

Definition at line 231 of file KalmanFilter.hpp.


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


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