Robotics: Science and Systems · 2026

Realizing Robotic Swimming with
Unified Fluid Robot Multiphysics

Jeong Hun Lee1,†· Junzhe Hu1,†· Sofia Kwok1· Carmel Majidi1· Zac Manchester1

1Carnegie Mellon University

Equal contribution

arXiv Code Video BibTeX
Time-lapse comparison of a multi-link eel robot across t = 0 to 3 seconds. Top row: hardware. Middle row: our unified multiphysics simulator. Bottom row: particle-based simulator.
Time-lapse on a multi-link eel robot across t = 0–3 s. Hardware (top) is closely tracked by our unified multiphysics simulator (middle), while a particle-based simulator (bottom) fails to capture the coupled fluid-robot dynamics — rolling out the same control trajectory drifts off the hardware path.

Abstract

Matching the swimming efficiency and agility of fish has remained an elusive goal in underwater robotics. Such locomotion relies on complex vortex interactions between the robot's body and the surrounding fluid, governed by coupled ordinary and partial differential equations — significantly more difficult than the multi-body dynamics of classical rigid robotic systems.

We present a differentiable framework for simulating strongly coupled fluid-robot multiphysics as a unified optimization problem. The coupled manipulator and incompressible Navier–Stokes equations are derived together from a single Lagrangian using the principle of least action. We employ discrete variational mechanics to derive a stable, well-conditioned, and physically accurate scheme for jointly simulating articulated bodies and the surrounding fluid, and leverage the implicit function theorem to compute derivatives through the fully coupled dynamics.

Using this simulator and its gradients, we realize undulating swimming gaits and optimize a highly dynamic C-start escape maneuver for a bioinspired eel robot. We validate both gaits on physical hardware, demonstrating successful sim-to-real transfer.

Video Overview

Full supplemental video — an end-to-end walkthrough of the unified Lagrangian formulation, the discrete variational integrator, simulation results, and hardware experiments on the eel robot.

Method

Existing multiphysics simulators time-integrate the fluid and robot equations separately, then couple them through an explicit force term. We instead pose the entire problem as a single least-action optimization: the unified Lagrangian is discretized directly, and the coupling forces emerge as Lagrange multipliers of a no-slip constraint.

Unified least-action formulation: a single constrained optimization yields the incompressible Navier-Stokes and manipulator equations, coupled through Lagrange multipliers.
The unified Lagrangian governing the coupled fluid–robot dynamics. Variational calculus on the combined action recovers the incompressible Navier–Stokes and manipulator equations; the multiphysics coupling stems from a single constraint enforcing no-slip at the fluid–robot interface.

1.From least action to the manipulator equation

For a system with configuration $q(t)\in\R^n$, velocity $v(t)\in\R^m$, kinetic energy $T(v)$, and potential energy $U(q)$, the principle of least action poses the dynamics as a continuous-time optimization problem:

$$\min_{q,\,v}\;\; \int_{t_0}^{t_f} T\!\big(v(t)\big) - U\!\big(q(t)\big)\, dt \quad\text{s.t.}\quad v=\dot{q}.$$ (1)

Introducing a Lagrange multiplier $\lambda$ for the kinematic constraint and writing $L(q,v) = T(v) - U(q)$, the action becomes $\;S(q,v)=\int_{t_0}^{t_f} L(q,v) + \lambda^\top(\dot q - v)\, dt.$ Stationarity yields the Euler–Lagrange equation

$$\frac{d}{dt}\frac{\partial L}{\partial \dot q} - \frac{\partial L}{\partial q} \;=\; 0,$$ (2)

which in robotics is more familiar as the manipulator equation $\;M(q)\ddot q + C(q,\dot q)\dot q + G(q) = 0.$ The least-action principle generalizes to dissipative systems via Lagrange–D'Alembert, to non-trivial kinematics $v=f(q,\dot q)$, and to additional constraints $c(q,v)=0$:

$$\min_{q,\,v}\; \int_{t_0}^{t_f} T(q,v) - U(q) + F(t)^\top q(t)\, dt \;\;\text{s.t.}\;\; v=f(q,\dot q),\;\; c(q,v)=0.$$ (3)

2.A unified Lagrangian for fluid–robot multiphysics

For a rigid multibody robot interacting with an incompressible Newtonian fluid (e.g., water), we define fluid and robot Lagrangians as

$$L^f(q^f,v^f) = \int_\Omega \tfrac{1}{2}\rho\, (v^f)^\top v^f - \rho\, g^\top q^f \, dV$$ (4)
$$L^r(q^r,v^r) = \tfrac{1}{2}(v^r)^\top M^r v^r - M^r g^\top q^r$$ (5)

