sim

package
v0.4.2 Latest Latest
Warning

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

Go to latest
Published: Aug 21, 2021 License: Apache-2.0 Imports: 8 Imported by: 0

Documentation

Index

Constants

This section is empty.

Variables

This section is empty.

Functions

func New2DPlot

func New2DPlot(model, measure, filter *mat.Dense) (*plot.Plot, error)

New2DPlot creates new plot of the simulation from the three data sources: model: idealised model values measure: measurement values filter: filter values It returns error if the plot fails to be created. This can be due to either of the following conditions: * either of the supplied data matrices is nil * either of the supplied data matrices does not have at least 2 columns * gonum plot fails to be created

Types

type Continuous added in v0.4.2

type Continuous struct {
	System
}

Continuous is a basic model of a linear, continuous-time, dynamical system

func NewContinuous added in v0.4.2

func NewContinuous(A, B, C, D, E *mat.Dense) (*Continuous, error)

NewContinuous creates a linear continuous-time model based on the control theory equations which is advanced by timestep dt.

dx/dt = A*x + B*u + E*z (disturbances E not implemented yet)
y = C*x + D*u

func (*Continuous) Propagate added in v0.4.2

func (ct *Continuous) Propagate(x, u, wd mat.Vector, dt float64) (mat.Vector, error)

Propagate propagates returns the next internal state x of a linear, continuous-time system given an input vector u and a disturbance input z. (wd is process noise, z not implemented yet). It propagates the solution by a timestep `dt`.

func (*Continuous) ToDiscrete added in v0.4.2

func (ct *Continuous) ToDiscrete(Ts float64) (*Discrete, error)

ToDiscrete creates a discrete-time model from a continuous time model using Ts as the sampling time.

It is calculated using Euler's method, an approximation valid for small timesteps. TODO(soypat): implement Discrete system method ToContinuous to be able to test conversion between the two.

type Discrete added in v0.4.2

type Discrete struct {
	System
}

Discrete is a basic model of a linear, discrete-time, dynamical system

func NewDiscrete added in v0.4.2

func NewDiscrete(A, B, C, D, E *mat.Dense) (*Discrete, error)

NewDiscrete creates a linear discrete-time model based on the control theory equations.

x[n+1] = A*x[n] + B*u[n] + E*z[n] (disturbances E not implemented yet)
y[n] = C*x[n] + D*u[n]

func (*Discrete) Propagate added in v0.4.2

func (dt *Discrete) Propagate(x, u, wd mat.Vector) (mat.Vector, error)

Propagate propagates returns the next internal state x of a linear, continuous-time system given an input vector u and a disturbance input z. (wd is process noise, z not implemented yet)

type InitCond

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

InitCond implements filter.InitCond

func NewInitCond

func NewInitCond(state mat.Vector, cov mat.Symmetric) *InitCond

NewInitCond creates new InitCond and returns it

func (*InitCond) Cov

func (c *InitCond) Cov() mat.Symmetric

Cov returns initial covariance

func (*InitCond) State

func (c *InitCond) State() mat.Vector

State returns initial state

type System added in v0.4.2

type System struct {
	// System/State matrix A
	A *mat.Dense
	// Control/Input Matrix B
	B *mat.Dense
	// Observation/Output Matrix C
	C *mat.Dense
	// Feedthrough matrix D
	D *mat.Dense
	// Perturbation matrix (related to process noise wd) E
	E *mat.Dense
}

System defines a linear model of a plant using traditional matrices of modern control theory.

It contains the System (A), input (B), Observation/Output (C) Feedthrough (D) and disturbance (E) matrices.

func (System) ControlMatrix added in v0.4.2

func (s System) ControlMatrix() (B mat.Matrix)

ControlMatrix returns state propagation control matrix `B`

func (System) FeedForwardMatrix added in v0.4.2

func (s System) FeedForwardMatrix() (D mat.Matrix)

FeedForwardMatrix returns observation control matrix `D`

func (System) Observe added in v0.4.2

func (s System) Observe(x, u, wn mat.Vector) (y mat.Vector, err error)

Observe returns external/observable state given internal state x and input u. wn is added to the output as a noise vector.

func (System) OutputMatrix added in v0.4.2

func (s System) OutputMatrix() (C mat.Matrix)

OutputMatrix returns observation matrix `C`

func (System) SystemDims added in v0.4.2

func (s System) SystemDims() (nx, nu, ny, nz int)

SystemDims returns internal state length (nx), input vector length (nu), external/observable/output state length (ny) and disturbance vector length (nz).

func (System) SystemMatrix added in v0.4.2

func (s System) SystemMatrix() (A mat.Matrix)

SystemMatrix returns state propagation matrix `A`.

Jump to

Keyboard shortcuts

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