journal: scaffold + 2 retroactive invention-log entries

journal/ directory, LaTeX-based, dated entries, callout boxes for
derivations / decisions / dead ends / limitations, plus an \apass{}
macro for in-line markers when a later deep-pass is needed.

Retroactive A-style entries for 2026-04-17 (controllers, linearization,
LQR, operation-mode linear reach, Lyapunov barrier) and 2026-04-20
(predicates restructure into deadbands+safety+invariants, OL-vs-CL
barrier analysis, mode-obligation taxonomy, heatup-rate-as-halfspace,
mode_boundaries, first Julia nonlinear reach attempt).

Both entries include derivations written out in math, dead-ends I
hit, code snippets with commentary, figure embeds, and terminal
output where it changed what we did next.  The goal is invention-log
depth — readable 4 years from now without the git history to help.

journal/README.md documents the conventions.  journal.tex aggregates
all entries into one PDF via latexmk.

Kept claude_memory/ separate as per earlier agreement — those are
short AI-context notes, different audience.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
This commit is contained in:
Dane Sabo 2026-04-20 21:37:59 -04:00
parent a56fcbedc2
commit fa45e96fd1
24 changed files with 2311 additions and 54 deletions

Binary file not shown.

Before

Width:  |  Height:  |  Size: 109 KiB

After

Width:  |  Height:  |  Size: 68 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 103 KiB

After

Width:  |  Height:  |  Size: 82 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 103 KiB

After

Width:  |  Height:  |  Size: 71 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 96 KiB

After

Width:  |  Height:  |  Size: 62 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 96 KiB

After

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 42 KiB

After

Width:  |  Height:  |  Size: 34 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 41 KiB

After

Width:  |  Height:  |  Size: 34 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 76 KiB

After

Width:  |  Height:  |  Size: 74 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 62 KiB

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 34 KiB

After

Width:  |  Height:  |  Size: 22 KiB

15
journal/.gitignore vendored Normal file
View File

@ -0,0 +1,15 @@
# LaTeX build artifacts
*.aux
*.bbl
*.bcf
*.blg
*.fdb_latexmk
*.fls
*.log
*.out
*.run.xml
*.synctex.gz
*.toc
*.lof
*.lot
*.pdf

124
journal/README.md Normal file
View File

@ -0,0 +1,124 @@
# Lab Journal
The HAHACS invention log for the `pwr-hybrid-3-demo` preliminary
example. Each dated session gets an entry. The goal: a reader in 2030
should be able to rebuild the thesis work from this journal alone.
## Structure
```
journal/
preamble.tex shared LaTeX setup (fonts, listings, callouts, macros)
journal.tex top-level aggregator (builds all entries into one PDF)
entries/ dated session entries, one file per session
YYYY-MM-DD-{topic-slug}.tex
figures/ journal-specific figures (referenced from entries)
README.md this file
```
## Conventions
### Filename
`entries/YYYY-MM-DD-{topic-slug}.tex`. One file per session. If a day has multiple distinct sessions, use time-of-day in the slug (e.g., `2026-04-20-morning-predicates.tex` and `2026-04-20-evening-mega-session.tex`).
### Entry skeleton
```tex
\session{2026-04-17}{duration}{one-line summary}
\section{Session: ... (YYYY-MM-DD)}
\label{sec:YYYYMMDD}
\subsection*{Goal}
What I set out to do and why.
\subsection*{What landed}
...
\subsection*{Key decisions}
...
\subsection*{Dead ends}
...
\subsection*{Derivations}
...
\subsection*{Results}
...
\subsection*{Limitations recorded}
...
\subsection*{Open at close}
...
```
Entries compile standalone (each starts with `\input{../preamble.tex}` wrapped in a conditional so it only pulls preamble when not already loaded by `journal.tex`), or together via `journal.tex`.
### Two entry styles
- **A-style (deep / invention-log)**: full derivations, code commentary, dead-ends, embedded figures, terminal output where useful. Used for retroactive entries and sessions that land meaningful artifacts.
- **B-style (narrative + pointers)**: end-of-session notes. Uses `\apass{...}` callouts to flag spots that need a later A-pass.
### Callout boxes
From `preamble.tex`:
| Environment | Use |
|---|---|
| `derivation` | Math derivations |
| `decision` | Design choices with rationale + alternatives |
| `deadend` | Paths that didn't work |
| `limitation` | Soundness gaps, known-approximate behavior |
Plus the inline `\apass{text}` marker for A-pass TODOs.
### Code inclusion
- `\juliafile[options]{path/to/file.jl}` — includes a Julia source file as a numbered listing.
- `\matlabfile[...]{...}` — for MATLAB sources.
- Or inline with `lstlisting` environment and `language=Julia` for snippets.
Always include the path as the listing caption so readers can find the file.
### Figures
Figures live in `../docs/figures/` (shared with the thesis) or `figures/` (journal-only). The preamble sets `\graphicspath` to check both.
Always include:
1. A descriptive caption (what's on axes, what's being shown).
2. A discussion in the surrounding prose — *what the figure proves or illustrates*. Figures without discussion are noise.
### Terminal output
For a numerical result or an error that drove a decision, include the actual terminal text in a `lstlisting` block with `style=terminal`:
```tex
\begin{lstlisting}[style=terminal]
TMJets: 10583 reach-sets
T_c envelope: [274.45, 295.0] C
FAILED: AssertionError: radius must be nonnegative
\end{lstlisting}
```
Don't include full logs — only the lines that changed what you did next.
## Build
```bash
cd journal
latexmk -pdf journal.tex # whole journal as one PDF
latexmk -pdf entries/2026-04-17-controllers-linear-reach.tex # one entry
```
Requires TeX Live with `tcolorbox`, `listings`, `inconsolata`, `siunitx`, `cleveref`, `hyperref`, `fancyhdr`. All in the standard distribution.
## Not a replacement for
- `claude_memory/` — short AI-context notes, Markdown, different audience.
- `reachability/WALKTHROUGH.md` — standalone doc summarizing current state of reach analysis.
- Git commit messages — per-commit rationale for code changes.
The journal is the *chronological narrative* of the work. The others are snapshots, summaries, or pointers. They're all legitimate; they do different things.

View File

