Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 11 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,20 @@ Supports continuous and discrete LTI models with MIMO capability.
go get github.com/jamestjsp/controlsys
```

> **Note:** This package depends on a [gonum fork](https://github.com/jamestjsp/gonum) for additional LAPACK routines. Add this to your `go.mod`:
> **Note:** This package depends on a [gonum fork](https://github.com/jamestjsp/gonum) for additional LAPACK routines. Because `replace` directives do not propagate to downstream modules, applications that import `controlsys` must add this to their own `go.mod`:
> ```
> replace gonum.org/v1/gonum => github.com/jamestjsp/gonum v0.17.2-fork
> ```

## Production Readiness

This package is intended to be usable in production control and estimation code, with the usual caveat that numerical software still needs application-specific validation.

- Pin both `controlsys` and the required gonum fork to explicit versions.
- Validate mission-critical models against an external reference, especially for ill-conditioned realizations and delay-heavy systems.
- `System` values are mutable. Use `Copy` before sharing a model across goroutines that may mutate names, delays, notes, or other receiver state.
- The repository CI runs `go vet ./...` and `go test -v -count=1 -race ./...`; those are the recommended baseline checks for downstream integrations.

## Features

- **Three representations:** state-space, transfer function, zero-pole-gain (ZPK) with bidirectional conversion
Expand Down Expand Up @@ -107,7 +116,7 @@ func main() {
| `Dlqr` | Discrete-time LQR regulator |
| `Lqe` | Kalman filter (observer) gain |
| `Lqi` | LQR with integral action |
| `Pole` | Pole placement |
| `Place` | Pole placement |
| `Care` | Continuous algebraic Riccati equation |
| `Dare` | Discrete algebraic Riccati equation |

Expand Down
4 changes: 2 additions & 2 deletions delay.go
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ func (sys *System) SetDelay(delay *mat.Dense) error {
if err := validateDelay(delay, p, m, sys.Dt); err != nil {
return err
}
sys.Delay = delay
sys.Delay = copyDelayOrNil(delay)
return nil
}

Expand Down Expand Up @@ -1643,7 +1643,7 @@ func (sys *System) GetDelayModel() (H *System, tau []float64) {
// Pull all delays into LFT
lft, err := sys.PullDelaysToLFT()
if err != nil {
// If PullDelaysToLFT fails (e.g. non-decomposable residual),
// If PullDelaysToLFT fails (e.g. non-decomposable residual),
// we fallback to just extracting InternalDelay if it exists,
// or return the original system.
if sys.LFT == nil {
Expand Down
34 changes: 34 additions & 0 deletions delay_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,26 @@ func TestNewWithDelay(t *testing.T) {
}
}

func TestNewWithDelayCopiesDelayMatrix(t *testing.T) {
delay := mat.NewDense(1, 1, []float64{3})
sys, err := NewWithDelay(
mat.NewDense(1, 1, []float64{0.5}),
mat.NewDense(1, 1, []float64{1}),
mat.NewDense(1, 1, []float64{1}),
mat.NewDense(1, 1, []float64{0}),
delay,
1.0,
)
if err != nil {
t.Fatal(err)
}

delay.Set(0, 0, 99)
if got := sys.Delay.At(0, 0); got != 3 {
t.Fatalf("delay alias detected: got %v, want 3", got)
}
}

func TestNewWithDelayNil(t *testing.T) {
A := mat.NewDense(1, 1, []float64{0.5})
B := mat.NewDense(1, 1, []float64{1})
Expand Down Expand Up @@ -62,6 +82,20 @@ func TestSetDelayNegative(t *testing.T) {
}
}

func TestSetDelayCopiesInputMatrix(t *testing.T) {
sys, _ := NewFromSlices(1, 1, 1,
[]float64{0.5}, []float64{1}, []float64{1}, []float64{0}, 1.0)
delay := mat.NewDense(1, 1, []float64{2})
if err := sys.SetDelay(delay); err != nil {
t.Fatal(err)
}

delay.Set(0, 0, 99)
if got := sys.Delay.At(0, 0); got != 2 {
t.Fatalf("delay alias detected: got %v, want 2", got)
}
}

func TestSetDelayFractionalDiscrete(t *testing.T) {
sys, _ := NewFromSlices(1, 1, 1,
[]float64{0.5}, []float64{1}, []float64{1}, []float64{0}, 1.0)
Expand Down
4 changes: 4 additions & 0 deletions doc.go
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,8 @@
// transport delays, state-space and transfer-function representations,
// frequency response analysis, discretization, simulation, and
// model reduction.
//
// Methods that configure delays, names, or notes mutate the receiver,
// so shared systems should be copied with Copy before concurrent
// mutation.
package controlsys
10 changes: 4 additions & 6 deletions ss.go
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ import (
// LFTDelay holds the internal delay representation using a linear
// fractional transformation (LFT) structure.
type LFTDelay struct {
Tau []float64
Tau []float64
B2, C2, D12, D21, D22 *mat.Dense
}

Expand Down Expand Up @@ -189,11 +189,12 @@ func NewGain(D *mat.Dense, dt float64) (*System, error) {
if D == nil {
return nil, fmt.Errorf("D matrix required for gain system: %w", ErrDimensionMismatch)
}
p, m := D.Dims()
return &System{
A: &mat.Dense{},
B: &mat.Dense{},
C: &mat.Dense{},
D: D,
D: denseCopySafe(D, p, m),
Dt: dt,
}, nil
}
Expand Down Expand Up @@ -241,10 +242,7 @@ func NewFromSlices(n, m, p int, a, b, c, d []float64, dt float64) (*System, erro
} else {
Dm = &mat.Dense{}
}
return &System{
A: &mat.Dense{}, B: &mat.Dense{}, C: &mat.Dense{},
D: Dm, Dt: dt,
}, nil
return NewGain(Dm, dt)
}

return newNoCopy(A, B, C, D, dt)
Expand Down
58 changes: 58 additions & 0 deletions ss_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,36 @@ func TestNewGain(t *testing.T) {
}
}

func TestNewCopiesInputMatrices(t *testing.T) {
A := mat.NewDense(2, 2, []float64{0, 1, -2, -3})
B := mat.NewDense(2, 1, []float64{0, 1})
C := mat.NewDense(1, 2, []float64{1, 0})
D := mat.NewDense(1, 1, []float64{0})

sys, err := New(A, B, C, D, 0)
if err != nil {
t.Fatal(err)
}

A.Set(0, 0, 99)
B.Set(0, 0, 99)
C.Set(0, 0, 99)
D.Set(0, 0, 99)

if got := sys.A.At(0, 0); got != 0 {
t.Fatalf("A alias detected: got %v, want 0", got)
}
if got := sys.B.At(0, 0); got != 0 {
t.Fatalf("B alias detected: got %v, want 0", got)
}
if got := sys.C.At(0, 0); got != 1 {
t.Fatalf("C alias detected: got %v, want 1", got)
}
if got := sys.D.At(0, 0); got != 0 {
t.Fatalf("D alias detected: got %v, want 0", got)
}
}

func TestNewFromSlices(t *testing.T) {
sys, err := NewFromSlices(2, 1, 1,
[]float64{0, 1, -2, -3},
Expand Down Expand Up @@ -126,6 +156,34 @@ func TestNewFromSlicesGain(t *testing.T) {
}
}

func TestNewGainCopiesInputMatrix(t *testing.T) {
D := mat.NewDense(1, 2, []float64{3, 4})

sys, err := NewGain(D, 0)
if err != nil {
t.Fatal(err)
}

D.Set(0, 0, 99)
if got := sys.D.At(0, 0); got != 3 {
t.Fatalf("D alias detected: got %v, want 3", got)
}
}

func TestNewFromSlicesGainOnlyCopiesInputSlice(t *testing.T) {
d := []float64{3, 4}

sys, err := NewFromSlices(0, 2, 1, nil, nil, nil, d, 0)
if err != nil {
t.Fatal(err)
}

d[0] = 99
if got := sys.D.At(0, 0); got != 3 {
t.Fatalf("D alias detected: got %v, want 3", got)
}
}

func TestCopy(t *testing.T) {
sys, _ := NewFromSlices(2, 1, 1,
[]float64{0, 1, -2, -3},
Expand Down
Loading