Definition at line 61 of file WNJfilter.hpp.
#include <WNJfilter.hpp>

Public Member Functions | |
| int | defineInitial (double &T0, gnsstk::Vector< double > &State, gnsstk::Matrix< double > &Cov) |
| KalmanReturn | defineMeasurements (double &T, const gnsstk::Vector< double > &X, const gnsstk::Matrix< double > &Cov, bool useFlag) |
| void | defineTimestep (double T, double DT, const gnsstk::Vector< double > &State, const gnsstk::Matrix< double > &Cov, bool useFlag) |
| virtual void | output (int N) |
| void | Reset (int dim) |
| WNJfilter () | |
| WNJfilter (int dim) | |
Public Member Functions inherited from gnsstk::KalmanFilter | |
| void | BackwardFilter (double M) |
| virtual void | BackwardFilter (int M) |
| virtual int | defineInterim (int which, double Time) |
| 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) |
| 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... | |
Public Attributes | |
| gnsstk::Vector< double > | apNoise |
| gnsstk::Vector< double > | apState |
| int | count |
| std::vector< double > | data |
| bool | filterOutput |
| std::vector< double > | msig |
| unsigned int | prec |
| std::vector< double > | psig |
| std::vector< double > * | ptra |
| std::vector< double > * | ptrs |
| std::vector< double > * | ptrv |
| std::vector< double > * | ptrx |
| std::vector< double > | ttag |
| unsigned int | width |
Additional Inherited Members | |
Public Types inherited from gnsstk::KalmanFilter | |
| 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 |
Protected Types inherited from gnsstk::KalmanFilter | |
| typedef struct gnsstk::KalmanFilter::Smoother_storage_record | SmootherStoreRec |
| Storage for smoothing algorithm; stored by forward filter, used by SU. More... | |
Protected Attributes inherited from gnsstk::KalmanFilter | |
| 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, SmootherStoreRec > | SmootherStore |
| 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... | |
|
inline |
Definition at line 89 of file WNJfilter.hpp.
|
inline |
Definition at line 96 of file WNJfilter.hpp.
|
inlinevirtual |
Get apriori state and covariance from user.
| Exception |
Implements gnsstk::KalmanFilter.
Definition at line 155 of file WNJfilter.hpp.
|
inlinevirtual |
Input T,X,Cov - the current state. Output T=time of next MU Fill and return the data quantities Partials,Data,MCov.
| Exception |
Implements gnsstk::KalmanFilter.
Definition at line 243 of file WNJfilter.hpp.
|
inlinevirtual |
|
inlinevirtual |
Output at each stage ... the user may override if singular is true, State and Cov may or may not be good
| N | user-defined counter that is included on each line after the tag. |
Reimplemented from gnsstk::KalmanFilter.
Definition at line 282 of file WNJfilter.hpp.
|
inline |
Definition at line 98 of file WNJfilter.hpp.
| gnsstk::Vector<double> gnsstk::WNJfilter::apNoise |
Definition at line 69 of file WNJfilter.hpp.
| gnsstk::Vector<double> gnsstk::WNJfilter::apState |
Definition at line 68 of file WNJfilter.hpp.
| int gnsstk::WNJfilter::count |
Definition at line 72 of file WNJfilter.hpp.
| std::vector<double> gnsstk::WNJfilter::data |
Definition at line 76 of file WNJfilter.hpp.
| bool gnsstk::WNJfilter::filterOutput |
Definition at line 66 of file WNJfilter.hpp.
| std::vector<double> gnsstk::WNJfilter::msig |
Definition at line 77 of file WNJfilter.hpp.
| unsigned int gnsstk::WNJfilter::prec |
Definition at line 84 of file WNJfilter.hpp.
| std::vector<double> gnsstk::WNJfilter::psig |
Definition at line 78 of file WNJfilter.hpp.
| std::vector<double> * gnsstk::WNJfilter::ptra |
Definition at line 80 of file WNJfilter.hpp.
| std::vector<double>* gnsstk::WNJfilter::ptrs |
Definition at line 81 of file WNJfilter.hpp.
| std::vector<double> * gnsstk::WNJfilter::ptrv |
Definition at line 80 of file WNJfilter.hpp.
| std::vector<double>* gnsstk::WNJfilter::ptrx |
Definition at line 80 of file WNJfilter.hpp.
| std::vector<double> gnsstk::WNJfilter::ttag |
Definition at line 75 of file WNJfilter.hpp.
| unsigned int gnsstk::WNJfilter::width |
Definition at line 84 of file WNJfilter.hpp.