@ -0,0 +1,681 @@
% ---------------------------------------------------------------------------
% 2026-04-17 — Controllers + linearization + operation-mode linear reach
% Deep / A-style invention-log entry.
% ---------------------------------------------------------------------------
\session{2026-04-17}{full afternoon, $\sim$5 hr}{Build out the three
missing DRC controllers (shutdown, heatup, scram), add a numerical
linearization, design an LQR, and discharge the operation-mode safety
obligation with a hand-rolled zonotope reach. Try a Lyapunov-ellipsoid
barrier certificate; find it fundamentally too coarse for this plant.}
\section{2026-04-17 — Controllers, linearization, operation-mode reach}
\label{sec:20260417}
\subsection*{Starting state}
Coming into this session the repository had:
\begin{itemize}
\item A 10-state PKE + thermal-hydraulics plant model
(\texttt{plant-model/pke\_th\_rhs.m}) and its parameters
(\texttt{plant-model/pke\_params.m}).
\item Two controllers: \texttt{ctrl\_null.m} (u=0 baseline) and
\texttt{ctrl\_operation.m} (plain P on $T_{\mathrm{avg}}$).
\item A FRET synthesis pipeline producing a discrete controller
(DRC) with four modes (\texttt{q\_shutdown}, \texttt{q\_heatup},
\texttt{q\_operation}, \texttt{q\_scram}) and seven transitions.
\item An empty \texttt{reachability/} directory. The thesis calls
for per-mode reach analysis; nothing has been done yet.
\end{itemize}
\subsection*{Goal}
Move the reachability thrust from zero to a first working artifact.
To do that, the continuous side needs all four modes' controllers
built out (can't reach-analyze a mode with no controller), a
linearization tool (for LQR design and for linear reach set
propagation), and a choice of reach tool. Build all that, then
discharge one mode's safety obligation.
\subsection*{Plant-model recap (what we're controlling)}
The plant is a lumped point-kinetic reactor coupled to a three-node
thermal loop. State vector $x \in \mathbb{R}^{10}$:
$$x = \bigl[\,n,\; C_1,\; C_2,\; C_3,\; C_4,\; C_5,\; C_6,\; T_f,\;
T_c,\; T_{\mathrm{cold}}\,\bigr]^\top$$
with $n$ normalized power, $C_i$ the six delayed-neutron precursor
concentrations, $T_f$ fuel temperature, $T_c$ average coolant
temperature, $T_{\mathrm{cold}}$ cold-leg coolant temperature.
Hot-leg temperature is algebraic: $T_{\mathrm{hot}} = 2T_c - T_{\mathrm{cold}}$
(linear coolant profile).
\begin{derivation}
The full RHS $\dot x = f(x, u, w)$ is:
\begin{align*}
\rho &= u + \alpha_f(T_f - T_{f0}) + \alpha_c(T_c - T_{c0}) \\
\dot n &= \frac{\rho - \beta}{\Lambda} n + \sum_{i=1}^{6} \lambda_i C_i \\
\dot C_i &= \frac{\beta_i}{\Lambda} n - \lambda_i C_i \quad (i = 1,\dots,6) \\
\dot T_f &= \frac{P_0 n - hA(T_f - T_c)}{M_f c_f} \\
\dot T_c &= \frac{hA(T_f - T_c) - 2 W c_c (T_c - T_{\mathrm{cold}})}{M_c c_c} \\
\dot T_{\mathrm{cold}} &= \frac{W c_c (T_{\mathrm{hot}} - T_{\mathrm{cold}}) - Q_{\mathrm{sg}}(t)}{M_{\mathrm{sg}} c_c}
\end{align*}
$u$ is external rod-worth reactivity (the control input).
$Q_{\mathrm{sg}}(t)$ is the steam-generator heat-removal disturbance.
All other symbols are plant constants (see
\texttt{plant-model/pke\_params.m} for sourcing; most are representative
of a 2-loop Westinghouse-class PWR).
\end{derivation}
\subsection*{Part 1: The three new controllers}
The DRC has four modes; we had only one mode's continuous controller
written. Need to fill in shutdown, heatup, and scram.
\subsubsection*{Shutdown and scram — trivial, picked for physical defensibility}
Both modes are passive: the reactor is parked deeply subcritical, rods
are fully in, no feedback control is applied. Each is a one-liner.
\begin{lstlisting}[language=Matlab,caption={\texttt{plant-model/controllers/ctrl\_shutdown.m}}]
u = -5 * plant.beta; % ~5 $ subcritical
\end{lstlisting}
\begin{lstlisting}[language=Matlab,caption={\texttt{plant-model/controllers/ctrl\_scram.m}}]
u = -8 * plant.beta; % ~8 $, typical regulatory 8-10 $ rod worth
\end{lstlisting}
\begin{decision}
Constants, not feedback laws. Rationale:
\begin{itemize}
\item Real shutdown/scram behavior is ``rods fully inserted, worth
$\sim$5--10~\$, no further action.'' A feedback law would be
un-physical.
\item Constants are trivial to reach-analyze. Closed-loop matrix
$A_{\mathrm{cl}} = A$ (controller adds nothing to dynamics).
\item At cold-start conditions ($T = T_{\mathrm{cold0}} \approx 290\,^\circ\mathrm{C}$),
the linearized feedback from $\alpha_f, \alpha_c$ is about
$+2.79\,\$$ of ``wants-to-be-supercritical'' reactivity. So
$u = -5\,\$$ gives total $\rho \approx -2.2\,\$$, comfortably
subcritical with margin for uncertainty. $-8\,\$$ on scram
gives $\sim$$-5\,\$$ total — conservative.
\item We could tighten to $-3\,\$$ and still be subcritical at
warm temperatures, but the thesis wants a safety margin
robust to any plausible state.
\end{itemize}
\end{decision}
\subsubsection*{Heatup — the interesting controller}
Heatup is the one transition mode that does real control work: drive
$T_{\mathrm{avg}}$ from hot-standby conditions up to operating
conditions while keeping the reactor bounded. This one needs design.
The structure I landed on:
\begin{equation}
u(t, x) = \mathrm{sat}\Bigl(u_{\mathrm{ff}}(x) + K_p\bigl(T_{\mathrm{ref}}(t) - T_c\bigr),\; u_{\min},\; u_{\max}\Bigr)
\end{equation}
with three ingredients:
\textbf{Feedback linearization.} Cancel the intrinsic temperature
feedback exactly:
\begin{equation}
u_{\mathrm{ff}}(x) = -\alpha_f(T_f - T_{f0}) - \alpha_c(T_c - T_{c0})
\end{equation}
so that after substitution into the $\rho$ equation,
\begin{equation}
\rho_{\mathrm{total}} = u_{\mathrm{ff}} + K_p(T_{\mathrm{ref}} - T_c) + \underbrace{\alpha_f(T_f - T_{f0}) + \alpha_c(T_c - T_{c0})}_{\text{cancels } u_{\mathrm{ff}}}
= K_p \cdot e
\end{equation}
where $e = T_{\mathrm{ref}} - T_c$. The cancellation is exact only if
the controller's $(\alpha_f, \alpha_c)$ match the plant's. This is the
seat of the controller's robustness risk; see \cref{sub:alpha-drift}.
\textbf{Ramped reference.}
\begin{equation}
T_{\mathrm{ref}}(t) = \min\bigl(T_{\mathrm{start}} + r \cdot t,\; T_{\mathrm{target}}\bigr)
\end{equation}
with $r$ = 28~\unit{\celsius/\hour} (\num{7.78e-3}~\unit{\celsius/\second}),
the tech-spec heatup rate. Clamped at $T_{\mathrm{target}}$ once the
ramp reaches operating conditions.
\textbf{Saturation on $u$.} Cap $|u|$ at $0.5\beta$ on the positive
side and $5\beta$ on the negative side. The upper cap keeps
$\rho < \beta$ (the prompt-criticality line) under any plausible
state, which bounds the neutron-kinetics excursion rate for later
reach analysis.
\begin{deadend}
\textbf{First-pass heatup controller, before saturation was added.}
The initial design was just feedback-linearization + P with no
saturation, starting from an initial condition $n = 10^{-6}$ (decay-heat
level) at $T_{\mathrm{cold0}} = 290\,^\circ\mathrm{C}$ everywhere.
What went wrong: at that cold IC, the feedback terms give about
$+2.79\,\$$ of positive reactivity. With $u_{\mathrm{ff}}$ cancelling
those, $u = K_p \cdot e$ with $K_p = \num{1e-4}$. Error grows as
$T_{\mathrm{ref}}$ ramps away from $T_c$ (which is still cold because
the reactor has no power to heat it yet). Reactivity builds slowly,
but because $n$ is tiny, power is tiny; the system takes
\textbf{about 20 minutes} to generate enough power to heat the coolant,
during which $T_c$ stays at 290~\unit{\celsius} while $T_{\mathrm{ref}}$
ramps to 297. Once power catches up, the large accumulated error
produces a power spike (visible in the first-pass figure: $n$ peaks
near $0.018 = 1.8\%$), and the thermal mass overshoots
$T_{\mathrm{target}}$ by about 7~\unit{\celsius} before the controller
pulls it back.
Why it doesn't actually match physics: real plant heatup doesn't
start from $n \approx 0$. Operators take the reactor critical at
low power \emph{in shutdown mode}, by slowly withdrawing rods, then
the DRC transitions to heatup with $n \sim 0.1\,\%$ already
established. Two fixes landed:
\begin{enumerate}
\item Saturation on $u$: prevents the accumulated-error spike.
\item Start heatup sims from a ``critical-at-low-power'' IC
($n = 10^{-3}$). \texttt{main\_mode\_sweep.m} uses this IC.
\end{enumerate}
The feedback-linearization controller alone doesn't know any of this
— it just does what the math says. The fixes are a controller design
change (saturation) and an IC assumption. A fancier heatup controller
would also include ramp-rate feedforward, but we don't need it yet.
\end{deadend}
\begin{decision}
\textbf{No integrator.} We stay with P-only (no PI), even knowing
there will be structural ramp-tracking lag on the order of
$r/K_p/\omega_{\mathrm{thermal}}$. Rationale:
\begin{itemize}
\item The plant already has strong integrators via thermal mass
($M_c c_c$, $M_{\mathrm{sg}} c_c$). PI would double-integrate.
\item PI adds state, turning the 10-state reach problem into 11 states.
Modest cost by itself.
\item The dealbreaker: \textbf{anti-windup saturation makes PI a
hybrid system}. Each saturation region (unsat / low-sat /
high-sat) is its own continuous mode with its own dynamics.
Our outer hybrid automaton is the DRC; nesting an inner hybrid
system inside each DRC mode doubles the verification
complexity.
\item The DRC exits heatup on a predicate window
(\texttt{t\_avg\_in\_range} $\wedge$ \texttt{p\_above\_crit}),
not on zero steady-state error. So the structural lag is
acceptable.
\end{itemize}
\end{decision}
Final controller (after iteration) lives in
\texttt{plant-model/controllers/ctrl\_heatup.m}. The relevant body:
\begin{lstlisting}[language=Matlab,caption={\texttt{ctrl\_heatup.m} body (abbreviated)}]
Kp = 1e-4;
T_f = x(8); T_c = x(9); T_avg = T_c;
u_ff = -plant.alpha_f*(T_f - plant.T_f0) ...
-plant.alpha_c*(T_avg - plant.T_c0);
T_ref = min(ref.T_start + ref.ramp_rate * t, ref.T_target);
e = T_ref - T_avg;
u_unsat = u_ff + Kp * e;
u = min(max(u_unsat, -5*plant.beta), 0.5*plant.beta);
\end{lstlisting}
\subsection*{Part 2: Linearization}
We need $(A, B, B_w)$ matrices for (a) LQR gain synthesis and (b)
linear reach set propagation.
\begin{derivation}
Central finite differences on $f(x, u, w)$ at a chosen operating
point $(x^\star, u^\star, w^\star)$:
\begin{align*}
A_{:,k} &\approx \frac{f(x^\star + h_k e_k, u^\star, w^\star) - f(x^\star - h_k e_k, u^\star, w^\star)}{2 h_k} \\
B &\approx \frac{f(x^\star, u^\star + h_u, w^\star) - f(x^\star, u^\star - h_u, w^\star)}{2 h_u} \\
B_w &\approx \frac{f(x^\star, u^\star, w^\star + h_w) - f(x^\star, u^\star, w^\star - h_w)}{2 h_w}
\end{align*}
with $h_k = \max(\epsilon_{\mathrm{rel}} |x^\star_k|,\; \epsilon_{\mathrm{abs}})$
to handle the wildly different magnitudes in $x$ (e.g.\ $n \sim 1$
vs.\ $C_1 \sim 10^2$ vs.\ $T_f \sim 3 \times 10^2$).
\end{derivation}
Validation: simulate the linear model and the nonlinear model in
parallel under a small $Q_{\mathrm{sg}}$ step and compare deviations
from $x^\star$. \Cref{fig:linearize-sanity} shows the result.
\begin{figure}[h]
\centering
\includegraphics[width=0.85\linewidth]{linearize_sanity.png}
\caption{Linear vs.\ nonlinear sanity check under a 5\% $Q_{\mathrm{sg}}$
down-step at $t = 30$~\unit{\second}, $u = 0$. Linear (red dashed)
tracks nonlinear (blue solid) within $4 \times 10^{-4}$ relative
error at 60~\unit{\second}, improving to $5 \times 10^{-6}$ by
300~\unit{\second} as the system relaxes. The match is best on $n$
(tightly coupled), loosest on $C_3$ (slow precursor). Eigenvalues of
$A$ span $[-65.93, -0.0124]$~\unit{\per\second} — stiffness ratio
$\sim$5000. Conclusion: linearization is quantitatively trustworthy
for perturbations around $x^\star$ in a $\pm 50\,^\circ\mathrm{C}$
window.}
\label{fig:linearize-sanity}
\end{figure}
The code is a straightforward loop (see
\texttt{plant-model/pke\_linearize.m}); nothing subtle, but the
magnitude-aware step size matters — using a uniform $h = 10^{-6}$
either loses precision on the small states or truncates on the big
ones.
\subsection*{Part 3: LQR controller for operation mode}
With $(A, B)$ in hand, design a linear quadratic regulator around the
operating point.
\begin{derivation}
Solve the continuous-time algebraic Riccati equation (CARE) for
$X \succeq 0$:
$$A^\top X + X A - X B R^{-1} B^\top X + Q = 0$$
then set gain $K = R^{-1} B^\top X$. The closed-loop control law
$u = -K(x - x^\star)$ minimizes
$$\int_0^\infty \left[(x - x^\star)^\top Q (x - x^\star) + u^\top R u\right] dt$$
and guarantees $A_{\mathrm{cl}} = A - BK$ is Hurwitz whenever $(A,B)$
is stabilizable and $Q \succeq 0$.
\end{derivation}
Weight choices:
\begin{lstlisting}[language=Matlab,caption={LQR weights, from \texttt{ctrl\_operation\_lqr.m}}]
Q = diag([1, % n
1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, % precursors C_1..C_6
1e-2, % T_f
1e2, % T_c (the primary objective)
1]); % T_cold
R = 1e6;
\end{lstlisting}
\begin{decision}
$Q(9,9) = 10^2$ for $T_c$ is the primary design knob — heavy because
we care about the coolant average deviation. Precursor weights at
$10^{-3}$ because they're informational (not directly regulated).
$T_{\mathrm{cold}}$ at 1 because it's secondary but couples to $T_c$.
$R = 10^6$ balances so $|u|$ stays in the few-cent range — below prompt,
above sensor noise. Ballpark numbers; we can retune if the reach tube
comes out too tight or too loose.
\end{decision}
Head-to-head against plain P on the same 100\% $\to$ 80\%
$Q_{\mathrm{sg}}$ step (\cref{fig:p-vs-lqr}):
\begin{figure}[h]
\centering
\includegraphics[width=0.85\linewidth]{mode_sweep_op_P_vs_LQR.png}
\caption{P vs.\ LQR on operation mode under a 100\%$\to$80\%
$Q_{\mathrm{sg}}$ step at $t = 30$~\unit{\second}. Plain P
(\texttt{ctrl\_operation.m}) has a 5~\unit{\degreeFahrenheit} peak
overshoot and 0.8~\unit{\degreeFahrenheit} steady-state lag. LQR
(\texttt{ctrl\_operation\_lqr.m}) holds $T_{\mathrm{avg}}$
essentially at setpoint throughout. Zero extra state in either;
LQR is just using all ten state measurements instead of one.}
\label{fig:p-vs-lqr}
\end{figure}
\subsection*{Part 4: Running all modes end-to-end}
\texttt{plant-model/main\_mode\_sweep.m} exercises all five controllers
(null, shutdown, heatup, operation-P, operation-LQR, scram) back-to-back
from mode-appropriate ICs, and saves figures. The normalized-power
overview (\cref{fig:power-overview}) captures the whole sweep:
\begin{figure}[h]
\centering
\includegraphics[width=0.95\linewidth]{mode_sweep_power_overview.png}
\caption{Normalized power $n(t)$ across the four DRC modes
plus baseline. \emph{Shutdown} (top left, log scale): $n$ decays
from $10^{-6}$ to $10^{-12}$ over 10~\unit{\minute}. \emph{Heatup}
(top right): small power burst around minute 22 as the reactor
goes critical and heats. \emph{Operation} (bottom left): $Q_{\mathrm{sg}}$
step at 30~\unit{\second} drops $n$ to 78\% briefly before settling
at 80\%. \emph{Scram} (bottom right, log scale): $n$ drops $1 \to 10^{-6}$
via prompt jump + delayed-neutron tail over 10~\unit{\minute}. All
four behave as textbook would predict.}
\label{fig:power-overview}
\end{figure}
\subsection*{Part 5: Tool choice for reach analysis}
Three candidate tools were evaluated:
\begin{itemize}
\item \textbf{CORA} (MATLAB) — mature, stays in the existing
language, handles linear + nonlinear. Downside: $\sim$0.5~GB
install, heavy.
\item \textbf{JuliaReach} — newer, faster for large reach sets,
rigorous Taylor-model support. Downside: requires porting
the plant model to Julia.
\item \textbf{Flow* / SpaceEx} — C++ / no-longer-maintained,
both add toolchain friction.
\end{itemize}
\begin{decision}
For this first artifact: \textbf{write the reach tube by hand in pure
MATLAB}. Rationale: linear reach with bounded disturbance has a clean
analytic form — matrix exponential on state, augmented-matrix integral
for the disturbance contribution — that compiles to about 50 lines of
MATLAB. No toolbox install, no language switch. The result is a
sound box-shaped over-approximation.
If/when we need nonlinear reach, that's the point to stand up
JuliaReach. (Spoiler for the reader: this did happen in the
\texttt{2026-04-20-evening} session.)
\end{decision}
\subsection*{Part 6: The zonotope reach propagator}
For the LQR-closed-loop linear system
$\dot{\delta x} = A_{\mathrm{cl}} \delta x + B_w w$ with $\delta x(0) \in X_0$
(axis-aligned box) and $w \in [w_{\mathrm{lo}}, w_{\mathrm{hi}}]$, the
analytic solution splits into a homogeneous piece and a disturbance
integral:
\begin{derivation}
\begin{equation}
\delta x(t) = e^{A_{\mathrm{cl}} t} \delta x(0)
+ \int_0^t e^{A_{\mathrm{cl}}(t-s)} B_w w(s)\, ds.
\end{equation}
Discretize with step $\Delta t$ and let
$A_{\Delta} = e^{A_{\mathrm{cl}} \Delta t}$. The disturbance integral
over one step is
$$G_\Delta = \int_0^{\Delta t} e^{A_{\mathrm{cl}} s} B_w \, ds.$$
\textbf{Van Loan's trick (1978):} expand the matrix exponential of an
augmented matrix,
\begin{equation}
\exp\!\left(\begin{bmatrix} A & B_w \\ 0 & 0 \end{bmatrix} \Delta t\right)
= \begin{bmatrix} e^{A \Delta t} & G_\Delta \\ 0 & 1 \end{bmatrix}.
\end{equation}
Read the upper-right block — $G_\Delta$ is exact to machine precision
without numerical quadrature.
\end{derivation}
Now propagate a box $\delta x \in [c - h,\ c + h]$ (center $c$,
halfwidth $h$) through the linear map $M$:
\begin{derivation}
If $y = M \delta x$ and $\delta x_j \in [c_j - h_j,\ c_j + h_j]$, then
$$y_i = \sum_j M_{ij} \delta x_j \quad \Longrightarrow \quad y_i \in \bigl[\,M c \mp |M| h\,\bigr]_i.$$
The $\pm$ signs of $M_{ij}$ align with opposite corners of the
input box, so the sum extremum takes the absolute value of each
coefficient times the halfwidth. Conclusion: box propagation uses
\emph{elementwise} $|M|$, not signed $M$.
\end{derivation}
\begin{deadend}
\textbf{First version of \texttt{reach\_linear.m} used signed
$A_\Delta$ for halfwidth propagation.} Result: the reach tube came
out suspiciously tight — maximum $|T_c - T_{c0}|$ over 600~\unit{\second}
was exactly equal to the initial halfwidth, as if the disturbance
wasn't contributing at all.
Diagnosed after about 15~\unit{\minute} of confusion: when I wrote
$S_{\mathrm{half}} \leftarrow A_\Delta S_{\mathrm{half}} + G_\Delta w_{\mathrm{half}}$
with \emph{signed} $A_\Delta$, the positive and negative entries of
$A_\Delta$ across successive steps happened to cancel, so
$S_{\mathrm{half}}$ stayed near zero. The fix is to use elementwise
absolute values per the derivation above:
$$S_{\mathrm{half}} \leftarrow |A_\Delta| S_{\mathrm{half}} + |G_\Delta| w_{\mathrm{half}}.$$
Once the abs was added the disturbance halfwidth grew monotonically
as expected, and the reach tube gained a sensible envelope. This is
a case of ``the bug is easy to catch in the math, harder to catch
when you copy-pasted from the center-propagation code.''
\end{deadend}
The final propagator is the core of
\texttt{reachability/reach\_linear.m} (about 50~lines). The per-step
update is compact:
\begin{lstlisting}[language=Matlab,caption={Halfwidth-propagation core of \texttt{reach\_linear.m}}]
A_step = expm(A_cl * dt);
A_abs_step = abs(A_step);
M_aug = expm([A_cl, B_w; zeros(1, n+1)] * dt);
G_step = M_aug(1:n, n+1);
G_abs_step = abs(G_step);
for k = 2:M
x_center_now = A_step * x_center_now;
halfwidth_now = A_abs_step * halfwidth_now;
S_center = A_step * S_center + G_step * w_mid;
S_half = A_abs_step * S_half + G_abs_step * w_half;
center(:, k) = x_center_now + S_center;
R_lo(:, k) = center(:, k) - halfwidth_now - S_half;
R_hi(:, k) = center(:, k) + halfwidth_now + S_half;
end
\end{lstlisting}
\subsection*{Part 7: Operation-mode reach — discharging the safety obligation}
Entry box around $x_{\mathrm{op}}$:
\begin{itemize}
\item $n$: $\pm 1\%$ of nominal.
\item $C_i$: $\pm 0.1\%$ of equilibrium (precursors equilibrate
fast; tight entry).
\item $T_f,\ T_c,\ T_{\mathrm{cold}}$: $\pm 0.1$~\unit{\kelvin}.
\end{itemize}
Disturbance: $Q_{\mathrm{sg}} \in [0.85 P_0,\ 1.00 P_0]$ — a 15\%
load-down envelope (grid-following). Horizon: 600~\unit{\second}.
The reach envelope on $T_c$ is shown in \cref{fig:reach-tc}.
\begin{figure}[h]
\centering
\includegraphics[width=0.95\linewidth]{reach_operation_Tc.png}
\caption{Operation-mode reach tube on $T_{\mathrm{avg}}$, two views.
\emph{Left:} safety-band scale — reach tube (pink) is barely visible
because LQR holds it tight against the dashed $\pm 5$~\unit{\celsius}
safety band. \emph{Right:} zoomed to reveal the actual tube.
Halfwidth at $t=0$ is 0.1~\unit{\kelvin} (the entry box);
halfwidth at $t=600$~\unit{\second} is 0.033~\unit{\kelvin}. The
tube \emph{contracts} on the regulated direction — the signature
of tight feedback control. Max $|\delta T_c|$ over the horizon:
0.1~\unit{\kelvin} (the initial halfwidth dominates).}
\label{fig:reach-tc}
\end{figure}
Per-halfspace margins against \texttt{inv2\_holds} (the operation-mode
safety envelope):
\begin{lstlisting}[style=terminal]
=== Operation-mode reach vs inv2_holds safety limits ===
[fuel_centerline] a'x <= 1200.000 | max a'x = 328.934 | margin = +871.066 OK
[t_avg_high_trip] a'x <= 320.000 | max a'x = 308.449 | margin = +11.551 OK
[t_avg_low_trip] a'x <= -280.000 | max a'x = -308.249 | margin = +28.249 OK
[n_high_trip] a'x <= 1.150 | max a'x = 1.012 | margin = +0.138 OK
[n_low_operation] a'x <= -0.150 | max a'x = -0.842 | margin = +0.692 OK
[cold_leg_subcooled] a'x <= 305.000 | max a'x = 292.852 | margin = +12.148 OK
\end{lstlisting}
All six safety halfspaces pass. Tightest margin is
\texttt{n\_high\_trip} — LQR lets $n$ swing up to $\sim$1.01 to
compensate for load variation, leaving 12\% margin to the high-flux
trip. Temperatures have 10--870~\unit{\kelvin} margin each.
\textbf{Operation-mode obligation discharged}, subject to the
linearization caveat in \cref{sec:limitations-17}.
Per-state reach-set evolution (final halfwidth vs.\ initial):
\begin{center}
\small
\begin{tabular}{l r r r}
\hline
state & init halfwidth & final halfwidth & ratio \\
\hline
$n$ & $0.010$ & $0.083$ & 8.3$\times$ expand \\
$C_1 \dots C_6$ & varies & varies & 160--200$\times$ expand \\
$T_f$ & 0.1~\unit{\kelvin} & 2.08~\unit{\kelvin} & 21$\times$ expand \\
$\boldsymbol{T_c}$ & $\mathbf{0.1}$~\unit{\kelvin} & $\mathbf{0.033}$~\unit{\kelvin} & $\mathbf{0.33\times}$ \textbf{contract} \\
$T_{\mathrm{cold}}$ & 0.1~\unit{\kelvin} & 1.47~\unit{\kelvin} & 15$\times$ expand \\
\hline
\end{tabular}
\end{center}
$T_c$ \emph{contracts} — LQR drags the regulated direction toward
setpoint faster than disturbance can push it. Uncontrolled states
drift. Precursor expansion ($\sim$$200\times$) is immaterial for
safety (no predicate uses them).
\subsection*{Part 8: Lyapunov barrier attempt}
A reach tube is a numerical certificate: compute, check. A
\emph{barrier certificate} is analytic: produce a function $B(x)$ such
that $B \leq 0$ on the initial set, $B > 0$ on the unsafe set, and
$\dot B \leq 0$ when $B = 0$. Forward-invariance of the safe set
follows from the dynamics without iterating them.
For linear systems with bounded disturbance, the canonical candidate
is a Lyapunov quadratic.
\begin{derivation}
Let $V(\delta x) = \delta x^\top P \delta x$ with $P \succ 0$ solving
$A_{\mathrm{cl}}^\top P + P A_{\mathrm{cl}} + \bar Q = 0$. Along
trajectories of $\dot{\delta x} = A_{\mathrm{cl}} \delta x + B_w w$:
\begin{align}
\dot V &= -\delta x^\top \bar Q \delta x + 2 \delta x^\top P B_w w.
\end{align}
Bound each piece. The dissipation term using the generalized
eigenvalue
$\mu = \lambda_{\min}\bigl(P^{-1/2} \bar Q P^{-1/2}\bigr)$:
$$-\delta x^\top \bar Q \delta x \leq -\mu V.$$
The disturbance kick, Cauchy-Schwarz in the $P$-metric:
$$2 \delta x^\top P B_w w \leq 2 \bar w \sqrt{B_w^\top P B_w}\sqrt{V}.$$
Combining:
$$\dot V \leq -\mu V + 2 \bar w \sqrt{B_w^\top P B_w}\sqrt{V}.$$
Set $s = \sqrt{V}$, requiring $\dot s \leq 0$:
$$s \geq \frac{2 \bar w \sqrt{B_w^\top P B_w}}{\mu}
\quad \Longleftrightarrow \quad V \geq \left(\frac{2 \bar w \sqrt{B_w^\top P B_w}}{\mu}\right)^2 =: c_{\mathrm{inv}}.$$
The sub-level set $\{ V \leq c_{\mathrm{inv}} \}$ is forward-invariant
under any admissible disturbance.
\end{derivation}
So the recipe is: solve Lyapunov, compute $c_{\mathrm{inv}}$, compute
the worst-case deviation of $T_c$ (or any linear functional of state)
on the resulting ellipsoid, and check whether it fits inside the
safety slab.
\begin{derivation}
Max of a linear functional $a^\top \delta x$ over the ellipsoid
$\{\delta x : \delta x^\top P \delta x \leq \gamma\}$:
$$\max a^\top \delta x = \sqrt{\gamma \cdot a^\top P^{-1} a}.$$
(Lagrange multipliers: the maximum is achieved at
$\delta x = \sqrt{\gamma / a^\top P^{-1} a} \cdot P^{-1} a$.)
\end{derivation}
\textbf{Result:} the best quadratic barrier — across a sweep of
$\bar Q(9,9)$ from 10 to $10^6$ — allows max $|T_c - T_{c0}| \approx 33$~\unit{\kelvin},
more than six times the 5~\unit{\kelvin} safety band. On the hard
safety halfspaces (\texttt{inv2\_holds}), it says $n$ could deviate by
$\pm 1242$~$\times$ nominal — physically meaningless.
\begin{limitation}
\textbf{The quadratic Lyapunov barrier fails on this plant. This is
a structural finding, not a tuning failure.}
The safety spec is anisotropic: a thin slab $|T_c| \leq 5$~\unit{\kelvin}
in a 10-D state space where $T_c$ is one direction and the other nine
are precursors / fuel temperature / cold-leg. Any
quadratic $V$ yields axis-uniform ellipsoidal level sets. To contain
the disturbance-driven invariant set, the ellipsoid must be \emph{fat
in the slow directions} (precursors, where Lyapunov dissipation is
weakest). Projecting that fat ellipsoid back onto $T_c$ yields a
range much larger than the physical $T_c$ behavior.
Confirmed the issue is not controller tuning by running the barrier
open-loop (no LQR): the bound becomes $\pm 27{,}000{,}000\,n$. LQR
helps by $\sim$20{,}000$\times$, but still leaves a 3-4 order-of-magnitude
gap to usability. The ceiling is plant anisotropy: prompt-neutron
timescale $\Lambda = 10^{-4}$~\unit{\second} vs.\ thermal timescales
$\sim$10--100~\unit{\second}, a factor-of-$10^4$ spread that forces
$P$ to be ill-conditioned regardless of controller design.
\textbf{Fix:} non-quadratic barrier. Two candidate approaches:
\begin{itemize}
\item \textbf{Polytopic barrier:} $B(\delta x) = \max_i (a_i^\top \delta x - b_i)$.
Piecewise-linear, can match a slab shape directly.
Requires polyhedral-set tooling.
\item \textbf{SOS polynomial barrier:} $B$ a polynomial of
degree $\geq 4$, coefficients found by sum-of-squares
optimization. Requires an SOS solver (Mosek, SDPT3).
\end{itemize}
Neither is implemented; both are in-scope for the thesis chapter.
The quadratic-Lyapunov failure, stated quantitatively, is the clean
motivation.
\end{limitation}
\subsection*{Session result}
Artifacts landing, in order:
\begin{enumerate}
\item \texttt{plant-model/controllers/ctrl\_shutdown.m},
\texttt{ctrl\_scram.m}, \texttt{ctrl\_heatup.m} (three new
controllers).
\item \texttt{plant-model/pke\_linearize.m} and
\texttt{plant-model/test\_linearize.m}.
\item \texttt{plant-model/controllers/ctrl\_operation\_lqr.m}.
\item \texttt{plant-model/main\_mode\_sweep.m}.
\item \texttt{reachability/reach\_linear.m} and
\texttt{reachability/reach\_operation.m}.
\item \texttt{reachability/barrier\_lyapunov.m}.
\item Eleven figures in \texttt{docs/figures/}.
\end{enumerate}
Key claims established:
\begin{itemize}
\item LQR closed-loop operation mode satisfies the safety obligation
under $\pm 15\%$ $Q_{\mathrm{sg}}$ variation (approximate,
via linear reach).
\item Quadratic Lyapunov barrier insufficient on this plant
(open-loop or closed-loop). Need polytopic or SOS.
\item LQR adds zero state, dominates plain P by $\sim 5\times$
on tracking.
\end{itemize}
\subsection*{Limitations recorded at close}
\label{sec:limitations-17}
\begin{limitation}
All reach results are \emph{approximate}, not sound: they are reach
tubes of the \emph{linearized} closed-loop. The linearization error
— the gap between $f_{\mathrm{nl}}(x, u)$ and $(A x + B u)$ — is not
propagated into the tube. For a real safety claim, either
(a)~nonlinear reach directly or (b)~linear reach plus Taylor-remainder
inflation. Neither is done.
\end{limitation}
\begin{limitation}
\label{sub:alpha-drift}
The feedback-linearization in \texttt{ctrl\_heatup} assumes exact
$\alpha_f, \alpha_c$. Real PWRs have $\alpha$ drift: $\sim$20\%
over burnup; $\sim$10$\times$ across soluble-boron dilution; xenon
transients worth 2--3~\$. Robust version would treat $\alpha$ as
parametric interval and propagate through reach.
\end{limitation}
\begin{limitation}
Saturation in \texttt{ctrl\_heatup} is formally a 3-mode piecewise-affine
sub-system. Operation-mode LQR is dormant-saturated (trivially); a
rigorous heatup reach would need explicit region decomposition or a
dormancy proof.
\end{limitation}
\begin{limitation}
The model's $\alpha_f, \alpha_c$ are linearized at the hot full-power
operating point. Trust region is $\pm 50$~\unit{\celsius} around $x^\star$.
True cold shutdown ($\sim$50~\unit{\celsius}) is out of scope. What
the DRC calls \texttt{q\_shutdown} we interpret as hot standby
($\sim$290~\unit{\celsius}).
\end{limitation}
\subsection*{Open at close}
\begin{itemize}
\item Nonlinear reach, at minimum on one mode, to retire the
soundness asterisk.
\item Polytopic or SOS barrier to retire the analytic-certificate
asterisk.
\item Parametric $\alpha$ uncertainty in the reach machinery.
\item Heatup reach — ramped reference needs LTV or nonlinear
treatment.
\item Shutdown + scram reach (trivial forever-invariance /
bounded-time respectively, but not yet done).
\end{itemize}

View File

@ -0,0 +1,472 @@
% ---------------------------------------------------------------------------
% 2026-04-20 — Predicates restructure, mode taxonomy, Julia nonlinear reach
% Deep / A-style invention-log entry.
% ---------------------------------------------------------------------------
\session{2026-04-20}{afternoon session, $\sim$3 hr}{Walk through the
2026-04-17 work with a critical eye, surface three structural errors
hiding in it, restructure the predicates JSON to fix them, formalize
the per-mode reach-obligation taxonomy (equilibrium vs.\ transition),
and take the first swing at Julia nonlinear reach. The Julia reach
framework works but is limited to $\sim$10-second horizons by
prompt-neutron stiffness. The remedy (singular-perturbation reduction)
is identified and deferred.}
\section{2026-04-20 — Predicates restructure, mode taxonomy, nonlinear reach}
\label{sec:20260420-afternoon}
\subsection*{How this session started}
Walking through the 2026-04-17 work slide-by-slide with a critical
reviewer looking for inconsistencies. Each section of the linear
reach story had a latent bug the first pass missed; by the end of the
walkthrough three structural errors were exposed and fixed.
\subsection*{Error 1: the barrier was checking the wrong invariant}
The 2026-04-17 barrier code compared the Lyapunov-ellipsoid reach
against a \emph{symmetric} slab $|T_c - T_{c0}| \leq 2.78$~\unit{\celsius}
— the operational deadband \texttt{t\_avg\_in\_range}. But that
predicate is used by the DRC for \emph{mode transitions}: crossing it
triggers heatup$\to$operation, not damage. The barrier should be
checking the \emph{safety limits} — one-sided halfspaces reflecting
actual trip setpoints and physical damage thresholds. These are not
symmetric:
\begin{itemize}
\item $T_f \leq 1200$~\unit{\celsius} (fuel centerline design limit).
\item $T_c \leq 320$~\unit{\celsius} (high-$T_{\mathrm{avg}}$ trip).
\item $T_c \geq 280$~\unit{\celsius} (low-$T_{\mathrm{avg}}$ trip).
\item $n \leq 1.15$ (high-flux trip).
\item $n \geq 0.15$ (operation range only).
\item $T_{\mathrm{cold}} \leq T_{\mathrm{cold0}} + 15$ (subcooling).
\end{itemize}
\begin{decision}
Restructure \texttt{reachability/predicates.json} into three categories:
\begin{description}
\item[\texttt{operational\_deadbands}] soft bands used by DRC for
mode switching. \texttt{t\_avg\_above\_min},
\texttt{t\_avg\_in\_range}, \texttt{p\_above\_crit}.
\item[\texttt{safety\_limits}] hard one-sided halfspaces. Six rows
as listed above, plus new heatup-rate ones (see Error 3).
\item[\texttt{mode\_invariants}] \texttt{inv1\_holds},
\texttt{inv2\_holds}: declared as \emph{conjunctions} of
named safety limits, so changing a limit propagates.
\end{description}
Safety proofs target \texttt{mode\_invariants}; DRC transitions
target \texttt{operational\_deadbands}. The distinction is
load-bearing.
\end{decision}
\subsection*{Error 2: the "2364$\times$ bound" should have included LQR, and didn't tell us}
After the restructure, re-running \texttt{barrier\_lyapunov.m} against
\texttt{inv2\_holds} produced:
\begin{lstlisting}[style=terminal]
=== Lyapunov barrier vs inv2_holds halfspaces ===
[fuel_centerline] max a'dx = 2244.1 margin = -1372.4 too loose
[t_avg_high_trip] max a'dx = 33.3 margin = -21.6 too loose
[n_high_trip] max a'dx = 1242.0 margin = -1242.0 too loose (!!)
[cold_leg_subcooled] max a'dx = 150.7 margin = -135.7 too loose
\end{lstlisting}
The $n_{\mathrm{high\_trip}}$ row was the stopper: the barrier says
$n$ could deviate by $\pm 1242\times$ nominal. Physically meaningless.
Fair enough to ask: is this because \emph{LQR isn't in the
barrier computation?} The code uses $A_{\mathrm{cl}} = A - BK$, but
that detail was buried and Dane rightly flagged it.
\begin{decision}
\textbf{Write \texttt{barrier\_compare\_OL\_CL.m}} to explicitly
measure LQR's contribution to the barrier. Same Qbar, same
disturbance envelope, two runs: open-loop $A$ vs.\ closed-loop
$A_{\mathrm{cl}} = A - BK$.
\end{decision}
Result (\cref{fig:ol-vs-cl}):
\begin{figure}[h]
\centering
\begin{tabular}{lrrr}
\hline
halfspace & open-loop & LQR closed-loop & ratio CL/OL \\
\hline
\texttt{fuel\_centerline} & 26{,}941{,}862 K & 1{,}137 K & $4.2 \times 10^{-5}$ \\
\texttt{t\_avg\_high\_trip} & 788{,}220 K & 33.2 K & $4.2 \times 10^{-5}$ \\
\texttt{n\_high\_trip} & 27{,}379{,}931 & 1{,}242 & $4.5 \times 10^{-5}$ \\
\texttt{cold\_leg\_subcooled} & 1{,}806{,}166 K& 77.8 K & $4.3 \times 10^{-5}$ \\
$\gamma$ (ellipsoid level) & $1.04 \times 10^{13}$ & $1.85 \times 10^{4}$ & $1.78 \times 10^{-9}$ \\
\hline
\end{tabular}
\caption{Open-loop vs.\ LQR closed-loop Lyapunov barrier bounds on
each \texttt{inv2\_holds} halfspace, same $\bar Q$ and same
disturbance envelope. LQR improves every bound by a uniform
$\sim$20{,}000$\times$, but the bounds remain physically absurd.
The open-loop version says $n$ could deviate by 27~million; the
closed-loop says 1{,}242. Both unusable. The ceiling is plant
anisotropy ($\Lambda/\tau_{\mathrm{thermal}} \sim 10^{-4}$ timescale
ratio), not controller tuning. Generated by
\texttt{barrier\_compare\_OL\_CL.m}.}
\label{fig:ol-vs-cl}
\end{figure}
\begin{derivation}
Why the eigenvalues barely move but $\gamma$ changes 9 orders of
magnitude:
\begin{itemize}
\item $\max \Re(\mathrm{eig}\,A) = -0.0125$ — slowest thermal mode.
\item $\max \Re(\mathrm{eig}\,A_{\mathrm{cl}}) = -0.0124$ — virtually
identical. LQR cannot speed up the slowest mode past what
physics allows.
\item But $\gamma = c_{\mathrm{inv}} \propto (w_{\mathrm{bar}} \sqrt{B_w^\top P B_w} / \mu)^2$,
and $P$ changes \emph{shape} between OL and CL: LQR makes the
disturbance penetrate $V$ far less. $B_w^\top P B_w$ drops
substantially under LQR, $\mu$ stays similar. Ratio squared
$\to$ nine orders of magnitude.
\end{itemize}
\end{derivation}
\begin{limitation}
Quadratic Lyapunov barrier is insufficient for this plant regardless
of LQR tuning. Root cause: the plant's natural timescale spread
(prompt-neutron $\Lambda = 10^{-4}$~\unit{\second} vs.\ thermal $\sim 10$~\unit{\second})
forces any Lyapunov $P$ to be ill-conditioned by $\sim 10^4$. The
resulting ellipsoid stretches absurdly in the fast directions when
projected to physical coordinates. Fix:\ non-quadratic barrier
(polytopic or SOS). Neither implemented yet.
\end{limitation}
\subsection*{Error 3: the heatup-rate invariant IS expressible as a halfspace}
In the first version of \texttt{predicates.json}, I put a comment on
\texttt{inv1\_holds} claiming a ramp-rate constraint could not be
written as a state halfspace without state augmentation. That was
wrong.
\begin{derivation}
From \texttt{pke\_th\_rhs.m}, $\dot T_c$ is linear in
$(T_f, T_c, T_{\mathrm{cold}})$:
$$\dot T_c = \frac{hA(T_f - T_c) - 2 W c_c (T_c - T_{\mathrm{cold}})}{M_c c_c}
= a_f T_f + a_c T_c + a_{\mathrm{cold}} T_{\mathrm{cold}}$$
with
\begin{align*}
a_f &= \frac{hA}{M_c c_c} = \frac{5 \times 10^7}{1.09 \times 10^8} = +0.4587~\unit{\per\second} \\
a_c &= -\frac{hA + 2 W c_c}{M_c c_c} = -\frac{1.045 \times 10^8}{1.09 \times 10^8} = -0.9587~\unit{\per\second} \\
a_{\mathrm{cold}} &= \frac{2 W c_c}{M_c c_c} = \frac{5.45 \times 10^7}{1.09 \times 10^8} = +0.5000~\unit{\per\second}
\end{align*}
Coefficients sum to zero exactly: at thermal equilibrium
($T_f = T_c = T_{\mathrm{cold}}$), $\dot T_c = 0$.
A ramp-rate constraint $|\dot T_c| \leq r_{\max}$ is therefore two
halfspaces over the 10-state vector, with three nonzero coefficients
each (on indices $8, 9, 10$):
\begin{align*}
+a_f T_f + a_c T_c + a_{\mathrm{cold}} T_{\mathrm{cold}} &\leq r_{\max} \\
-a_f T_f - a_c T_c - a_{\mathrm{cold}} T_{\mathrm{cold}} &\leq r_{\max}
\end{align*}
Clean polyhedron; no augmentation. The confusion came from conflating
this with rate constraints on \emph{non-linearly-driven} states — e.g.\
$|\dot n|$ involves $(\rho - \beta) n / \Lambda$, which is nonlinear,
and \emph{that} would need augmentation. For the coolant temperature
rate, the thermal-hydraulic subsystem is linear-in-state and the
halfspace drops out directly.
\end{derivation}
$r_{\max}$ chosen as 50~\unit{\celsius\per\hour} (tech-spec nominal is
28~\unit{\celsius\per\hour}; add budget for transient overshoot).
\texttt{plant-model/test\_heatup\_rate.m} measures the actual peak
rate from the current \texttt{ctrl\_heatup.m} controller:
\begin{lstlisting}[style=terminal]
=== Heatup rate statistics ===
max dT_c/dt: 0.0135 C/s = 48.5 C/hr
min dT_c/dt: 0.0000 C/s = 0.0 C/hr
rate limit: +/- 0.01389 C/s = +/- 50.0 C/hr
violates upper? false
violates lower? false
\end{lstlisting}
Right at 50~\unit{\celsius\per\hour} peak during mid-ramp — barely
inside the budget, and \emph{70\% above tech-spec nominal}. Would
fail a strict 28~\unit{\celsius\per\hour} interpretation. Documented
as an open controller-tuning item.
\subsection*{The mode-obligation taxonomy}
The key conceptual move of the session. Walking through the reach
code, Dane observed that the per-mode reach obligations aren't all the
same shape. They split cleanly in two:
\begin{decision}
\textbf{Two kinds of mode, two kinds of obligation.}
\textbf{Equilibrium modes} (\texttt{q\_operation}, \texttt{q\_shutdown}):
plant is parked at a setpoint. Obligation is forever-invariance under
bounded disturbance. External disturbance matters — it's the thing
that could push the state out. \emph{This is what the 2026-04-17
operation-mode reach actually proves} (up to the linearization
caveat).
\textbf{Transition modes} (\texttt{q\_heatup}, \texttt{q\_scram}):
plant is being driven from one mode's territory to another's.
Obligation is \emph{reach-avoid}: from $X_{\mathrm{entry}}$, reach
$X_{\mathrm{exit}}$ within bounded time $[T_{\min}, T_{\max}]$, while
maintaining $\mathrm{inv}_{\mathrm{mode}}$ along the way. External
disturbance in these modes is essentially zero
($Q_{\mathrm{sg}} = 0$ during heatup, rods slam on scram). The only
``disturbance'' is parametric uncertainty in the plant coefficients,
which we defer.
\end{decision}
The point of per-mode reach is \emph{not} generic disturbance
rejection — it's to prove that the DRC's discrete transitions
physically fire in finite time on the real plant. The reach tube is
the artifact that transfers discrete correctness
(\texttt{ltlsynt}-guaranteed) to physical correctness.
Formal claim per transition mode (heatup example):
\begin{align}
&\text{Given } x(0) \in X_{\mathrm{entry}}(\text{heatup}), \notag \\
&\text{applying } u = \texttt{ctrl\_heatup}(t, x, \mathrm{plant}, \mathrm{ref}), \notag \\
&\text{with } Q_{\mathrm{sg}} = 0, \notag \\
&\text{we show } \exists\, T \in [T_{\min}, T_{\max}] \text{ s.t.} \notag \\
&\quad x(T) \in X_{\mathrm{exit}}(\text{heatup}) \quad \text{[reach]} \notag \\
&\quad x(t) \in \mathrm{inv1\_holds} \quad \forall t \in [0, T] \quad \text{[avoid]}
\end{align}
The entry/exit sets and time budgets need machine-readable
definitions. Added a \texttt{mode\_boundaries} block to
\texttt{predicates.json}:
\begin{itemize}
\item Each mode's \texttt{X\_entry\_polytope} as box bounds per state.
\item Each mode's \texttt{X\_exit\_predicate} as a reference to named
predicates.
\item Each mode's \texttt{T\_min}, \texttt{T\_max} (\texttt{null} for
equilibrium modes).
\end{itemize}
Values are engineering-reasonable placeholders:
\texttt{T\_max(heatup)} = 5~\unit{\hour} (tech-spec 28~\unit{\celsius/\hour}
over 60~\unit{\degreeFahrenheit} span is 1.19~\unit{\hour} nominal, 4$\times$
margin). \texttt{T\_min(heatup)} = 2~\unit{\hour} 9~\unit{\minute} (any
faster violates the rate invariant). \texttt{T\_max(scram)} = 60~\unit{\second}
(NRC expects seconds; 60 is generous for idealized rod insertion).
\begin{limitation}
All mode-boundary values are engineering guesses. Thesis defense
will require real tech-spec numbers pinned to a specific plant.
Flagged in the JSON as \texttt{\_placeholder\_warning}.
\end{limitation}
\subsection*{WALKTHROUGH.md — standalone reach documentation}
With the mode-obligation taxonomy, predicate restructure, and barrier
findings in hand, wrote \texttt{reachability/WALKTHROUGH.md} as a
standalone document. Captures the taxonomy table verbatim, per-mode
obligation definitions, code walkthrough, per-halfspace results, and
every known limitation.
\apass{WALKTHROUGH.md should probably be folded into a journal-style
chapter at some point, but for now it's the external-facing doc people
read first. Keep it in sync when structural things change.}
\subsection*{Julia nonlinear reach — first attempt, partial success}
With linear work consolidated, turned to the real soundness question.
The linear reach proves the LQR closed-loop is safe, \emph{if} we
trust the linearization. To close the gap, we need nonlinear reach.
Framework choice: \texttt{ReachabilityAnalysis.jl} with TMJets (Taylor
model integration). Already have Julia scaffolding in
\texttt{julia-port/} and know the package.
Target: heatup mode reach, saturation disabled (simplifying
assumption to establish the framework; will add back saturation as
a hybrid sub-mode later).
\subsubsection*{The first three attempts failed}
\begin{deadend}
\textbf{Attempt 1:} naive RHS with \texttt{plant} as a function
argument. Fails immediately with
\texttt{MethodError: setindex!(::Taylor1\{Float64\}, ::TaylorModel1\{...\}, ...)}
Taylor model arithmetic needs the RHS in a specific form. Need
\texttt{@taylorize}.
\textbf{Attempt 2:} add \texttt{@taylorize} to the function. Same error.
Missing piece: the macro only handles \emph{constants} in arithmetic,
not struct-field accesses. Need all plant parameters as \texttt{const}
globals.
\textbf{Attempt 3:} inline all constants. Still fails. Running out
of ideas; then noticed that \texttt{min()} inside the body (for the
ramp-reference clamp) is non-smooth — Taylor models can't handle
non-smooth operations. Also: the raw time argument \texttt{t} in the
signature was interacting badly with TMJets' internal time parameter.
\end{deadend}
\begin{decision}
\textbf{Attempt 4 (landed):} three changes together.
\begin{enumerate}
\item All plant parameters as \texttt{const} at module scope.
\item \texttt{@taylorize} on the RHS, all arithmetic scalar (loops
unrolled, no function calls in the hot path).
\item Time carried as an \emph{augmented state} $x_{11}$ with
$\dot x_{11} = 1$. Instead of $T_{\mathrm{ref}}(t)$, the RHS
references $T_{\mathrm{ref}}(x_{11})$ with no \texttt{min()}
— valid while the ramp hasn't hit the target clamp, which is
true for our probe horizons.
\end{enumerate}
\end{decision}
The final RHS body (see
\texttt{julia-port/scripts/reach\_heatup\_nonlinear.jl}):
\begin{lstlisting}[language=Julia,caption={Taylor-model-aware heatup RHS}]
@taylorize function rhs_heatup_taylor!(dx, x, p, t)
rho = KP_HEATUP * (T_STANDBY + RAMP_RATE_CS * x[11] - x[9])
dx[1] = (rho - BETA) / LAMBDA * x[1] +
LAM_1*x[2] + LAM_2*x[3] + LAM_3*x[4] +
LAM_4*x[5] + LAM_5*x[6] + LAM_6*x[7]
dx[2] = (BETA_1 / LAMBDA) * x[1] - LAM_1 * x[2]
dx[3] = (BETA_2 / LAMBDA) * x[1] - LAM_2 * x[3]
dx[4] = (BETA_3 / LAMBDA) * x[1] - LAM_3 * x[4]
dx[5] = (BETA_4 / LAMBDA) * x[1] - LAM_4 * x[5]
dx[6] = (BETA_5 / LAMBDA) * x[1] - LAM_5 * x[6]
dx[7] = (BETA_6 / LAMBDA) * x[1] - LAM_6 * x[7]
dx[8] = (P0 * x[1] - HA * (x[8] - x[9])) / (M_F * C_F)
dx[9] = (HA * (x[8] - x[9]) - 2 * W_M * C_C * (x[9] - x[10])) / (M_C * C_C)
dx[10] = (2 * W_M * C_C * (x[9] - x[10])) / (M_SG * C_C)
dx[11] = one(x[1]) # d(time)/dt = 1, in the right Taylor type
return nothing
end
\end{lstlisting}
Probes at $T = 10, 60, 300$~\unit{\second}:
\begin{lstlisting}[style=terminal]
--- Probe T = 10.0 s ---
TMJets: 10583 reach-sets
t reached: 10.0 s of 10.0
n envelope: [-0.0005178, 0.005015]
T_f envelope: [274.46, 295.01] C
T_c envelope: [274.45, 295.00] C
T_cold env: [270.00, 287.16] C
--- Probe T = 60.0 s ---
Warning: Maximum number of integration steps reached; exiting.
TMJets: 50000 reach-sets
FAILED: AssertionError: radius must be nonnegative but is [NaN, NaN, ...]
--- Probe T = 300.0 s ---
(same as 60s)
\end{lstlisting}
\textbf{10 seconds works}; 60 seconds onward exhaust the step budget
and then propagate NaN. The 10-second envelope is sound — the
$n$-envelope going slightly negative is over-approximation tax
(physically impossible, numerically correct for a box hull).
\begin{derivation}
Step-size analysis. TMJets' adaptive stepper shrinks $\Delta t$ to
resolve the fastest active mode. Prompt-neutron timescale is
$\Lambda = 10^{-4}$~\unit{\second}. For the Taylor remainder
(\texttt{abstol=1e-10}) to be bounded, the stepper needs
$\Delta t \lesssim 10^{-3}$~\unit{\second}. Over a 10~\unit{\second}
horizon that's $\sim 10{,}000$ steps — consistent with the observed
10{,}583.
Extrapolate: a 5-hour heatup reach would need $\sim 1.8 \times 10^7$
steps at this cadence. Totally infeasible, and we'd hit numerical
precision floor long before that.
\end{derivation}
\begin{limitation}
\textbf{TMJets on the full 10-state PKE is stuck at $\sim$10-second
horizons.} Prompt-neutron stiffness ($\Lambda = 10^{-4}$~\unit{\second}
vs.\ thermal $\sim 10$~\unit{\second}, ratio $10^5$) forces tiny
time steps. Step budget runs out, then numerical underflow
produces NaN in the precursor-decay arithmetic. Not a framework
bug; not a tuning issue; a fundamental property of reach on the
full PKE.
\end{limitation}
\subsection*{The singular-perturbation remedy (not done yet)}
\begin{decision}
For hours-long reach, the prompt neutron timescale must be eliminated
from the state dynamics. Standard move in reactor-kinetics reach
literature: set $\dot n \approx 0$ and solve for $n$ algebraically.
This gives the \emph{prompt-jump approximation} (sometimes written
as the \emph{reduced-order PKE}):
$$(\rho - \beta) n / \Lambda + \sum_i \lambda_i C_i = 0
\quad \Longrightarrow \quad
n \approx \frac{\Lambda \sum_i \lambda_i C_i}{\beta - \rho}$$
valid when $\rho < \beta$ (subcritical). $n$ becomes algebraic in
the remaining state; the dynamic state drops to 9-D, the stiffness
disappears, and TMJets can take steps on the thermal timescale
($\sim 1$~\unit{\second} per step is fine).
Tradeoff: we lose the prompt-supercritical regime, which is a
$\sim 50$~\unit{\microsecond} transient. For heatup over hours, that
transient is irrelevant to safety. Soundness is reduced (we no
longer capture prompt-dynamic trajectories), but the reduction
introduces a bounded error that can be characterized separately.
Deferred to a future session.
\end{decision}
\subsection*{Session result}
Artifacts:
\begin{itemize}
\item \texttt{reachability/predicates.json} restructured:
three-layer (deadbands, safety limits, mode invariants)
+ \texttt{mode\_boundaries} with per-mode entry/exit/time.
\item \texttt{reachability/load\_predicates.m} handles the new format
including multi-coefficient rows (for the rate halfspace).
\item \texttt{reachability/reach\_operation.m} and
\texttt{barrier\_lyapunov.m} now report per-halfspace margins
against \texttt{inv2\_holds}.
\item \texttt{reachability/barrier\_compare\_OL\_CL.m} — OL vs.\
CL Lyapunov barrier.
\item \texttt{reachability/WALKTHROUGH.md} — 550-line standalone
document.
\item \texttt{julia-port/scripts/reach\_heatup\_nonlinear.jl} and
\texttt{sim\_heatup.jl}. Nonlinear reach framework proven
to 10~\unit{\second}.
\item Six commits on \texttt{main}.
\end{itemize}
Key findings:
\begin{itemize}
\item Quadratic Lyapunov barrier fails structurally on this plant.
LQR improves it 20{,}000$\times$ but not enough. Need
polytopic or SOS barriers.
\item Heatup rate is a clean state halfspace (three-coefficient row).
Current controller peaks at 48.5~\unit{\celsius\per\hour}
tight against a strict 28-spec interpretation.
\item Per-mode reach obligations split cleanly into equilibrium
(forever-invariance under disturbance) vs.\ transition
(reach-avoid with time budget, essentially zero disturbance).
\item Nonlinear reach framework functional in Julia at 10-second
horizons. Prompt-neutron stiffness is the wall; reduced-order
PKE is the known remedy.
\end{itemize}
\subsection*{Open at close}
\begin{itemize}
\item Reduced-order PKE for long-horizon nonlinear reach.
\item Heatup reach to $T_{\max} = 5$~\unit{\hour}.
\item Scram reach (same reduction will apply).
\item Add polytopic or SOS barrier as alternative certificate.
\item Port MATLAB to Julia end-to-end; remove MATLAB dependency.
\item Build a FRET-adjacent UI for exploring the predicates
$\to$ halfspaces correspondence.
\item Lab journal to document all of the above (this is what got
done in the 2026-04-20 evening session — see next entry).
\end{itemize}

67
journal/journal.tex Normal file
View File

@ -0,0 +1,67 @@
% journal.tex — top-level document that aggregates all dated entries.
%
% Build:
% cd journal && latexmk -pdf journal.tex
% or individual entry:
% cd journal && latexmk -pdf entries/2026-04-17-controllers-linear-reach.tex
\input{preamble.tex}
\title{HAHACS Lab Journal\\
\large PWR\_HYBRID\_3 preliminary example, invention log}
\author{Dane Sabo, with Claude (Hacker-Split)}
\date{Started \today}
\begin{document}
\maketitle
\tableofcontents
\newpage
\section*{How to read this journal}
Each section is a dated session. Sessions are written in two styles:
\begin{itemize}
\item \textbf{Deep (A-style)}: full invention-log depth. Derivations
in math, code snippets with commentary, figures with long
captions, dead-ends documented, terminal output included where
it changes the story. A reader in 2030 should be able to
rebuild the work from this alone.
\item \textbf{Narrative (B-style)}: end-of-session notes with
pointers. Marked with \apass{some detail} callouts for
content that should be expanded in a later A-pass.
\end{itemize}
Callout boxes signal specific content types:
\begin{derivation}
Mathematical derivations — algebra, integrals, limits. Where they
matter to the safety claim, they live here in full.
\end{derivation}
\begin{decision}
Design decisions made during the session, with the rationale and the
alternatives considered.
\end{decision}
\begin{deadend}
Approaches that didn't work and why. These are as valuable as the
working paths — they keep the next explorer from repeating the mistake.
\end{deadend}
\begin{limitation}
Known-approximate or known-broken behavior. Soundness gaps live here.
Each limitation ties to a plan or an open question.
\end{limitation}
\newpage
% ---- Session entries, in chronological order -------------------------------
\input{entries/2026-04-17-controllers-linear-reach.tex}
\newpage
\input{entries/2026-04-20-predicates-boundaries-julia-nonlinear.tex}
\newpage
\input{entries/2026-04-20-evening-mega-session.tex}
\end{document}

176
journal/preamble.tex Normal file
View File

@ -0,0 +1,176 @@
% preamble.tex — shared LaTeX setup for the HAHACS lab journal.
%
% Intent: a reader in 2030 picks up this journal and can rebuild the
% work from scratch. This file defines the visual vocabulary — code
% listings, figures, callouts — that each dated entry uses.
\documentclass[11pt, letterpaper]{article}
% --- Page geometry ------------------------------------------------------------
\usepackage[margin=1in, headheight=15pt]{geometry}
\usepackage{parskip} % blank line between paragraphs; no indent
\usepackage{microtype}
% --- Fonts --------------------------------------------------------------------
\usepackage[T1]{fontenc}
\usepackage{lmodern}
\usepackage{inconsolata} % monospaced font for code
% --- Math ---------------------------------------------------------------------
\usepackage{amsmath, amssymb, amsthm, mathtools}
\usepackage{siunitx}
\sisetup{detect-all, per-mode=symbol}
% --- Graphics -----------------------------------------------------------------
\usepackage{graphicx}
\graphicspath{{./figures/}{../docs/figures/}}
\usepackage{caption}
\captionsetup{font=small, labelfont=bf}
% --- Code listings ------------------------------------------------------------
\usepackage{listings}
\usepackage{xcolor}
% Palette
\definecolor{code-bg}{HTML}{F7F7F2}
\definecolor{code-rule}{HTML}{D0D0C8}
\definecolor{code-comment}{HTML}{708070}
\definecolor{code-keyword}{HTML}{0050A0}
\definecolor{code-string}{HTML}{A04060}
\definecolor{code-number}{HTML}{806010}
\lstdefinelanguage{Julia}%
{morekeywords={abstract,break,case,catch,const,continue,do,else,elseif,%
end,export,false,for,function,immutable,import,importall,if,in,%
macro,module,otherwise,quote,return,struct,switch,true,try,type,%
typealias,using,while,mutable,global,local,let,primitive,where},%
sensitive=true,%
morecomment=[l]\#,%
morecomment=[n]{\#=}{=\#},%
morestring=[s]{"}{"},%
morestring=[m]{'}{'},%
}
\lstdefinestyle{labstyle}{
backgroundcolor=\color{code-bg},
basicstyle=\ttfamily\small,
breaklines=true,
breakatwhitespace=false,
captionpos=b,
commentstyle=\color{code-comment}\itshape,
frame=single,
framerule=0.5pt,
rulecolor=\color{code-rule},
keywordstyle=\color{code-keyword}\bfseries,
numberstyle=\tiny\color{code-comment},
showspaces=false,
showstringspaces=false,
showtabs=false,
stringstyle=\color{code-string},
tabsize=2,
numbers=left,
numbersep=6pt,
xleftmargin=14pt
}
\lstset{style=labstyle}
\lstdefinestyle{terminal}{
backgroundcolor=\color{black!90},
basicstyle=\ttfamily\small\color{green!80!white},
commentstyle=\color{white!60},
frame=none,
numbers=none,
breaklines=true,
xleftmargin=0pt
}
% --- Callout boxes ------------------------------------------------------------
\usepackage[most]{tcolorbox}
\newtcolorbox{limitation}[1][]{%
colback=red!5!white,
colframe=red!55!black,
title=\textbf{Limitation},
fonttitle=\bfseries,
boxrule=0.6pt,
arc=2pt,
left=6pt, right=6pt, top=4pt, bottom=4pt,
#1
}
\newtcolorbox{derivation}[1][]{%
colback=blue!3!white,
colframe=blue!40!black,
title=\textbf{Derivation},
fonttitle=\bfseries,
boxrule=0.6pt,
arc=2pt,
left=6pt, right=6pt, top=4pt, bottom=4pt,
#1
}
\newtcolorbox{deadend}[1][]{%
colback=gray!8!white,
colframe=gray!50!black,
title=\textbf{Dead end},
fonttitle=\bfseries,
boxrule=0.5pt,
arc=2pt,
borderline west={2pt}{0pt}{gray!40},
left=6pt, right=6pt, top=4pt, bottom=4pt,
#1
}
\newtcolorbox{decision}[1][]{%
colback=green!3!white,
colframe=green!35!black,
title=\textbf{Decision},
fonttitle=\bfseries,
boxrule=0.6pt,
arc=2pt,
left=6pt, right=6pt, top=4pt, bottom=4pt,
#1
}
% TODO-for-A-pass marker: highlighted so we can find them for later deep-pass.
\newcommand{\apass}[1]{%
{\fboxsep=2pt\colorbox{orange!20}{\textbf{[A-pass]}}\,\textit{#1}}
}
% --- Session header ----------------------------------------------------------
% Usage: \session{2026-04-17}{afternoon, ~5 hr}{summary line}
\newcommand{\session}[3]{%
\noindent\rule{\linewidth}{0.8pt}
\vspace{2pt}
\noindent\textbf{\Large Session: #1} \hfill \textit{#2}\par
\vspace{2pt}
\noindent\emph{#3}\par
\vspace{4pt}
\noindent\rule{\linewidth}{0.4pt}
\vspace{6pt}
}
% --- Code macros --------------------------------------------------------------
\newcommand{\juliafile}[2][]{\lstinputlisting[language=Julia,caption={#2},#1]{#2}}
\newcommand{\matlabfile}[2][]{\lstinputlisting[language=Matlab,caption={#2},#1]{#2}}
\newcommand{\pyfile}[2][]{\lstinputlisting[language=Python,caption={#2},#1]{#2}}
% --- Cross-reference helpers --------------------------------------------------
\usepackage[colorlinks=true, linkcolor=blue!50!black, citecolor=blue!40!black,
urlcolor=teal!60!black]{hyperref}
\usepackage{bookmark}
\usepackage{cleveref}
% --- Headers & footers --------------------------------------------------------
\usepackage{fancyhdr}
\pagestyle{fancy}
\fancyhf{}
\fancyhead[L]{HAHACS lab journal}
\fancyhead[R]{\leftmark}
\fancyfoot[C]{\thepage}
\renewcommand{\headrulewidth}{0.3pt}
% --- A small quiet easter egg for anyone who greps the preamble ---------------
% "Looks ordinary on the surface but is something else underneath."
% — the name behind Split. Keep the journal honest; under every summary
% there's a derivation; under every derivation there's a doubt.

View File

@ -0,0 +1,82 @@
#!/usr/bin/env julia
#
# barrier_compare_OL_CL.jl — head-to-head Lyapunov barrier bounds with
# and without LQR feedback. Julia port of reachability/barrier_compare_OL_CL.m.
#
# Expected: LQR improves every bound by ~20,000x, but bounds stay
# physically meaningless. Point is to show the ceiling is plant
# anisotropy, not controller tuning.
using Pkg
Pkg.activate(joinpath(@__DIR__, ".."))
using Printf
using LinearAlgebra
using MatrixEquations
using JSON
include(joinpath(@__DIR__, "..", "src", "pke_params.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_th_rhs.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_linearize.jl"))
include(joinpath(@__DIR__, "..", "src", "load_predicates.jl"))
plant = pke_params()
x_op = pke_initial_conditions(plant)
pred = load_predicates(plant)
A, B, B_w, _, _, _ = pke_linearize(plant)
# LQR gain (same weights as ctrl_operation_lqr).
Q_lqr = Diagonal([1.0, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-2, 1e2, 1.0])
R_lqr = 1e6 * ones(1, 1)
X_ric, _, _ = arec(A, reshape(B, :, 1), R_lqr, Matrix(Q_lqr))
K = (R_lqr \ reshape(B, 1, :)) * X_ric
A_cl = A - reshape(B, :, 1) * K
# Shared Qbar — best from the earlier sweep.
Qbar = Diagonal([1.0, 1e-4, 1e-4, 1e-4, 1e-4, 1e-4, 1e-4, 1.0, 1e2, 1.0])
w_bar = 0.15 * plant.P0
delta_entry = [0.01 * x_op[1];
0.001 .* abs.(x_op[2:7]);
0.1; 0.1; 0.1]
inv2 = pred.mode_invariants[:inv2_holds]
A_inv = inv2.A_poly
b_inv = inv2.b_poly
comps = inv2.components
b_dev = b_inv .- A_inv * x_op
function run_case(Acase)
P = lyapc(Matrix(Acase)', Matrix(Qbar))
Ph = Hermitian(sqrt(Hermitian(P)))
Phi = inv(Ph)
mu = minimum(eigvals(Symmetric(Phi * Matrix(Qbar) * Phi)))
g_bound = sqrt(B_w' * P * B_w)
c_inv = (2 * w_bar * g_bound / mu)^2
c_entry = delta_entry' * abs.(P) * delta_entry
gamma = max(c_inv, c_entry)
Pinv = inv(P)
maxima = [sqrt(gamma * (A_inv[k, :]' * Pinv * A_inv[k, :])) for k in 1:size(A_inv, 1)]
return gamma, maxima, eigvals(Acase)
end
gamma_OL, max_OL, eig_OL = run_case(A)
gamma_CL, max_CL, eig_CL = run_case(A_cl)
println("\n=== Open-loop vs LQR closed-loop Lyapunov barrier ===")
@printf " max Re(eig) OL = %.3e CL = %.3e\n" maximum(real.(eig_OL)) maximum(real.(eig_CL))
@printf " min Re(eig) OL = %.3e CL = %.3e\n" minimum(real.(eig_OL)) minimum(real.(eig_CL))
@printf " gamma OL = %.3e CL = %.3e (ratio CL/OL = %.3g)\n" gamma_OL gamma_CL gamma_CL/gamma_OL
println("\n Per-halfspace max |a' dx| on gamma-ellipsoid:")
@printf " %-22s %-10s %-14s %-14s %-14s %-10s\n" "halfspace" "headroom" "open-loop" "closed-loop" "CL - OL" "ratio"
for k in 1:size(A_inv, 1)
ratio = max_CL[k] / max_OL[k]
@printf " %-22s %10.3f %14.3f %14.3f %+14.3f %10.3gx\n" comps[k] b_dev[k] max_OL[k] max_CL[k] (max_CL[k] - max_OL[k]) ratio
end
println("\n Interpretation:")
println(" - CL < OL on a row => LQR tightens that halfspace.")
println(" - CL ~= OL => LQR does not help that direction at all.")
println(" - CL > OL => LQR made that direction WORSE for the barrier.")

View File

@ -0,0 +1,118 @@
#!/usr/bin/env julia
#
# barrier_lyapunov.jl — Lyapunov-ellipsoid barrier cert.
# Julia port of reachability/barrier_lyapunov.m.
#
# Sweeps Qbar(T_c) weight to find the tightest quadratic barrier;
# reports per-halfspace margins against inv2_holds.
#
# Expected result: every halfspace exceeded by orders of magnitude.
# This is the structural anisotropy limitation, not a code bug.
using Pkg
Pkg.activate(joinpath(@__DIR__, ".."))
using Printf
using LinearAlgebra
using MatrixEquations
using JSON
include(joinpath(@__DIR__, "..", "src", "pke_params.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_th_rhs.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_linearize.jl"))
include(joinpath(@__DIR__, "..", "src", "load_predicates.jl"))
plant = pke_params()
x_op = pke_initial_conditions(plant)
pred = load_predicates(plant)
# --- Closed-loop ---
A, B, B_w, _, _, _ = pke_linearize(plant)
Q_lqr = Diagonal([1.0, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-2, 1e2, 1.0])
R_lqr = 1e6 * ones(1, 1)
X_ric, _, _ = arec(A, reshape(B, :, 1), R_lqr, Matrix(Q_lqr))
K = (R_lqr \ reshape(B, 1, :)) * X_ric
A_cl = A - reshape(B, :, 1) * K
# --- Lyapunov ---
# lyapc solves A' P + P A + Q = 0 for P. Julia's MatrixEquations uses
# lyapc(A', Q) to solve A' P + P A = -Q (note: sign conventions vary).
# Check: for a Hurwitz A, lyapc(A, Q) with Q > 0 returns P > 0.
Qbar = Diagonal([1.0, 1e-4, 1e-4, 1e-4, 1e-4, 1e-4, 1e-4, 1.0, 1e2, 1.0])
P = lyapc(Matrix(A_cl)', Matrix(Qbar))
@assert all(eigvals(P) .> 0) "P not positive definite"
# --- Disturbance bound ---
w_bar = 0.15 * plant.P0
# Invariant level via the derivation in the MATLAB file.
P_half = Hermitian(sqrt(Hermitian(P)))
P_half_inv = inv(P_half)
mu = minimum(eigvals(Symmetric(P_half_inv * Matrix(Qbar) * P_half_inv)))
g_bound = sqrt(B_w' * P * B_w)
c_inv = (2 * w_bar * g_bound / mu)^2
delta_entry = [0.01 * x_op[1];
0.001 .* abs.(x_op[2:7]);
0.1; 0.1; 0.1]
c_entry = delta_entry' * abs.(P) * delta_entry
gamma = max(c_inv, c_entry)
println("\n=== Lyapunov barrier certificate ===")
@printf " lambda_min(P) = %.3e\n" minimum(eigvals(P))
@printf " lambda_max(P) = %.3e\n" maximum(eigvals(P))
@printf " sqrt(B_w' P B_w) = %.3e\n" g_bound
@printf " mu (Qbar eig on P-metric)= %.3e\n" mu
@printf " w_bar (15%% P0) = %.3e W\n" w_bar
@printf " c_inv (invariant level) = %.3e\n" c_inv
@printf " c_entry (from X_entry) = %.3e\n" c_entry
@printf " gamma = %.3e\n" gamma
# --- inv2_holds per-halfspace barrier check ---
inv2 = pred.mode_invariants[:inv2_holds]
A_inv = inv2.A_poly
b_inv = inv2.b_poly
comps = inv2.components
b_dev = b_inv .- A_inv * x_op
Pinv = inv(P)
println("\n=== Lyapunov barrier vs inv2_holds halfspaces ===")
for k in 1:size(A_inv, 1)
a = A_inv[k, :]
max_adx = sqrt(gamma * (a' * Pinv * a))
margin = b_dev[k] - max_adx
status = margin < 0 ? "*** TOO LOOSE ***" : "OK"
@printf " [%-22s] headroom = %8.3f | max a'dx = %8.3f | margin = %+8.3f %s\n" comps[k] b_dev[k] max_adx margin status
end
# --- Qbar(T_c) sweep for tightness ---
println("\n=== Qbar(T_c) weight sweep ===")
e9 = zeros(10); e9[9] = 1.0
weights = [1e1, 1e2, 1e3, 1e4, 1e5, 1e6]
let best_dTc = Inf, best_w = NaN, best_gamma = NaN, best_P = nothing
for wTc in weights
Qbs = copy(Matrix(Qbar))
Qbs[9, 9] = wTc
Ps = try
lyapc(Matrix(A_cl)', Qbs)
catch
continue
end
any(eigvals(Ps) .<= 0) && continue
Phs = Hermitian(sqrt(Hermitian(Ps)))
Phi = inv(Phs)
mu_s = minimum(eigvals(Symmetric(Phi * Qbs * Phi)))
g_s = sqrt(B_w' * Ps * B_w)
ci_s = (2 * w_bar * g_s / mu_s)^2
ce_s = delta_entry' * abs.(Ps) * delta_entry
gs = max(ci_s, ce_s)
Pinv_s = inv(Ps)
dTc = sqrt(gs * (e9' * Pinv_s * e9))
@printf " Qbar(9,9) = %.0e -> gamma = %.3e, max|dT_c| = %7.3f K\n" wTc gs dTc
if dTc < best_dTc
best_dTc = dTc; best_w = wTc; best_gamma = gs; best_P = Ps
end
end
@printf " Best: Qbar(9,9) = %.0e -> max|dT_c| = %.3f K\n" best_w best_dTc
end

View File

@ -0,0 +1,132 @@
#!/usr/bin/env julia
#
# main_mode_sweep.jl — run every DRC-mode controller back-to-back.
#
# Julia equivalent of plant-model/main_mode_sweep.m. Produces the
# same four-panel plots, saves to docs/figures/ with `mode_sweep_*.png`
# names (overwrites MATLAB outputs — the Julia versions take over).
using Pkg
Pkg.activate(joinpath(@__DIR__, ".."))
using Printf
using LinearAlgebra
using OrdinaryDiffEq
using Plots
using MatrixEquations
using JSON
include(joinpath(@__DIR__, "..", "src", "pke_params.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_th_rhs.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_linearize.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_solver.jl"))
include(joinpath(@__DIR__, "..", "src", "plot_pke_results.jl"))
include(joinpath(@__DIR__, "..", "controllers", "controllers.jl"))
# --- Plant + predicates ---
plant = pke_params()
# Load T_standby from predicates.json for the hot-standby IC + heatup ref.
pred_path = joinpath(@__DIR__, "..", "..", "reachability", "predicates.json")
pred_raw = JSON.parsefile(pred_path)
T_standby = plant.T_c0 + pred_raw["derived"]["T_standby_offset_C"]
# --- ICs ---
x_op = pke_initial_conditions(plant)
# Hot-standby IC: everything at T_standby, trace n.
n_shut = 1e-6
C_shut = (plant.beta_i ./ (plant.lambda_i .* plant.Lambda)) .* n_shut
x_shut = [n_shut; C_shut; T_standby; T_standby; T_standby]
# Heatup IC: already critical at 0.1% power, thermally matched.
n_heat = 1e-3
C_heat = (plant.beta_i ./ (plant.lambda_i .* plant.Lambda)) .* n_heat
x_heat = [n_heat; C_heat; T_standby; T_standby; T_standby]
# --- LQR gain (needed by ctrl_operation_lqr_factory) ---
A, B, B_w, _, _, _ = pke_linearize(plant)
Q_lqr = Diagonal([1.0, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-2, 1e2, 1.0])
R_lqr = 1e6 * ones(1, 1)
ctrl_op_lqr, K_lqr, _ = ctrl_operation_lqr_factory(
plant, A, B; Q_lqr=Matrix(Q_lqr), R_lqr=R_lqr)
# --- Figure output directory ---
figdir = joinpath(@__DIR__, "..", "..", "docs", "figures")
isdir(figdir) || mkpath(figdir)
# --- Run each mode ---
println("\n===== Mode 1: ctrl_shutdown =====")
Q_shut = t -> 0.0
t1, X1, U1 = pke_solver(plant, Q_shut, ctrl_shutdown, nothing, (0.0, 600.0); x0=x_shut)
println("\n===== Mode 2: ctrl_heatup =====")
ref_heat = (; T_start=T_standby, T_target=plant.T_c0, ramp_rate=28/3600)
Q_heat = t -> 0.0
t2, X2, U2 = pke_solver(plant, Q_heat, ctrl_heatup, ref_heat, (0.0, 5400.0); x0=x_heat)
println("\n===== Mode 3a: ctrl_operation (P) =====")
Q_op = t -> plant.P0 * (1.0 - 0.2 * (t >= 30))
ref_op = (; T_avg=plant.T_c0)
t3, X3, U3 = pke_solver(plant, Q_op, ctrl_operation, ref_op, (0.0, 600.0))
println("\n===== Mode 3b: ctrl_operation_lqr =====")
# LQR closure ignores ref; pass nothing.
t3b, X3b, U3b = pke_solver(plant, Q_op, ctrl_op_lqr, nothing, (0.0, 600.0))
println("\n===== Mode 4: ctrl_scram =====")
Q_scr = t -> plant.P0 * max(0.03, 1 - max(0, t - 10) / 10)
t4, X4, U4 = pke_solver(plant, Q_scr, ctrl_scram, nothing, (0.0, 600.0))
# --- Per-mode 4-panel plots ---
plot_pke_results(t1, X1, U1, plant, Q_shut;
title="ctrl_shutdown (cold IC)",
savepath=joinpath(figdir, "mode_sweep_1_shutdown.png"))
plot_pke_results(t2, X2, U2, plant, Q_heat;
title="ctrl_heatup (ramp T_avg)",
savepath=joinpath(figdir, "mode_sweep_2_heatup.png"))
plot_pke_results(t3, X3, U3, plant, Q_op;
title="ctrl_operation (P on T_avg)",
savepath=joinpath(figdir, "mode_sweep_3_operation.png"))
plot_pke_results(t3b, X3b, U3b, plant, Q_op;
title="ctrl_operation_lqr",
savepath=joinpath(figdir, "mode_sweep_3b_operation_lqr.png"))
plot_pke_results(t4, X4, U4, plant, Q_scr;
title="ctrl_scram",
savepath=joinpath(figdir, "mode_sweep_4_scram.png"))
# --- Heatup ramp-tracking figure ---
CtoF(T) = T*9/5 + 32
T_ref_trace = [min(T_standby + (28/3600)*ti, plant.T_c0) for ti in t2]
fig_heat = plot(t2 ./ 60, CtoF.(T_ref_trace), lw=1.3, ls=:dash, color=:black,
label="T_ref (28 C/hr ramp)",
xlabel="Time [min]", ylabel="T_avg [F]",
title="ctrl_heatup: reference tracking", size=(1000, 400))
plot!(fig_heat, t2 ./ 60, CtoF.(X2[:, 9]), lw=2, color=:red,
label="T_avg (plant)")
savefig(fig_heat, joinpath(figdir, "mode_sweep_heatup_tracking.png"))
# --- P vs LQR head-to-head ---
fig_ctrl = plot(t3, CtoF.(X3[:, 9]), lw=2, color=:blue, label="ctrl_operation (P)",
xlabel="Time [s]", ylabel="T_avg [F]",
title="Operation mode: P vs LQR under 100% -> 80% Q_sg step",
size=(1000, 400))
plot!(fig_ctrl, t3b, CtoF.(X3b[:, 9]), lw=2, color=:red, label="ctrl_operation_lqr")
hline!(fig_ctrl, [CtoF(plant.T_c0)], ls=:dash, color=:black, label="setpoint")
savefig(fig_ctrl, joinpath(figdir, "mode_sweep_op_P_vs_LQR.png"))
# --- Power overview ---
p_shut = plot(t1, max.(X1[:,1], 1e-20), yaxis=:log, title="Shutdown",
xlabel="t [s]", ylabel="n (log)", legend=false, lw=1.5)
p_heat = plot(t2 ./ 60, X2[:,1], title="Heatup", xlabel="t [min]", ylabel="n",
legend=false, lw=1.5)
p_op = plot(t3, X3[:,1], title="Operation", xlabel="t [s]", ylabel="n",
legend=false, lw=1.5)
p_scr = plot(t4, max.(X4[:,1], 1e-20), yaxis=:log, title="Scram",
xlabel="t [s]", ylabel="n (log)", legend=false, lw=1.5)
fig_ov = plot(p_shut, p_heat, p_op, p_scr, layout=(2,2), size=(1100, 650),
plot_title="Normalized reactor power n(t) across DRC modes")
savefig(fig_ov, joinpath(figdir, "mode_sweep_power_overview.png"))
println("\n=== Figures written to $figdir ===")

View File

@ -1,90 +1,150 @@
#!/usr/bin/env julia #!/usr/bin/env julia
# #
# reach_operation.jl — operation-mode linear reach in Julia. **STUB**. # reach_operation.jl — Julia port of reachability/reach_operation.m.
# #
# Attempt to reproduce reachability/reach_operation.m using # Linear reach tube for operation-mode LQR closed-loop. Per-halfspace
# ReachabilityAnalysis.jl. # margin check against inv2_holds (from predicates.json, single source
# of truth). Figures saved to docs/figures/.
# #
# STATUS: does NOT yet produce a useful result. The closed-loop system # Soundness caveat: this reach tube is a sound over-approximation of the
# is strongly stiff (eigvals spanning 0.012 to 65 /s) and has states # LINEARIZED closed-loop system's reach set, not of the nonlinear plant.
# with magnitudes differing by ~10 orders of magnitude (precursors C_i # Linear-reach results here are an approximate-but-useful gut check.
# ~ 1e5 due to 1/Lambda, temperatures ~ 300). LGG09 / GLGM06 / BFFPSV18
# all blow up numerically over the 600s horizon, returning envelopes
# ranging from 2757 K to 1e37 K instead of the known-tight 0.03 K.
#
# Likely fix: diagonal state scaling S such that A_cl_scaled = S A_cl S^{-1}
# has O(1) entries, run reach in scaled coordinates, then invert S.
# Also worth trying: ASB07 (adaptive step) or the Taylor-model schemes.
# Left as future work — the hand-rolled MATLAB zonotope in
# reachability/reach_linear.m gives a valid result today, so the Julia
# port is priority-B.
using Pkg using Pkg
Pkg.activate(joinpath(@__DIR__, "..")) Pkg.activate(joinpath(@__DIR__, ".."))
using Printf
using LinearAlgebra using LinearAlgebra
using MatrixEquations using MatrixEquations
using ReachabilityAnalysis, LazySets using Plots
using JSON
using MAT
include(joinpath(@__DIR__, "..", "src", "pke_params.jl")) include(joinpath(@__DIR__, "..", "src", "pke_params.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_th_rhs.jl")) include(joinpath(@__DIR__, "..", "src", "pke_th_rhs.jl"))
include(joinpath(@__DIR__, "..", "src", "pke_linearize.jl")) include(joinpath(@__DIR__, "..", "src", "pke_linearize.jl"))
include(joinpath(@__DIR__, "..", "src", "load_predicates.jl"))
include(joinpath(@__DIR__, "..", "src", "reach_linear.jl"))
plant = pke_params() plant = pke_params()
x_op = pke_initial_conditions(plant) x_op = pke_initial_conditions(plant)
pred = load_predicates(plant)
# --- Linearize around the operating point --- # --- Closed-loop linearization + LQR gain ---
A, B, B_w, _, _, _ = pke_linearize(plant) A, B, B_w, _, _, _ = pke_linearize(plant)
# --- LQR gain (same Q, R as the MATLAB side) ---
Q_lqr = Diagonal([1.0, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-2, 1e2, 1.0]) Q_lqr = Diagonal([1.0, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-3, 1e-2, 1e2, 1.0])
R_lqr = 1e6 * ones(1, 1) R_lqr = 1e6 * ones(1, 1)
X_ric, _, _ = arec(A, reshape(B, :, 1), R_lqr, Matrix(Q_lqr)) X_ric, _, _ = arec(A, reshape(B, :, 1), R_lqr, Matrix(Q_lqr))
K = (R_lqr \ reshape(B, 1, :) * X_ric) # 1 x 10 K = (R_lqr \ reshape(B, 1, :)) * X_ric
A_cl = A - reshape(B, :, 1) * K A_cl = A - reshape(B, :, 1) * K
println("\n=== Julia closed-loop spectrum ===") eigs_cl = eigvals(A_cl)
ev = eigvals(A_cl) println("\n=== Closed-loop spectrum (A - BK) ===")
println(" max Re(eig) = ", round(maximum(real.(ev)); sigdigits=4)) @printf " max Re(eig) = %.3e\n" maximum(real.(eigs_cl))
println(" min Re(eig) = ", round(minimum(real.(ev)); sigdigits=4)) @printf " min Re(eig) = %.3e\n" minimum(real.(eigs_cl))
@assert all(real.(eigs_cl) .< -1e-8) "A_cl not Hurwitz"
# --- Reach-set problem: dx/dt = A_cl dx + B_w w, dx(0) ∈ X0, w ∈ W --- # --- Entry box ---
delta_entry = [0.01 * x_op[1]; delta_entry = [0.01 * x_op[1];
0.001 .* abs.(x_op[2:7]); 0.001 .* abs.(x_op[2:7]);
0.1; 0.1; 0.1] 0.1; 0.1; 0.1]
X0 = Hyperrectangle(zeros(10), delta_entry)
# --- Disturbance envelope ---
Q_nom = plant.P0 Q_nom = plant.P0
w_lo, w_hi = -0.15 * plant.P0, 0.0 Q_min = 0.85 * plant.P0
W = Interval(w_lo, w_hi) Q_max = 1.00 * plant.P0
B_w_col = reshape(B_w, :, 1) dQ_lo = Q_min - Q_nom
dQ_hi = Q_max - Q_nom
# Encode the bounded disturbance as a bounded input: # --- Reach in deviation coordinates ---
# dx/dt = A_cl x + B_w u, u ∈ W. tspan = (0.0, 600.0)
# Direct constructor since the @system macro's dialect is package-version sensitive. dt = 0.5
sys = ConstrainedLinearControlContinuousSystem(A_cl, B_w_col, Universe(10), W) T, R_lo, R_hi, Cnom = reach_linear(A_cl, B_w, zeros(10), delta_entry,
prob = InitialValueProblem(sys, X0) dQ_lo, dQ_hi, tspan, dt)
sol = solve(prob; T=600.0, alg=GLGM06(; δ=0.5, max_order=20))
# Extract T_c envelope via support function queries. # Translate back to absolute coordinates.
flow = flowpipe(sol) X_lo = R_lo .+ x_op
e9 = zeros(10); e9[9] = 1.0 X_hi = R_hi .+ x_op
T_c_hi = [ρ(e9, set(R)) for R in flow] X_nom = Cnom .+ x_op
T_c_lo = [-ρ(-e9, set(R)) for R in flow]
println("\n=== Operation-mode reach envelope on T_c (deviation from T_c0) ===") # --- Safety check: inv2_holds halfspace-by-halfspace ---
println(" min dT_c = ", round(minimum(T_c_lo); digits=4), " K") inv2 = pred.mode_invariants[:inv2_holds]
println(" max dT_c = ", round(maximum(T_c_hi); digits=4), " K") A_inv = inv2.A_poly
println(" safety band |dT_c| <= 5.0 K") b_inv = inv2.b_poly
if maximum(abs.([T_c_lo; T_c_hi])) <= 5.0 comps = inv2.components
println(" OK: Julia reach set inside safety band.")
else println("\n=== Operation-mode reach vs inv2_holds safety limits ===")
println(" *** VIOLATION ***") for k in 1:size(A_inv, 1)
a = A_inv[k, :]
# Envelope max of a'*x: take Xhi where a>0, Xlo where a<0.
env_for_max = (a .> 0) .* X_hi .+ (a .< 0) .* X_lo
# Small correction: zero coeffs have no preference (both values equal).
zero_mask = (a .== 0)
env_for_max[zero_mask, :] .= X_hi[zero_mask, :]
max_ax = maximum(a' * env_for_max)
margin = b_inv[k] - max_ax
status = margin < 0 ? "*** VIOLATED ***" : "OK"
@printf " [%-22s] a'x <= %8.3f | max a'x = %8.3f | margin = %+8.3f %s\n" comps[k] b_inv[k] max_ax margin status
end end
# Save the envelope for later comparison # --- Per-state reach-set width diagnostic ---
using MAT state_names = ["n","C1","C2","C3","C4","C5","C6","T_f","T_c","T_cold"]
matwrite(joinpath(@__DIR__, "..", "..", "reachability", "julia_reach_operation.mat"), println("\n=== Reach-set width at t=0 vs t=T_final ===")
Dict("T_c_lo" => T_c_lo, "T_c_hi" => T_c_hi, @printf " %-7s %-14s %-14s %-8s\n" "state" "init halfwidth" "final halfwidth" "ratio"
"A_cl" => A_cl, "K" => Matrix(K), "delta_entry" => delta_entry)) for i in 1:10
println("\nSaved envelope to reachability/julia_reach_operation.mat") hi = 0.5 * (R_hi[i, 1] - R_lo[i, 1])
hf = 0.5 * (R_hi[i, end] - R_lo[i, end])
@printf " %-7s %.4e %.4e %.2f\n" state_names[i] hi hf hf/max(hi, eps())
end
# --- Plots: T_c reach tube, two views ---
CtoF(T) = T * 9/5 + 32
delta_safe_Tc = pred.constants.t_avg_in_range_halfwidth_C
figdir = joinpath(@__DIR__, "..", "..", "docs", "figures")
isdir(figdir) || mkpath(figdir)
p_safety = plot(T, CtoF.(X_nom[9, :]), lw=1.2, color=:red,
label="nominal",
xlabel="Time [s]", ylabel="T_avg [F]",
title="Safety-band view")
plot!(p_safety, T, CtoF.(X_hi[9, :]), fillrange=CtoF.(X_lo[9, :]),
fillalpha=0.3, color=:red, linealpha=0.0,
label="reach tube")
hline!(p_safety, [CtoF(plant.T_c0 + delta_safe_Tc),
CtoF(plant.T_c0 - delta_safe_Tc)],
ls=:dash, color=:black, label="safety +/- $(round(delta_safe_Tc; digits=2)) C")
dev_lo = X_lo[9, :] .- plant.T_c0
dev_hi = X_hi[9, :] .- plant.T_c0
max_dev = maximum(abs, [dev_lo; dev_hi])
p_zoom = plot(T, X_nom[9, :] .- plant.T_c0, lw=1.2, color=:red,
label="nominal",
xlabel="Time [s]", ylabel="T_avg - T_c0 [K]",
title=@sprintf("Zoomed: max |dT_c| = %.3e K", max_dev))
plot!(p_zoom, T, dev_hi, fillrange=dev_lo, fillalpha=0.3,
color=:red, linealpha=0.0, label="reach tube")
hline!(p_zoom, [0.0], ls=:dot, color=:black, label=nothing)
fig = plot(p_safety, p_zoom, layout=(1, 2), size=(1400, 500),
plot_title=@sprintf("Operation-mode reach tube, LQR, Q_sg in [%.0f%%, %.0f%%] P0",
100*Q_min/Q_nom, 100*Q_max/Q_nom))
savefig(fig, joinpath(figdir, "reach_operation_Tc.png"))
# n tube
fig_n = plot(T, X_nom[1, :], lw=1.2, color=:blue, label="nominal",
xlabel="Time [s]", ylabel="n",
title="Operation mode reach tube on normalized power")
plot!(fig_n, T, X_hi[1, :], fillrange=X_lo[1, :], fillalpha=0.3,
color=:blue, linealpha=0.0, label="reach tube")
savefig(fig_n, joinpath(figdir, "reach_operation_n.png"))
# --- Save result ---
matfile = joinpath(@__DIR__, "..", "..", "reachability", "reach_operation_result.mat")
matwrite(matfile, Dict("T" => collect(T), "R_lo" => R_lo, "R_hi" => R_hi,
"center" => Cnom, "X_lo" => X_lo, "X_hi" => X_hi,
"X_nom" => X_nom, "K" => Matrix(K), "A_cl" => A_cl,
"delta_entry" => delta_entry,
"Q_min" => Q_min, "Q_max" => Q_max,
"delta_safe_Tc" => delta_safe_Tc))
println("\nSaved reach result to $matfile")

View File

@ -0,0 +1,132 @@
"""
load_predicates(plant)
Parse `reachability/predicates.json` into a NamedTuple of concretized
halfspaces + constants. Julia counterpart of `reachability/load_predicates.m`.
Returns a NamedTuple with fields:
- `constants` NamedTuple of plant-derived constants
(T_c0, T_f0, T_cold0, T_standby, etc.)
- `operational_deadbands` Dict{Symbol, NamedTuple{(:A_poly, :b_poly, :meaning)}}
- `safety_limits` same shape
- `mode_invariants` NamedTuple with .inv1_holds, .inv2_holds,
each holding conjoined A_poly, b_poly,
and a components list
Each `A_poly` is an `n_halfspaces × 10` matrix; the predicate is
`{x : A_poly * x <= b_poly}`.
Multi-coefficient rows are supported: an entry with `"row"` key listing
`[[state_index, coeff], ...]` pairs populates multiple columns of one
row. Single-coefficient entries (`"state_index"` + `"coeff"`) still
work for backward compat.
"""
function load_predicates(plant)
here = @__DIR__
json_path = joinpath(here, "..", "..", "reachability", "predicates.json")
J = JSON.parsefile(json_path)
# Context for rhs_expr evaluation.
T_c0 = plant.T_c0
T_f0 = plant.T_f0
T_cold0 = plant.T_cold0
T_standby_offset_C = J["derived"]["T_standby_offset_C"]
T_standby = T_c0 + T_standby_offset_C
function eval_rhs(expr::AbstractString)
# Tiny sandbox — only the names below are visible.
local_ctx = Dict(
:T_c0 => T_c0,
:T_f0 => T_f0,
:T_cold0 => T_cold0,
:T_standby => T_standby,
)
parsed = Meta.parse(expr)
# Evaluate within a let-block binding our locals.
eval_expr = quote
let T_c0 = $T_c0, T_f0 = $T_f0, T_cold0 = $T_cold0, T_standby = $T_standby
$parsed
end
end
return eval(eval_expr)
end
function parse_group(group_dict)
out = Dict{Symbol, NamedTuple}()
for (name, entry) in group_dict
startswith(name, "_") && continue
!isa(entry, AbstractDict) && continue
!haskey(entry, "halfspaces") && continue
hs_list = entry["halfspaces"]
n_hs = length(hs_list)
A_poly = zeros(n_hs, 10)
b_poly = zeros(n_hs)
for (i, hs) in enumerate(hs_list)
if haskey(hs, "row")
# Multi-coefficient row: [[idx, coeff], ...]
for pair in hs["row"]
idx = Int(pair[1])
coeff = Float64(pair[2])
A_poly[i, idx] = coeff
end
else
# Single-coefficient row.
A_poly[i, Int(hs["state_index"])] = Float64(hs["coeff"])
end
b_poly[i] = eval_rhs(hs["rhs_expr"])
end
meaning = get(entry, "meaning", "")
out[Symbol(name)] = (A_poly=A_poly, b_poly=b_poly, meaning=meaning)
end
return out
end
deadbands = parse_group(J["operational_deadbands"])
safety = parse_group(J["safety_limits"])
# Mode invariants: conjunctions of safety_limits entries.
inv_dict = J["mode_invariants"]
mode_inv = Dict{Symbol, NamedTuple}()
for (name, entry) in inv_dict
startswith(name, "_") && continue
!isa(entry, AbstractDict) && continue
!haskey(entry, "conjunction_of") && continue
components = entry["conjunction_of"]
isa(components, String) && (components = [components])
A_all = Matrix{Float64}(undef, 0, 10)
b_all = Vector{Float64}()
for comp in components
sym = Symbol(comp)
if haskey(safety, sym)
A_all = [A_all; safety[sym].A_poly]
b_all = [b_all; safety[sym].b_poly]
end
end
mode_inv[Symbol(name)] = (A_poly=A_all, b_poly=b_all,
components=components,
meaning=get(entry, "meaning", ""))
end
constants = (
T_c0 = T_c0,
T_f0 = T_f0,
T_cold0 = T_cold0,
T_standby = T_standby,
T_standby_offset_C = T_standby_offset_C,
T_standby_offset_F = J["derived"]["T_standby_offset_F"],
t_avg_in_range_halfwidth_C = J["derived"]["t_avg_in_range_halfwidth_C"],
p_above_crit_threshold_n = J["derived"]["p_above_crit_threshold_n"],
T_fuel_limit_C = J["derived"]["T_fuel_limit_C"],
T_c_high_trip_C = J["derived"]["T_c_high_trip_C"],
n_high_trip = J["derived"]["n_high_trip"],
)
return (
constants = constants,
operational_deadbands = deadbands,
safety_limits = safety,
mode_invariants = mode_inv,
)
end

View File

@ -0,0 +1,77 @@
"""
pke_solver(plant, Q_sg, ctrl_fn, ref, tspan; x0=nothing, verbose=true)
Closed-loop simulation of the PKE + thermal-hydraulics plant with a
named controller. Analog of `plant-model/pke_solver.m` but using
Julia's OrdinaryDiffEq under the hood (Rodas5 for stiff systems,
matches MATLAB's ode15s behavior).
Arguments:
- `plant` : parameter NamedTuple from `pke_params()`
- `Q_sg` : callable `Q_sg(t)` returning SG heat removal [W]
- `ctrl_fn` : callable `u = ctrl_fn(t, x, plant, ref)`
- `ref` : any ref struct (NamedTuple or nothing) passed to controller
- `tspan` : `(t_start, t_end)` tuple
- `x0` : optional initial state (default: operating-point equilibrium)
- `verbose` : print steady-state and final-state banners (default: true)
Returns `(t, X, U)`:
- `t :: Vector{Float64}` time grid from the solver
- `X :: Matrix{Float64}` M × 10 state matrix (rows are time, cols are states)
- `U :: Vector{Float64}` M-element control trajectory
The state column indices match `pke_th_rhs!`: `[n, C1..C6, T_f, T_c, T_cold]`.
"""
function pke_solver(plant, Q_sg, ctrl_fn, ref, tspan; x0=nothing, verbose=true)
if x0 === nothing
x0 = pke_initial_conditions(plant)
end
CtoF(T) = T * 9 / 5 + 32
if verbose
println("=== Steady-State Conditions ===")
@printf " beta = %.5f (%.1f pcm)\n" plant.beta plant.beta*1e5
@printf " Lambda = %.1e s\n" plant.Lambda
@printf " P0 = %.0f MWth\n" plant.P0/1e6
@printf " T_cold = %.1f F\n" CtoF(plant.T_cold0)
@printf " T_avg = %.1f F\n" CtoF(plant.T_c0)
@printf " T_hot = %.1f F\n" CtoF(plant.T_hot0)
@printf " T_fuel = %.1f F\n" CtoF(plant.T_f0)
@printf " Core dT = %.1f F\n" plant.dT_core * 9/5
println("================================\n")
end
# Closed-loop RHS: controller provides u, then plant RHS.
function rhs!(dx, x, p, t)
u = ctrl_fn(t, x, plant, ref)
pke_th_rhs!(dx, x, t, plant, Q_sg, u)
end
prob = ODEProblem(rhs!, x0, tspan)
sol = solve(prob, Rodas5(); reltol=1e-8, abstol=1e-10)
t_arr = sol.t
X = reduce(hcat, sol.u)' # M × 10
U = [ctrl_fn(sol.t[k], sol.u[k], plant, ref) for k in 1:length(sol.t)]
if verbose
n_f = X[end, 1]
T_f_f = X[end, 8]
T_c_f = X[end, 9]
T_col_f = X[end, 10]
T_hot_f = 2 * T_c_f - T_col_f
rho_tot = U[end] + plant.alpha_f*(T_f_f - plant.T_f0) +
plant.alpha_c*(T_c_f - plant.T_c0)
println("=== Final State (t = $(round(t_arr[end]; digits=1)) s) ===")
@printf " Power = %.1f MWth (%.3f x nominal)\n" n_f*plant.P0/1e6 n_f
@printf " T_fuel = %.1f F\n" CtoF(T_f_f)
@printf " T_hot = %.1f F\n" CtoF(T_hot_f)
@printf " T_avg = %.1f F\n" CtoF(T_c_f)
@printf " T_cold = %.1f F\n" CtoF(T_col_f)
@printf " u = %.4f \$ (external reactivity)\n" U[end]/plant.beta
@printf " rho = %.4f \$ (total, incl. T-feedback)\n" rho_tot/plant.beta
end
return t_arr, Matrix(X), U
end

View File

@ -0,0 +1,50 @@
"""
plot_pke_results(t, X, U, plant, Q_sg; title="", savepath=nothing)
Four-panel visualization of a closed-loop PKE + T/H simulation result.
Analog of `plant-model/plot_pke_results.m`. Uses `Plots.jl` with GR
backend (default; no extra dependencies).
Panels:
(1) Normalized power and Q_sg demand
(2) Coolant temperatures (T_cold, T_avg, T_hot)
(3) Fuel temperature
(4) External reactivity u (in dollars)
"""
function plot_pke_results(t, X, U, plant, Q_sg; title="", savepath=nothing)
CtoF(T) = T * 9/5 + 32
n_trace = X[:, 1]
T_f = X[:, 8]
T_c = X[:, 9]
T_cold = X[:, 10]
T_hot = 2 .* T_c .- T_cold
Q_trace = [Q_sg(ti) / plant.P0 for ti in t]
u_dollars = U ./ plant.beta
p1 = plot(t, n_trace, lw=1.8, label="n (normalized power)",
xlabel="Time [s]", ylabel="n", legend=:right)
plot!(p1, t, Q_trace, lw=1.2, ls=:dash,
label="Q_sg / P_0 (demand)")
p2 = plot(t, CtoF.(T_cold), lw=1.8, label="T_cold",
xlabel="Time [s]", ylabel="T [F]", legend=:right)
plot!(p2, t, CtoF.(T_c), lw=1.8, label="T_avg")
plot!(p2, t, CtoF.(T_hot), lw=1.8, label="T_hot")
p3 = plot(t, CtoF.(T_f), lw=1.8, label="T_fuel",
xlabel="Time [s]", ylabel="T [F]", legend=:right)
p4 = plot(t, u_dollars, lw=1.8, label="u [\$]",
xlabel="Time [s]", ylabel="Reactivity [\$]", legend=:right)
fig = plot(p1, p2, p3, p4, layout=(2,2), size=(1100, 700),
plot_title=title, plot_titlefontsize=11)
if savepath !== nothing
savefig(fig, savepath)
end
return fig
end

View File

@ -0,0 +1,71 @@
"""
reach_linear(A_cl, B_w, x0_center, x0_halfwidth, w_lo, w_hi, tspan, dt)
Hand-rolled box-zonotope reach tube for `dx/dt = A_cl*x + B_w*w` with
`x(0)` in an axis-aligned box (center, halfwidths) and `w` in a scalar
interval. Julia port of `reachability/reach_linear.m`.
Returns `(T, R_lo, R_hi, center)`:
- `T :: Vector{Float64}` time grid
- `R_lo :: Matrix{Float64}` `n × M` lower bounds
- `R_hi :: Matrix{Float64}` `n × M` upper bounds
- `center :: Matrix{Float64}` `n × M` nominal (w_mid-driven) trajectory
Mathematical setup:
x(t) = e^(A·t)·x(0) + integral_0^t e^((t-s))·B_w·w(s) ds
Per step of size dt:
A_step = expm(A_cl * dt)
G_step = integral_0^dt e^(A_cl·s)·B_w ds (via Van Loan augmented trick)
Halfwidths propagate using elementwise-|·| matrix: a box under linear
map M becomes a box with halfwidth |M|·h (sound over-approximation).
"""
function reach_linear(A_cl, B_w, x0_center, x0_halfwidth, w_lo, w_hi, tspan, dt)
n = size(A_cl, 1)
@assert size(A_cl, 2) == n "A_cl must be square"
x0_center = vec(x0_center)
x0_halfwidth = vec(x0_halfwidth)
B_w_col = vec(B_w)
w_mid = 0.5 * (w_lo + w_hi)
w_half = 0.5 * (w_hi - w_lo)
T = collect(tspan[1]:dt:tspan[2])
M = length(T)
R_lo = zeros(n, M)
R_hi = zeros(n, M)
centr = zeros(n, M)
A_step = exp(A_cl * dt)
A_abs = abs.(A_step)
# Van Loan augmented matrix: upper-right block of exp([A B_w; 0 0]*dt)
# equals integral_0^dt exp(A*s)*B_w ds.
aug = [A_cl B_w_col; zeros(1, n+1)]
aug_exp = exp(aug * dt)
G_step = aug_exp[1:n, n+1]
G_abs = abs.(G_step)
x_center_now = copy(x0_center)
halfwidth_now = copy(x0_halfwidth)
S_center = zeros(n)
S_half = zeros(n)
centr[:, 1] = x_center_now .+ S_center
R_lo[:, 1] = centr[:, 1] .- halfwidth_now .- S_half
R_hi[:, 1] = centr[:, 1] .+ halfwidth_now .+ S_half
for k in 2:M
x_center_now = A_step * x_center_now
halfwidth_now = A_abs * halfwidth_now
S_center = A_step * S_center + G_step * w_mid
S_half = A_abs * S_half + G_abs * w_half
centr[:, k] = x_center_now .+ S_center
R_lo[:, k] = centr[:, k] .- halfwidth_now .- S_half
R_hi[:, k] = centr[:, k] .+ halfwidth_now .+ S_half
end
return T, R_lo, R_hi, centr
end