gokalman

package module
v0.0.0-...-81e76c1 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: May 7, 2017 License: MIT Imports: 12 Imported by: 0

README

Build Status Coverage Status goreport

gokalman

Go lang implementations of the Kalman Filter and its variantes, along with examples in statistical orbit determination.

Usage

estimateChan := make(chan(Estimate), 1)
go processEstimates(estimateChan)
kf := New[KalmanFilter](...) // e.g. NewVanilla(...)
for k, measurement := range measurements {
	newEstimate, err := kf.Update(measurement, controlVectors[k])
	if err != nil {
		processError(err)
		continue
	}
	estimateChan <- newEstimate
}
close(estimateChan)
// Should add a usage of sync.

Documentation

Index

Constants

This section is empty.

Variables

This section is empty.

Functions

func AsSymDense

func AsSymDense(m *mat64.Dense) (*mat64.SymDense, error)

AsSymDense attempts return a SymDense from the provided Dense.

func DenseIdentity

func DenseIdentity(n int) *mat64.Dense

DenseIdentity returns an identity matrix of type Dense and of the provided size.

func HouseholderTransf

func HouseholderTransf(A *mat64.Dense, n, m int)

HouseholderTransf performs the Householder transformation of the given A matrix. Changes are done directly in the provided matrix.

func Identity

func Identity(n int) *mat64.SymDense

Identity returns an identity matrix of the provided size.

func IsNil

func IsNil(m mat64.Matrix) bool

IsNil returns whether the provided matrix only has zero values

func NewChiSquare

func NewChiSquare(kf LDKF, runs MonteCarloRuns, controls []*mat64.Vector, withNEES, withNIS bool) ([]float64, []float64, error)

NewChiSquare runs the Chi square tests from the MonteCarlo runs. These runs and the KF used are the ones tested via Chi square. The KF provided must be a pure predictor Vanilla KF and will be used to compute the intermediate steps of both the NEES and NIS tests. Returns NEESmeans, NISmeans and an error if applicable TODO: Change order of parameters.

func NewHybridKF

func NewHybridKF(x0 *mat64.Vector, P0 mat64.Symmetric, noise Noise, measSize int) (*HybridKF, *HybridKFEstimate, error)

NewHybridKF returns a new hybrid Kalman Filter which can be used both as a CKF and EKF. Warning: there is a failsafe preventing any update prior to updating the matrices. Usage: ``` / kf.Prepare(Φ, Htilde)

estimate, err := kf.Update(realObs, computedObs)

/ ``` Parameters: - x0: initial state estimate - P0: initial covariance symmetric matrix - noise: Noise - measSize: number of rows of the measurement vector (not actually important)

func NewInformation

func NewInformation(i0 *mat64.Vector, I0 mat64.Symmetric, F, G, H mat64.Matrix, noise Noise) (*Information, *InformationEstimate, error)

NewInformation returns a new Information KF. To get the next estimate, call Update() with the next measurement and the control vector. This will return a new InformationEstimate which contains everything of this step and an error if any. Parameters: - i0: initial information state (usually a zero vector) - I0: initial information matrix (usually a zero matrix) - F: state update matrix - G: control matrix (if all zeros, then control vector will not be used) - H: measurement update matrix - noise: Noise

func NewInformationFromState

func NewInformationFromState(x0 *mat64.Vector, P0 mat64.Symmetric, F, G, H mat64.Matrix, noise Noise) (*Information, *InformationEstimate, error)

NewInformationFromState returns a new Information KF. To get the next estimate, call Update() with the next measurement and the control vector. This will return a new InformationEstimate which contains everything of this step and an error if any. Parameters: - i0: initial information state (usually a zero vector) - I0: initial information matrix (usually a zero matrix) - F: state update matrix - G: control matrix (if all zeros, then control vector will not be used) - H: measurement update matrix - noise: Noise

func NewPurePredictorVanilla

func NewPurePredictorVanilla(x0 *mat64.Vector, Covar0 mat64.Symmetric, F, G, H mat64.Matrix, noise Noise) (*Vanilla, *VanillaEstimate, error)

NewPurePredictorVanilla returns a new Vanilla KF which only does prediction.

func NewSRIF

func NewSRIF(x0 *mat64.Vector, P0 mat64.Symmetric, measSize int, nonTriR bool, n Noise) (*SRIF, *SRIFEstimate, error)

NewSRIF returns a new Square Root Information Filter. It uses the algorithms from "Statistical Orbit determination" by Tapley, Schutz & Born. Set nonTriR to `true` to NOT use the Householder transformation on \bar{R_k}.