where $\rho$ is fluid density, $\mu$ its dynamic viscosity, $\Omega$ the fluid domain with boundary $\partial\Omega$, $\Gamma$ the robot geometry with boundary $\partial\Gamma$, and $M^r$ the robot mass matrix. Damping enters via the viscous term $F(t)=\int_\Omega \mu\,\Delta v^f\, dV$. The full multiphysics is then a single constrained optimization over fluid and robot states:

Unified least action
$$\begin{aligned} \min_{q^r,\,v^r,\,q^f,\,v^f}\;\; & \int_{t_0}^{t_f}\! \color{#5fb0e0}{L^f(q^f,v^f)} + \color{#6cc97a}{L^r(q^r,v^r)} + F(t)^\top q^f \, dt \\[2pt] \text{s.t.}\;\; & c_1(v^f)=\dot q^f - v^f(q^f)=0 && \forall\, q^f\in\Omega \\ & c_2(v^f)=\nabla\!\cdot v^f = 0 && \forall\, q^f\in\Omega \\ & c_3(v^f)=v^f - v_{bc}=0 && \forall\, q^f\in\partial\Omega \\ & c_4(v^r)=\dot q^r - v^r=0 && \forall\, q^r \\ & c_5(q^r)=0 && \forall\, q^r \\ & \color{#f0a45e}{c_6(v^f,v^r)=v^f - {}^bv^r=0} && \forall\, q^f\in\Gamma \end{aligned}$$
(6)

Constraints $c_1\!-\!c_4$ are the standard kinematic and conservation conditions; $c_5$ encodes joint constraints; $c_6$ is the no-slip condition at the fluid-robot interface and is the only coupling between the two physics.

Forming the action $S = \int (L^f + L^r + F^\top q^f + \sum_{i=1}^6 \lambda_i c_i)\, dt$ and taking variations w.r.t. $(q^f,v^f)$ and $(q^r,v^r)$ recovers the coupled incompressible Navier–Stokes and manipulator equations:

$$\rho\!\left(\dot v^f + (v^f\!\cdot\!\nabla) v^f\right) = -\nabla p + \mu\nabla^2 v^f - \rho g \;\color{#f0a45e}{- \tfrac{\partial c_3}{\partial v^f}^{\!\!\top}\!\dot\lambda_3 - \tfrac{\partial c_6}{\partial v^f}^{\!\!\top}\!\dot\lambda_6}$$ (7)
$$\nabla\!\cdot v^f = 0$$ (8)
$$M^r \dot v^r + \rho g = \tfrac{\partial c_5}{\partial q^r}^{\!\!\top}\!\lambda_5 \;\color{#f0a45e}{-\, \tfrac{\partial c_6}{\partial v^r}^{\!\!\top}\!\dot\lambda_6}, \qquad \dot q^r = v^r$$ (9)
Where the coupling lives

The orange terms in (7) and (9) share the same dual variable $\lambda_6$. The pressure $p \equiv \dot\lambda_2$ is itself the multiplier that enforces $\nabla\!\cdot v^f=0$ — a fact Lagrange noted in his Mécanique analytique. Boundary conditions and the no-slip interface inherit the same constraint-with-dual-variable structure that Allmaras (2005) used for compressible aerodynamics.

3.A variational integrator that handles the temporal lag

Discretizing the action in time is delicate. A midpoint quadrature gives a discrete Lagrangian $L_d(q_k,q_{k+1}) = h\,L\!\left(\tfrac{q_k+q_{k+1}}{2},\,\tfrac{q_{k+1}-q_k}{h}\right)$ in which the velocity $\bv_k$ lives between the configurations $q_k$ and $q_{k+1}$. For pure rigid-body simulation this half-step delay is harmless. For our problem it is not: the fluid is represented as a velocity field $\bv^f$ while the robot pose lives in $q^r$, and the no-slip constraint must couple them at a consistent time.

Marsden & West (2001) resolve this via the discrete Legendre transform, which is awkward in the presence of constraints. We instead define every constraint at the time step at which its variable naturally lives ($q_k$ for the robot, $\bv_k$ for the fluid), and rewrite the discrete Euler–Lagrange relation directly via the chain rule:

$$D_2 L_d(q_{k-1},q_k) = h\!\left(\tfrac{\partial L}{\partial \bq_k}\!\cdot\!\tfrac{1}{2} + \tfrac{\partial L}{\partial \bv_k}\!\cdot\!\tfrac{1}{h}\right)$$ (10)
$$D_1 L_d(q_k,q_{k+1}) = h\!\left(\tfrac{\partial L}{\partial \bq_{k+1}}\!\cdot\!\tfrac{1}{2} + \tfrac{\partial L}{\partial \bv_{k+1}}\!\cdot\!\big(\!-\!\tfrac{1}{h}\big)\right)$$ (11)

Substituting these back into the discrete Euler–Lagrange equation produces, after some algebra, two coupled update rules — one for the robot, one for the fluid — that are simultaneously solved each time step. With $\bv^r_{k+1}$ and $\bv^f_{k+1}$ as unknowns:

$$\tfrac{1}{2}M^r \bv^r_{k+1} \,-\, h\!\left(\tfrac{\partial c_5}{\partial q^r_k}\right)^{\!\!\top}\!\lambda_{5,k} \,\color{#f0a45e}{-\, h\!\left(\tfrac{\partial c_6}{\partial \bv^r_k}\right)^{\!\!\top}\!\lambda_{6,k}} = \tfrac{1}{2}M^r \bv^r_k - h M^r g$$ (12)
$$\begin{aligned} \tfrac{1}{2}(M^f - \mu h L)\bv^f_{k+1} &- \tfrac{h}{2} N(\bv^f_{k+1}) + \color{#b690d4}{G\, p_k} + B\,\lambda_{3,k} \color{#f0a45e}{- h\!\left(\tfrac{\partial c_6}{\partial \bv^f_k}\right)^{\!\!\top}\!\lambda_{6,k}} \\ &\quad = \tfrac{1}{2}(M^f + \mu h L)\bv^f_k + \tfrac{h}{2}N(\bv^f_k) - h M^f g \end{aligned}$$ (13)

Together with the discrete constraints $G^\top \bv^f_{k+1}=0$ (incompressibility), $B\bv^f_{k+1}=v_{bc}$ (boundary), $\bar E\,\bv^f_{k+1} = {}^b\bv^r(\bv^r_{k+1})$ (no-slip), and $c_5(q^r_{k+1})=0$ (joints), the system forms a sparse nonlinear root-finding problem solved by Newton's method. The resulting scheme is a 2nd-order implicit leap-frog integrator, and derivatives through it are obtained from the implicit function theorem.

Spatial discretization — finite-volume operators

The fluid domain is discretized with a second-order finite-volume scheme yielding the following discrete counterparts of the continuous operators that appear in the Navier–Stokes equations:

$\;\int_\Omega \rho v^f\, dV \mapsto M^f v^f,\quad \int_\Omega \nabla p\, dV \mapsto Gp,\quad \int_\Omega (v^f\!\cdot\!\nabla)v^f\, dV \mapsto N(v^f),\quad \int_\Omega \Delta v^f\, dV \mapsto Lv^f.$

$M^f$ is the lumped fluid mass matrix, $G$ the discrete gradient, $N(\cdot)$ the (nonlinear) convection operator, and $L$ the discrete Laplacian. $B$ extracts cells on $\partial\Omega$.

4.An integral-form immersed boundary for multibody robots

The classical immersed-boundary method enforces no-slip pointwise: $\;\int_\Omega v^f\,\delta(q^f-{}^bq^r)\, d\Omega = {}^bv^r,\;$ discretized as $\;E v^f - {}^bv^r = 0,\;$ with a convolution matrix $E$ built from a smoothed delta. This satisfies no-slip only at a finite set of boundary nodes — allowing fluid penetration when nodes are sparse, and producing redundant, ill-conditioned constraints when nodes from neighboring bodies overlap. Both pathologies are common in articulated robots.

We instead integrate the constraint along the whole boundary $\Gamma$:

$$\oint_\Gamma\!\int_\Omega v^f\, \delta\!\big(q^f-{}^bq^r(q^r)\big)\, dV\, dS \;=\; \oint_\Gamma {}^bv^r(q^r,v^r)\, dS$$ (14)

Discretizing with piecewise-linear interpolation along the boundary and integrating the smoothed delta along each segment yields a new convolution matrix $\bar E$:

$$\bar E\, v^f - {}^bv^r(v^r) \;=\; 0$$ (15)

Unlike the pointwise form, $\bar E$ stays well-conditioned when boundary nodes overlap, and the constraint is satisfied between nodes rather than only at them. Differentiating through (15) inside (12)–(13) gives the multibody-friendly coupling we use throughout the paper.

5.Contributions

Results

Steady undulatory swimming

We drive each joint with a phase-shifted sinusoid to produce a traveling wave at 1 Hz with body wavelength $\lambda = L_B$. Across joint amplitudes from 10° to 40° (20 trials each), our method consistently tracks hardware while the SPH baseline drifts — the gap widens with amplitude.

Time-lapse comparison: Hardware, Unified Multiphysics, and Particle-based Simulator at t = 0, 1, 2, 3, 4 seconds.
Time-lapse of forward swimming at 40° amplitude across t = 0–4 s. Hardware (top) is closely tracked by our unified multiphysics simulator (middle), while the particle-based baseline (bottom) drifts — the gap widens with amplitude.
Bar charts of head-link RMSE for x1, y1, and theta1 versus undulation amplitude (10, 20, 30, 40 degrees), comparing Unified Multiphysics against the particle-based baseline.
Mean trajectory RMSE of the head-link configuration ($x_1$, $y_1$, $\theta_1$) versus undulation amplitude. Unified multiphysics outperforms the particle-based baseline across all amplitudes, with up to 75% error reduction at 40°.
Hardware
Hardware undulatory swimming at 40° amplitude
Ours — unified multiphysics
Our unified multiphysics simulator at 40° amplitude
Genesis — particle-based
Genesis particle-based baseline at 40° amplitude

Optimizing a highly dynamic C-start

We use the simulator's gradients to optimize a fish-inspired C-start escape maneuver. The maneuver consists of a bend phase (0–1 s) where the robot curls into a C-shape, followed by a propulsion phase (1–3 s) where it transitions into undulation. The optimization variables are the per-joint bend angles $\bar\theta_{1:5}$, the head joint phase $\phi_1$, and body wavelength $\lambda$; the undulation amplitude is fixed at 25° to avoid hitting the wall. With L-BFGS, starting from $\bar\theta_{1:5}=[36^\circ\!,\,36^\circ\!,\,36^\circ\!,\,36^\circ\!,\,36^\circ]$, $\phi_1=-\pi/4$, $\lambda=0.7L_B$, we maximize center-of-mass velocity in the target direction and converge to $\bar\theta_{1:5}\!\approx\![17.2^\circ\!,\,17.8^\circ\!,\,19.4^\circ\!,\,23.1^\circ\!,\,36^\circ]$, $\phi_1\!\approx\!-1.16$, $\lambda\!\approx\!0.57L_B$ — achieving a 90° turn from rest that transfers open-loop to hardware. The SPH baseline fails to realize either the turn or the propulsion.

a.Initial guess (before optimization)

Hardware
Hardware C-start with the initial (un-optimized) parameters
Ours — unified multiphysics
Our unified multiphysics simulator C-start before optimization
Genesis — particle-based
Genesis particle-based baseline C-start before optimization

b.After gradient-based optimization — 90° turn from rest

Hardware
Hardware optimized C-start, 90° turn
Ours — unified multiphysics
Our unified multiphysics simulator optimized C-start, 90° turn
Genesis — particle-based
Genesis particle-based baseline rolled out with the optimized control trajectory
Head-link XY trajectories during the C-start: dotted lines for the initial guess and solid lines for the gradient-optimized parameters, plotted for Hardware, Unified Multiphysics, and the particle-based baseline.
Head-link XY trajectories during the C-start. Dotted: initial guess; solid: after gradient-based optimization. Our unified multiphysics simulator (cyan) closely follows the hardware (red) post-optimization, executing the 90° turn from rest, while the particle-based baseline (orange) stalls near the start point in both regimes.

Hardware

The eel robot has 6 rigid links (9.8 cm each) connected by revolute joints driven by Dynamixel XC330-M288-T servos. It is fully untethered, with an onboard 900 mAh battery and a Robotis OpenRB-150 microcontroller in the head link. Buoyant 3D-printed shells house the electronics; thin rigid fins underneath maintain a thin-plate hydrodynamic profile. Head-link pose is tracked by an overhead camera via AprilTags in a 122 × 122 cm pool, recreating the simulated walled cavity.

Hardware setup: a 122 x 122 cm pool with an overhead camera, and an inset showing the eel robot with annotated motors, body shells, fins, and microcontroller.
Sim-to-real validation setup. An overhead camera tracks AprilTags on the head link inside a 122 × 122 cm pool that recreates the simulated walled cavity. Inset: the bioinspired eel robot, with buoyant 3D-printed body shells housing the Dynamixel motors and head-link microcontroller; thin rigid fins underneath maintain a thin-plate hydrodynamic profile.

Citation

@inproceedings{lee2026realizing,
  title     = {Realizing Robotic Swimming with Unified Fluid-Robot Multiphysics},
  author    = {Lee, Jeong Hun and Hu, Junzhe and Kwok, Sofia
               and Majidi, Carmel and Manchester, Zachary},
  booktitle = {Robotics: Science and Systems (RSS)},
  year      = {2026},
  note      = {Equal contribution: J. H. Lee and J. Hu}
}

Acknowledgments

The authors thank the members of the Robotic Exploration Lab and the Soft Machines Lab at Carnegie Mellon University for valuable discussions and feedback. [Add funding sources and individual acknowledgments here.]

This page borrows its structure from the Nerfies project page; source available on GitHub.