Conditionally Linear Systems

Conditionally linear systems are a special class of nonlinear systems where the dynamics can be partitioned into nonlinear and linear substates. This structure enables significant computational savings in state estimation and control design.

Theory

Consider a nonlinear dynamical system:

\[\dot{x} = f(x, u)\]

where $x \in \mathbb{R}^{n}$ is the full state vector and $u$ is the control input.

A system is conditionally linear if the state $x$ can be partitioned into two substates:

  • $x^n \in \mathbb{R}^{n_n}$: the nonlinear substate
  • $x^l \in \mathbb{R}^{n_l}$: the linear substate

such that the dynamics can be written in the form:

\[\begin{aligned} \dot{x}^n &= f_n(x^n, u) + A_n(x^n, u) x^l \\ \dot{x}^l &= f_l(x^n, u) + A_l(x^n, u) x^l \end{aligned}\]

In this representation:

  • The nonlinear substate $x^n$ may appear nonlinearly
  • The linear substate $x^l$ appears only linearly (affinely)
  • The matrices $A_n$ and $A_l$ may depend on $x^n$ and $u$, but not on $x^l$

This structure is particularly useful for:

  1. Efficient state estimation using the Marginalized Unscented Kalman Filter (MUKF)
  2. Reduced computational complexity in nonlinear control design

Partitioning Algorithm

The conditionally_linear function uses a greedy heuristic to partition the state vector:

Step 1: Individual Analysis

First, identify variables that must be in the nonlinear substate $x^n$ because they appear non-affinely when considered individually.

Step 2: Pairwise Conflict Graph

Among the remaining variables, build a "conflict graph" where an edge between variables $v_i$ and $v_j$ indicates that they cannot both be in $x^l$ (they appear jointly in a nonlinear way, e.g., through a product $v_i \cdot v_j$).

Step 3: Greedy Selection

Greedily construct $x^l$ by adding variables with the fewest conflicts first, verifying at each step that the current $x^l$ remains affine.

Preference Hints

You can guide the partitioning by providing a preference dictionary that assigns priority values to variables. Variables with lower preference values are preferred for inclusion in $x^l$. This is useful when you have domain knowledge about which variables:

  • Vary slowly (parameters)
  • Have more accurate dynamics models
  • Are computationally expensive to include in the nonlinear substate

Connection to State Estimation

The conditionally linear structure is particularly valuable for state estimation using the Marginalized Unscented Kalman Filter (MUKF). When a system has conditionally linear structure, MUKF can:

  • Reduce sigma points: For a system with $n_n$ nonlinear dimension and $n_l$ linear dimension, MUKF uses only $2n_n + 1$ sigma points instead of $2(n_n + n_l) + 1$ that a standard UKF would require
  • Enable deterministic estimation: Unlike particle filters, MUKF is deterministic and suitable for gradient-based hyperparameter optimization

Example: Quadrotor with Unknown Parameters

Consider a quadrotor where mass $m$ and drag coefficient $C_d$ are unknown. By using the reparameterization $\theta = 1/m$ and $\varphi = \theta C_d$, the system becomes conditionally linear:

Nonlinear substate: velocities $[v_x, v_y, v_z]$Linear substate: positions $[x, y, z]$, inverse mass $\theta$, and scaled drag $\varphi$

This reduces sigma points from 17 (for 8D UKF) to 7 (for 3D nonlinear MUKF), a 59% reduction!

For a complete example, see the MUKF parameter estimation documentation in LowLevelParticleFilters.jl.

Implementation in DyadControlSystems

DyadControlSystems provides the conditionally_linear function to automatically identify the conditionally linear structure of a system.

Examples

Example 1: Simple System with Bilinear Terms

This example demonstrates a system where some variables are individually affine but have pairwise conflicts due to bilinear terms.

using DyadControlSystems
using Symbolics

@variables x1 x2 x3 u[1:1]
x = [x1, x2, x3]
u = collect(u)

# System dynamics
rhs = [
    -x[1]                       # x1dot: linear in x1
    2x[1]*x[2] + sin(x[2])      # x2dot: nonlinear (x1*x2 product and sin)
    2x[2]                       # x3dot: linear coupling with x2
]

# Partition into nonlinear and linear substates
xn, xl, f, A = conditionally_linear(rhs .+ [exp(2x[2]); 0.5; 0;;]*u, x)

println("Nonlinear substate: ", xn)  # Expected: [x2]
println("Linear substate: ", xl)     # Expected: [x1, x3]

The function returns:

  • xn: Nonlinear substate variables
  • xl: Linear substate variables
  • f: Drift term $f(x^n)$
  • A: Coupling matrix $A(x^n)$ such that $\dot{x} = f(x^n) + A(x^n) x^l$

Example 2: Complex System with Multiple Couplings

@variables x1 x2 x3 x4 x5 x6 x7 x8 u[1:3]
x = [x1, x2, x3, x4, x5, x6, x7, x8]
u = collect(u)