func NewSquareRoot

func NewSquareRoot(x0 *mat64.Vector, P0 mat64.Symmetric, F, G, H mat64.Matrix, noise Noise) (*SquareRoot, *SquareRootEstimate, error)

NewSquareRoot returns a new Square Root KF. To get the next estimate, push to the MeasChan the next measurement and read from StateEst and MeasEst to get the next state estimate (\hat{x}{k+1}^{+}) and next measurement estimate (\hat{y}{k+1}). The Covar channel stores the next covariance of the system (P_{k+1}^{+}). Parameters: - x0: initial state - Covar0: initial covariance matrix - F: state update matrix - G: control matrix (if all zeros, then control vector will not be used) - H: measurement update matrix - noise: Noise

func NewVanilla

func NewVanilla(x0 *mat64.Vector, Covar0 mat64.Symmetric, F, G, H mat64.Matrix, noise Noise) (*Vanilla, *VanillaEstimate, error)

NewVanilla returns a new Vanilla KF. To get the next estimate, simply push to the MeasChan the next measurement and read from StateEst and MeasEst to get the next state estimate (\hat{x}_{k+1}^{+}) and next measurement estimate (\hat{y}_{k+1}). The Covar channel stores the next covariance of the system (P_{k+1}^{+}). Parameters: - x0: initial state - Covar0: initial covariance matrix - F: state update matrix - G: control matrix (if all zeros, then control vector will not be used) - H: measurement update matrix - n: Noise

func ScaledDenseIdentity

func ScaledDenseIdentity(n int, s float64) *mat64.Dense

ScaledDenseIdentity returns an identity matrix time of type Dense a scaling factor of the provided size.

func ScaledIdentity

func ScaledIdentity(n int, s float64) *mat64.SymDense

ScaledIdentity returns an identity matrix time a scaling factor of the provided size.

func Sign

func Sign(v float64) float64

Sign returns the sign of a given number.

func VanLoan

func VanLoan(A, Γ, W *mat64.Dense, Δt float64) (*mat64.Dense, *mat64.SymDense, error)

VanLoan computes the F and Q matrices from the provided CT system A, Γ, W and the sampling rate Δt.

Types

type AWGN

type AWGN struct {
	Q, R mat64.Symmetric
	// contains filtered or unexported fields
}

AWGN implements the Noise interface and generates an Additive white Gaussian noise.

func NewAWGN

func NewAWGN(Q, R mat64.Symmetric) *AWGN

NewAWGN creates new AWGN noise from the provided Q and R.

func (*AWGN) Measurement

func (n *AWGN) Measurement(k int) *mat64.Vector

Measurement implements the Noise interface.

func (*AWGN) MeasurementMatrix

func (n *AWGN) MeasurementMatrix() mat64.Symmetric

MeasurementMatrix implements the Noise interface.

func (*AWGN) Process

func (n *AWGN) Process(k int) *mat64.Vector

Process implements the Noise interface.

func (*AWGN) ProcessMatrix

func (n *AWGN) ProcessMatrix() mat64.Symmetric

ProcessMatrix implements the Noise interface.

func (*AWGN) Reset

func (n *AWGN) Reset()

Reset does nothing for a Noiseless signal.

func (AWGN) String

func (n AWGN) String() string

String implements the Stringer interface.

type BatchGroundTruth

type BatchGroundTruth struct {
	// contains filtered or unexported fields
}

BatchGroundTruth computes the error of a given estimate from a known batch of states and measurements.

func NewBatchGroundTruth

func NewBatchGroundTruth(states, measurements []*mat64.Vector) *BatchGroundTruth

NewBatchGroundTruth initializes a new batch ground truth.

func (*BatchGroundTruth) Error

func (t *BatchGroundTruth) Error(k int, est Estimate) Estimate

Error returns an ErrorEstimate after comparing the provided state and measurements with the ground truths.

func (*BatchGroundTruth) ErrorWithOffset

func (t *BatchGroundTruth) ErrorWithOffset(k int, est Estimate, offset *mat64.Vector) Estimate

ErrorWithOffset returns an ErrorEstimate after comparing the provided state, adding the offset and measurements with the ground truths.

type BatchKF

type BatchKF struct {
	Λ            *mat64.Dense
	N            *mat64.Vector
	Measurements []measurementInfo
	// contains filtered or unexported fields
}