# Complex dynamics with mixed linear and nonlinear couplings
rhs = [
    -x[1] + cos(x[1]) + x[2]*x[3] + exp(x[5])*u[1];      # Nonlinear in x1, x2, x3, x5
    x[1]*x[2] + tanh(x[3]) + u[2]*x[5];                  # Nonlinear
    x[2]^2 + sin(x[3]) + u[3];                           # Nonlinear
    (1 + x[2]^2)*x[4] + x[1] - u[1];                     # Linear in x4 (xn-dependent gain)
    exp(x[1]) + x[2]*x[5] - u[2];                        # Nonlinear
    (2 + sin(x[3]))*x[6] + x[4] + u[3];                  # Linear in x6
    (u[1] + x[1]^2)*x[7] + x[6] - x[8] + x[2];           # Linear in x7, x8
    (x[2] + u[2]^2)*x[8] + x[7] + x[3]                   # Linear in x8
]

xn, xl, f, A = conditionally_linear(rhs, x)

println("Nonlinear substate: ", xn)  # [x1, x2, x3, x5]
println("Linear substate: ", xl)      # [x4, x6, x7, x8]

Example 3: Pairwise Conflicts

This example shows how the algorithm handles variables that are individually affine but jointly non-affine:

@variables x1 x2 x3 x4 x5 x6 u[1:2]
x = [x1, x2, x3, x4, x5, x6]
u = collect(u)

rhs = [
    sin(x[1]) + x[2]^2 + u[1];              # x1, x2 clearly nonlinear
    exp(x[2]) - u[2];                        # x2 nonlinear
    (1 + x[1]^2)*x[3] + x[4] - u[1];        # x3 individually affine
    (2 + cos(x[1]))*x[4] + x[5];            # x4 individually affine
    x[6] + u[1] - 3x[5];                    # x5, x6 affine
    x[3]*x[4] + x[5] - x[6] + u[2]          # ← Bilinear term x3*x4!
]

xn, xl = conditionally_linear(rhs, x)
# Result: x3 and x4 cannot both be in xl due to the x3*x4 term
# The algorithm will place one in xn and one in xl based on conflict analysis
println("Nonlinear substate: ", xn)

preference = Dict(x[3] => 2, x[4] => 1)
# With preference_first=true, preference takes priority over conflict count, a smaller preference number makes the variable likely to be picked first
xn, xl, f, A = conditionally_linear(rhs, x; preference=preference, preference_first=true)
println("Nonlinear substate with preference: ", xn)

Use preferences when you know that certain variables:

  • Represent slowly-varying parameters
  • Have more reliable dynamics models
  • Are computationally expensive in the nonlinear substate

Practical Considerations

When to Use Conditionally Linear Formulation

The conditionally linear structure is most beneficial when:

  • You have a mix of fast and slow dynamics
  • Some variables represent parameters or unknown inputs
  • You need efficient state estimation (e.g., real-time applications)
  • The system has a large state dimension but only a few truly nonlinear dimensions

Computational Savings

For state estimation with MUKF:

  • Standard UKF: $2n + 1$ sigma points for $n$-dimensional state
  • MUKF: $2n_n + 1$ sigma points for $n_n$-dimensional nonlinear substate

For a system with state dimension $n = 8$ where $n_n = 3$ dimensions are nonlinear:

  • UKF: 17 sigma points
  • MUKF: 7 sigma points (59% reduction)

Limitations

  • Discretization: The conditionally linear structure may only hold in continuous time. Forward Euler discretization preserves it, but higher-order methods (RK4) typically don't (unless the nonlinear and linear substates are decoupled, such as when estimating sensor bias).
  • Approximation: The greedy algorithm is heuristic and may not find the optimal partitioning

Index

DyadControlSystems.conditionally_linearFunction
result = conditionally_linear(rhs, x; preference = nothing, preference_first = false)

Partition the state vector x into a nonlinear substate xn and a linear substate xl such that rhs can be written as f(xn) + A(xn) * xl.

result is a ConditionallyLinearResult struct containing the fields xn, xl, f, and A.

Heuristic:

  1. Put in xn all variables that are non-affine individually.
  2. Among the remaining variables, build pairwise "conflict" edges whenever linear_expansion(rhs, [vi, vj]) is non-affine.
  3. Greedily construct a large xl by adding low-conflict variables first, verifying linear_expansion(rhs, current_xl) at each step.

Arguments

  • rhs: Array of symbolic expressions representing the system dynamics.
  • x: Array of symbolic variables representing the full state vector.
  • preference: Optional dictionary mapping variables to preference values (lower is more preferred) for inclusion in xl. Variables not in the dictionary are considered least preferred. You may prefer to include certain variables in xl if you know that, e.g., they vary slowly, or that their modeled dynamics is coarse (such as typical models of time varying parameters or unknown inputs).
  • preference_first: If true, preference is the primary sorting key; otherwise, it is secondary after conflict count.
source
(f_result, g_result) = conditionally_linear(rhs, x, y; kwargs...)

Partition the state vector x into a nonlinear substate xn and a linear substate xl such that dynamics rhs and outputs y can be written as

\[\begin{align*} rhs &= f(xn) + A(xn) xl\ y &= g(xn) + C(xn) xl \end{align*}\]

source