BatchKF defines a vanilla kalman filter. Use NewVanilla to initialize.

func NewBatchKF

func NewBatchKF(numMeasurements int, noise Noise) *BatchKF

NewBatchKF returns a new hybrid Kalman Filter which can be used both as a CKF and EKF. Warning: there is a failsafe preventing any update prior to updating the matrices. Usage: ``` / kf.Prepare(Φ, Htilde)

estimate, err := kf.Update(realObs, computedObs)

/ ``` Parameters: - x0: initial state estimate - P0: initial covariance symmetric matrix - noise: Noise - measSize: number of rows of the measurement vector (not actually important)

func (*BatchKF) SetNextMeasurement

func (kf *BatchKF) SetNextMeasurement(realObs, computedObs *mat64.Vector, Φ, H *mat64.Dense)

SetNextMeasurement sets the next sequential measurement to the list of measurements to be taken into account for the filter.

func (*BatchKF) Solve

func (kf *BatchKF) Solve() (xHat0 *mat64.Vector, P0 *mat64.SymDense, err error)

Solve will solve the Batch Kalman filter once and return xHat0 and P0, or an error

type BatchNoise

type BatchNoise struct {
	// contains filtered or unexported fields
}

BatchNoise implements the Noise interface.

func (BatchNoise) Measurement

func (n BatchNoise) Measurement(k int) *mat64.Vector

Measurement implements the Noise interface.

func (BatchNoise) MeasurementMatrix

func (n BatchNoise) MeasurementMatrix() mat64.Symmetric

MeasurementMatrix implements the Noise interface.

func (BatchNoise) Process

func (n BatchNoise) Process(k int) *mat64.Vector

Process implements the Noise interface.

func (BatchNoise) ProcessMatrix

func (n BatchNoise) ProcessMatrix() mat64.Symmetric

ProcessMatrix implements the Noise interface.

func (BatchNoise) Reset

func (n BatchNoise) Reset()

Reset does nothing for a BatchNoise signal.

func (BatchNoise) String

func (n BatchNoise) String() string

String implements the Stringer interface.

type CSVExporter

type CSVExporter struct {
	// contains filtered or unexported fields
}

CSVExporter returns a new CSV exporter.

func NewCSVExporter

func NewCSVExporter(headers []string, filepath, filename string) (e *CSVExporter, err error)

NewCSVExporter initializes a new CSV export.

func NewCustomCSVExporter

func NewCustomCSVExporter(headers []string, filepath, filename string, covarBound float64) (e *CSVExporter, err error)

NewCustomCSVExporter initializes a new CSV export. NOTE: Prefix header with `_` to state that it does not relate to the estimation (and therefore won't have the added covariance bounds).

func (CSVExporter) Close

func (e CSVExporter) Close() (err error)

Close closes the file.

func (CSVExporter) Write

func (e CSVExporter) Write(est Estimate) error

Write writes the estimate to the CSV file.

func (CSVExporter) WriteRaw

func (e CSVExporter) WriteRaw(s string) error

WriteRaw writes a raw line to the CSV file.

func (CSVExporter) WriteRawLn

func (e CSVExporter) WriteRawLn(s string) error

WriteRawLn writes a raw line to the CSV file.

type DimensionAgreement

type DimensionAgreement uint8

DimensionAgreement defines how two matrices' dimensions should agree.

type ErrorEstimate

type ErrorEstimate struct {
	VanillaEstimate // This is effectively the same as a VanillaEstimate, so no change.
}

ErrorEstimate implements the Estimate interface and is used to show the error of an estimate.

type Estimate

type Estimate interface {
	IsWithinNσ(N float64) bool       // IsWithinNσ returns whether the estimation is within the N*σ bounds.
	State() *mat64.Vector            // Returns \hat{x}_{k+1}^{+}
	Measurement() *mat64.Vector      // Returns \hat{y}_{k}^{+}
	Innovation() *mat64.Vector       // Returns y_{k} - H*\hat{x}_{k+1}^{-}
	Covariance() mat64.Symmetric     // Return P_{k+1}^{+}
	PredCovariance() mat64.Symmetric // Return P_{k+1}^{-}
	String() string                  // Must implement the stringer interface.
}

Estimate is returned from Update() in any KF. This allows to avoid some computations in other filters, e.g. in the Information filter.

type Exporter

type Exporter interface {
	Write(Estimate) error
	Close() error
}

Exporter defines an export interface.

type FilterType

type FilterType uint8

FilterType allows for quick comparison of filters.

const (
	// CKFType definition would be a tautology
	CKFType FilterType = iota + 1
	// EKFType definition would be a tautology
	EKFType
	// UKFType definition would be a tautology
	UKFType
	// SRIFType definition would be a tautology
	SRIFType
)

func (FilterType) String

func (f FilterType) String() string

type HybridKF

type HybridKF struct {
	Φ, Htilde, Γ *mat64.Dense
	Noise        Noise
	// contains filtered or unexported fields
}

HybridKF defines a hybrid kalman filter for non-linear dynamical systems. Use NewHybridKF to initialize.

func (*HybridKF) DisableEKF

func (kf *HybridKF) DisableEKF()

DisableEKF switches this back to a CKF mode.

func (*HybridKF) EKFEnabled

func (kf *HybridKF) EKFEnabled() bool

EKFEnabled returns whether the KF is in EKF mode.

func (*HybridKF) EnableEKF

func (kf *HybridKF) EnableEKF()

EnableEKF switches this to an EKF mode.

func (*HybridKF) GetNoise

func (kf *HybridKF) GetNoise() Noise

GetNoise updates the F matrix.

func (*HybridKF) Predict

func (kf *HybridKF) Predict() (est Estimate, err error)

Predict computes only the time update (or prediction). Will return an error if the KF is locked (call Prepare to unlock).

func (*HybridKF) Prepare

func (kf *HybridKF) Prepare(Φ, Htilde *mat64.Dense)

Prepare unlocks the KF ready for the next Update call.

func (*HybridKF) PreparePNT

func (kf *HybridKF) PreparePNT(Γ *mat64.Dense)

PreparePNT prepares the process noise transition matrix and enabled the SNC for the next update. WARNING: If not called, the SNC *will not* be included.

func (*HybridKF) SetNoise

func (kf *HybridKF) SetNoise(n Noise)

SetNoise updates the Noise.

func (*HybridKF) SmoothAll

func (kf *HybridKF) SmoothAll(estimates []*HybridKFEstimate) (err error)

SmoothAll will smooth all the previous estimates using the provided data. Returns the smoothed estimates. Will return an error if there are more estimates than there should be. WARNING: overwrites the provided array of estimates.

func (*HybridKF) String

func (kf *HybridKF) String() string

func (*HybridKF) Update

func (kf *HybridKF) Update(realObservation, computedObservation *mat64.Vector) (est Estimate, err error)

Update computes a full time and measurement update. Will return an error if the KF is locked (call Prepare to unlock).

type HybridKFEstimate

type HybridKFEstimate struct {
	Φ, Γ *mat64.Dense // Used for smoothing
	Δobs *mat64.Vector
	// contains filtered or unexported fields
}

HybridKFEstimate is the output of each update state of the Vanilla KF. It implements the Estimate interface.

func (HybridKFEstimate) Covariance

func (e HybridKFEstimate) Covariance() mat64.Symmetric

Covariance implements the Estimate interface.

func (HybridKFEstimate) Gain

func (e HybridKFEstimate) Gain() mat64.Matrix

Gain the Estimate interface.

func (HybridKFEstimate) Innovation

func (e HybridKFEstimate) Innovation() *mat64.Vector

Innovation implements the Estimate interface.

func (HybridKFEstimate) IsWithin2σ

func (e HybridKFEstimate) IsWithin2σ() bool

IsWithin2σ returns whether the estimation is within the 2σ bounds.

func (HybridKFEstimate) IsWithinNσ

func (e HybridKFEstimate) IsWithinNσ(N float64) bool

IsWithinNσ returns whether the estimation is within the 2σ bounds.

func (HybridKFEstimate) Measurement

func (e HybridKFEstimate) Measurement() *mat64.Vector

Measurement implements the Estimate interface.

func (HybridKFEstimate) ObservationDev

func (e HybridKFEstimate) ObservationDev() *mat64.Vector

ObservationDev returns the observation deviation.

func (HybridKFEstimate) PredCovariance

func (e HybridKFEstimate) PredCovariance() mat64.Symmetric

PredCovariance implements the Estimate interface.

func (HybridKFEstimate) State

func (e HybridKFEstimate) State() *mat64.Vector

State implements the Estimate interface.

func (HybridKFEstimate) String

func (e HybridKFEstimate) String() string

type Information

type Information struct {
	Finv  mat64.Matrix
	G     mat64.Matrix
	H     mat64.Matrix
	Qinv  mat64.Matrix
	Rinv  mat64.Matrix
	Noise Noise
	// contains filtered or unexported fields
}

Information defines a vanilla kalman filter. Use NewVanilla to initialize.

func (*Information) GetInputControl

func (kf *Information) GetInputControl() mat64.Matrix

GetInputControl returns the G matrix.

func (*Information) GetMeasurementMatrix

func (kf *Information) GetMeasurementMatrix() mat64.Matrix

GetMeasurementMatrix returns the H matrix.

func (*Information) GetNoise

func (kf *Information) GetNoise() Noise

GetNoise updates the F matrix.

func (*Information) GetStateTransition

func (kf *Information) GetStateTransition() mat64.Matrix

GetStateTransition returns the F matrix. *WARNING:* Returns the *INVERSE* of F for the information filter.

func (*Information) Reset

func (kf *Information) Reset()

Reset reinitializes the KF with its initial estimate.

func (*Information) SetInputControl

func (kf *Information) SetInputControl(G mat64.Matrix)

SetInputControl updates the G matrix.

func (*Information) SetMeasurementMatrix

func (kf *Information) SetMeasurementMatrix(H mat64.Matrix)

SetMeasurementMatrix updates the H matrix.

func (*Information) SetNoise

func (kf *Information) SetNoise(n Noise)

SetNoise updates the Noise.

func (*Information) SetStateTransition

func (kf *Information) SetStateTransition(F mat64.Matrix)

SetStateTransition updates the F matrix.

func (*Information) String

func (kf *Information) String() string

func (*Information) Update

func (kf *Information) Update(measurement, control *mat64.Vector) (est Estimate, err error)

Update implements the KalmanFilter interface.

type InformationEstimate

type InformationEstimate struct {
	// contains filtered or unexported fields
}

InformationEstimate is the output of each update state of the Information KF. It implements the Estimate interface.

func NewInformationEstimate

func NewInformationEstimate(infoState, meas *mat64.Vector, infoMat, predInfoMat mat64.Symmetric) InformationEstimate

NewInformationEstimate initializes a new InformationEstimate.

func (InformationEstimate) Covariance

func (e InformationEstimate) Covariance() mat64.Symmetric

Covariance implements the Estimate interface. *NOTE:* With the IF, one cannot view the covariance matrix until there is enough information.

func (InformationEstimate) Innovation

func (e InformationEstimate) Innovation() *mat64.Vector

Innovation implements the Estimate interface.

func (InformationEstimate) IsWithin2σ

func (e InformationEstimate) IsWithin2σ() bool

IsWithin2σ returns whether the estimation is within the 2σ bounds.

func (InformationEstimate) IsWithinNσ

func (e InformationEstimate) IsWithinNσ(N float64) bool

IsWithinNσ returns whether the estimation is within the 2σ bounds.

func (InformationEstimate) Measurement

func (e InformationEstimate) Measurement() *mat64.Vector

Measurement implements the Estimate interface.

func (InformationEstimate) PredCovariance

func (e InformationEstimate) PredCovariance() mat64.Symmetric

PredCovariance implements the Estimate interface. *NOTE:* With the IF, one cannot view the prediction covariance matrix until there is enough information.

func (InformationEstimate) State

func (e InformationEstimate) State() *mat64.Vector

State implements the Estimate interface.

func (InformationEstimate) String

func (e InformationEstimate) String() string

type LDKF

type LDKF interface {
	Update(measurement, control *mat64.Vector) (Estimate, error)
	GetNoise() Noise
	GetStateTransition() mat64.Matrix
	GetInputControl() mat64.Matrix
	GetMeasurementMatrix() mat64.Matrix
	SetStateTransition(mat64.Matrix)
	SetInputControl(mat64.Matrix)
	SetMeasurementMatrix(mat64.Matrix)
	SetNoise(Noise)
	Reset()
	String() string
}

LDKF defines a linear dynamics Kalman Filter.

type MonteCarloRun

type MonteCarloRun struct {
	Estimates []Estimate
}

MonteCarloRun stores the results of an MC run.

type MonteCarloRuns

type MonteCarloRuns struct {
	Runs []MonteCarloRun
	// contains filtered or unexported fields
}

MonteCarloRuns stores MC runs.

func NewMonteCarloRuns

func NewMonteCarloRuns(samples, steps, rowsH int, controls []*mat64.Vector, kf *Vanilla) MonteCarloRuns

NewMonteCarloRuns run monte carlos on the provided filter.

func (MonteCarloRuns) AsCSV

func (mc MonteCarloRuns) AsCSV(headers []string) []string

AsCSV is used as a CSV serializer. Does not include the header.

func (MonteCarloRuns) Mean

func (mc MonteCarloRuns) Mean(step int) (mean []float64)

Mean returns the mean of all the samples for the given time step.

func (MonteCarloRuns) StdDev

func (mc MonteCarloRuns) StdDev(step int) (mean []float64)

StdDev returns the standard deviation of all the samples for the given time step.

type NLDKF

type NLDKF interface {
	Prepare(Φ, Htilde *mat64.Dense)
	Predict() (est Estimate, err error)
	Update(realObservation, computedObservation *mat64.Vector) (est Estimate, err error)
	EKFEnabled() bool
	EnableEKF()
	DisableEKF()
	PreparePNT(Γ *mat64.Dense)
	SetNoise(n Noise)
}

NLDKF defines a non-linear dynamics Kalman Filter. Operates and is architectured slightly differently than LDKF.

type Noise

type Noise interface {
	Process(k int) *mat64.Vector        // Returns the process noise w at step k
	Measurement(k int) *mat64.Vector    // Returns the measurement noise w at step k
	ProcessMatrix() mat64.Symmetric     // Returns the process noise matrix Q
	MeasurementMatrix() mat64.Symmetric // Returns the measurement noise matrix R
	Reset()                             // Reinitializes the noise
	String() string                     // Stringer interface implementation
}

Noise allows to handle the noise for a KF.

type Noiseless

type Noiseless struct {
	Q, R mat64.Symmetric
	// contains filtered or unexported fields
}

Noiseless is noiseless and implements the Noise interface.

func NewNoiseless

func NewNoiseless(Q, R mat64.Symmetric) *Noiseless

NewNoiseless creates new AWGN noise from the provided Q and R.

func (Noiseless) Measurement

func (n Noiseless) Measurement(k int) *mat64.Vector

Measurement returns a vector of the correct size.

func (Noiseless) MeasurementMatrix

func (n Noiseless) MeasurementMatrix() mat64.Symmetric

MeasurementMatrix implements the Noise interface.

func (Noiseless) Process

func (n Noiseless) Process(k int) *mat64.Vector

Process returns a vector of the correct size.

func (Noiseless) ProcessMatrix

func (n Noiseless) ProcessMatrix() mat64.Symmetric

ProcessMatrix implements the Noise interface.

func (Noiseless) Reset

func (n Noiseless) Reset()

Reset does nothing for a Noiseless signal.

func (Noiseless) String

func (n Noiseless) String() string

String implements the Stringer interface.

type SRIF

type SRIF struct {
	Φ, Htilde *mat64.Dense
	// contains filtered or unexported fields
}

SRIF defines a square root information filter for non-linear dynamical systems. Use NewSquareRootInformation to initialize.

func (*SRIF) DisableEKF

func (kf *SRIF) DisableEKF()

DisableEKF does nothing.

func (*SRIF) EKFEnabled

func (kf *SRIF) EKFEnabled() bool

EKFEnabled always returns false.

func (*SRIF) EnableEKF

func (kf *SRIF) EnableEKF()

EnableEKF does nothing.

func (*SRIF) Predict

func (kf *SRIF) Predict() (est Estimate, err error)

Predict computes only the time update (or prediction). Will return an error if the KF is locked (call Prepare to unlock).

func (*SRIF) Prepare

func (kf *SRIF) Prepare(Φ, Htilde *mat64.Dense)

Prepare unlocks the KF ready for the next Update call.

func (*SRIF) PreparePNT

func (kf *SRIF) PreparePNT(Γ *mat64.Dense)

PreparePNT does nothing.

func (*SRIF) SetNoise

func (kf *SRIF) SetNoise(n Noise)

SetNoise updates the Noise.

func (*SRIF) SmoothAll

func (kf *SRIF) SmoothAll(estimates []*SRIFEstimate) (err error)

SmoothAll will smooth all the previous estimates using the provided data. Returns the smoothed estimates. Will return an error if there are more estimates than there should be. WARNING: overwrites the provided array of estimates.

func (*SRIF) Update

func (kf *SRIF) Update(realObservation, computedObservation *mat64.Vector) (est Estimate, err error)

Update computes a full time and measurement update. Will return an error if the KF is locked (call Prepare to unlock).

type SRIFEstimate

type SRIFEstimate struct {
	Φ *mat64.Dense // Used for smoothing

	Δobs *mat64.Vector
	R    *mat64.Dense
	// contains filtered or unexported fields
}

SRIFEstimate is the output of each update state of the Vanilla KF. It implements the Estimate interface.

func NewSRIFEstimate

func NewSRIFEstimate(Φ *mat64.Dense, sqinfoState, meas, Δobs *mat64.Vector, R0, predR0 *mat64.Dense) SRIFEstimate

NewSRIFEstimate initializes a new SRIFEstimate. NOTE: R0 and predR0 are mat64.Dense for simplicity of implementation, but they should be symmetric.

func (SRIFEstimate) Covariance

func (e SRIFEstimate) Covariance() mat64.Symmetric

Covariance implements the Estimate interface.

func (SRIFEstimate) Innovation

func (e SRIFEstimate) Innovation() *mat64.Vector

Innovation implements the Estimate interface.

func (SRIFEstimate) IsWithin2σ

func (e SRIFEstimate) IsWithin2σ() bool

IsWithin2σ returns whether the estimation is within the 2σ bounds.

func (SRIFEstimate) IsWithinNσ

func (e SRIFEstimate) IsWithinNσ(N float64) bool

IsWithinNσ returns whether the estimation is within the 2σ bounds.

func (SRIFEstimate) Measurement

func (e SRIFEstimate) Measurement() *mat64.Vector

Measurement implements the Estimate interface.

func (SRIFEstimate) ObservationDev

func (e SRIFEstimate) ObservationDev() *mat64.Vector

ObservationDev returns the observation deviation.

func (SRIFEstimate) PredCovariance

func (e SRIFEstimate) PredCovariance() mat64.Symmetric

PredCovariance implements the Estimate interface.

func (SRIFEstimate) State

func (e SRIFEstimate) State() *mat64.Vector

State implements the Estimate interface.

func (SRIFEstimate) String

func (e SRIFEstimate) String() string

type SquareRoot

type SquareRoot struct {
	F     mat64.Matrix
	G     mat64.Matrix
	H     mat64.Matrix
	Noise Noise
	// contains filtered or unexported fields
}

SquareRoot defines a square root kalman filter. Use NewSqrt to initialize.

func (*SquareRoot) GetInputControl

func (kf *SquareRoot) GetInputControl() mat64.Matrix

GetInputControl returns the G matrix.

func (*SquareRoot) GetMeasurementMatrix

func (kf *SquareRoot) GetMeasurementMatrix() mat64.Matrix

GetMeasurementMatrix returns the H matrix.

func (*SquareRoot) GetNoise

func (kf *SquareRoot) GetNoise() Noise

GetNoise updates the F matrix.

func (*SquareRoot) GetStateTransition

func (kf *SquareRoot) GetStateTransition() mat64.Matrix

GetStateTransition returns the F matrix.

func (*SquareRoot) Reset

func (kf *SquareRoot) Reset()

Reset reinitializes the KF with its initial estimate.

func (*SquareRoot) SetInputControl

func (kf *SquareRoot) SetInputControl(G mat64.Matrix)

SetInputControl updates the G matrix.

func (*SquareRoot) SetMeasurementMatrix

func (kf *SquareRoot) SetMeasurementMatrix(H mat64.Matrix)

SetMeasurementMatrix updates the H matrix.

func (*SquareRoot) SetNoise

func (kf *SquareRoot) SetNoise(n Noise)

SetNoise updates the Noise.

func (*SquareRoot) SetStateTransition

func (kf *SquareRoot) SetStateTransition(F mat64.Matrix)

SetStateTransition updates the F matrix.

func (*SquareRoot) String

func (kf *SquareRoot) String() string

Prints the output.

func (*SquareRoot) Update

func (kf *SquareRoot) Update(measurement, control *mat64.Vector) (est Estimate, err error)

Update implements the KalmanFilter interface.

type SquareRootEstimate

type SquareRootEstimate struct {
	// contains filtered or unexported fields
}

SquareRootEstimate is the output of each update state of the SquareRoot KF. It implements the Estimate interface.

func NewSqrtEstimate

func NewSqrtEstimate(state, meas, innovation *mat64.Vector, stddev, predStddev, gain *mat64.Dense) SquareRootEstimate

NewSqrtEstimate initializes a new InformationEstimate.

func (SquareRootEstimate) Covariance

func (e SquareRootEstimate) Covariance() mat64.Symmetric

Covariance implements the Estimate interface.

func (SquareRootEstimate) Gain

func (e SquareRootEstimate) Gain() mat64.Matrix

Gain the Estimate interface.

func (SquareRootEstimate) Innovation

func (e SquareRootEstimate) Innovation() *mat64.Vector

Innovation implements the Estimate interface.

func (SquareRootEstimate) IsWithin2σ

func (e SquareRootEstimate) IsWithin2σ() bool

IsWithin2σ returns whether the estimation is within the 2σ bounds.

func (SquareRootEstimate) IsWithinNσ

func (e SquareRootEstimate) IsWithinNσ(N float64) bool

IsWithinNσ returns whether the estimation is within the 2σ bounds.

func (SquareRootEstimate) Measurement

func (e SquareRootEstimate) Measurement() *mat64.Vector

Measurement implements the Estimate interface.

func (SquareRootEstimate) PredCovariance

func (e SquareRootEstimate) PredCovariance() mat64.Symmetric

PredCovariance implements the Estimate interface.

func (SquareRootEstimate) State

func (e SquareRootEstimate) State() *mat64.Vector

State implements the Estimate interface.

func (SquareRootEstimate) String

func (e SquareRootEstimate) String() string

type Vanilla

type Vanilla struct {
	F     mat64.Matrix
	G     mat64.Matrix
	H     mat64.Matrix
	Noise Noise
	// contains filtered or unexported fields
}

Vanilla defines a vanilla kalman filter. Use NewVanilla to initialize.

func (*Vanilla) GetInputControl

func (kf *Vanilla) GetInputControl() mat64.Matrix

GetInputControl returns the G matrix.

func (*Vanilla) GetMeasurementMatrix

func (kf *Vanilla) GetMeasurementMatrix() mat64.Matrix

GetMeasurementMatrix returns the H matrix.

func (*Vanilla) GetNoise

func (kf *Vanilla) GetNoise() Noise

GetNoise updates the F matrix.

func (*Vanilla) GetStateTransition

func (kf *Vanilla) GetStateTransition() mat64.Matrix

GetStateTransition returns the F matrix.

func (*Vanilla) Reset

func (kf *Vanilla) Reset()

Reset reinitializes the KF with its initial estimate.

func (*Vanilla) SetInputControl

func (kf *Vanilla) SetInputControl(G mat64.Matrix)

SetInputControl updates the F matrix.

func (*Vanilla) SetMeasurementMatrix

func (kf *Vanilla) SetMeasurementMatrix(H mat64.Matrix)

SetMeasurementMatrix updates the H matrix.

func (*Vanilla) SetNoise

func (kf *Vanilla) SetNoise(n Noise)

SetNoise updates the Noise.

func (*Vanilla) SetStateTransition

func (kf *Vanilla) SetStateTransition(F mat64.Matrix)

SetStateTransition updates the F matrix.

func (*Vanilla) String

func (kf *Vanilla) String() string

func (*Vanilla) Update

func (kf *Vanilla) Update(measurement, control *mat64.Vector) (est Estimate, err error)

Update implements the KalmanFilter interface.

type VanillaEstimate

type VanillaEstimate struct {
	// contains filtered or unexported fields
}

VanillaEstimate is the output of each update state of the Vanilla KF. It implements the Estimate interface.

func (VanillaEstimate) Covariance

func (e VanillaEstimate) Covariance() mat64.Symmetric

Covariance implements the Estimate interface.

func (VanillaEstimate) Gain

func (e VanillaEstimate) Gain() mat64.Matrix

Gain the Estimate interface.

func (VanillaEstimate) Innovation

func (e VanillaEstimate) Innovation() *mat64.Vector

Innovation implements the Estimate interface.

func (VanillaEstimate) IsWithin2σ

func (e VanillaEstimate) IsWithin2σ() bool

IsWithin2σ returns whether the estimation is within the 2σ bounds.

func (VanillaEstimate) IsWithinNσ

func (e VanillaEstimate) IsWithinNσ(N float64) bool

IsWithinNσ returns whether the estimation is within the 2σ bounds.

func (VanillaEstimate) Measurement

func (e VanillaEstimate) Measurement() *mat64.Vector

Measurement implements the Estimate interface.

func (VanillaEstimate) PredCovariance

func (e VanillaEstimate) PredCovariance() mat64.Symmetric

PredCovariance implements the Estimate interface.

func (VanillaEstimate) State

func (e VanillaEstimate) State() *mat64.Vector

State implements the Estimate interface.

func (VanillaEstimate) String

func (e VanillaEstimate) String() string

Directories

Path Synopsis
examples

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL