Introduction

Robots composed of soft and elastically deformable materials can be engineered to squeeze through confined spaces1, sustain large impacts2, execute rapid and dramatic shape change3, and exhibit other robust mechanical properties that are often difficult to achieve with more conventional, piece-wise rigid robots4,5,6,7,8,9,10. These platforms not only exhibit unique and versatile mobility for applications in biologically inspired field robotics, but can also serve as a testbed for understanding the locomotion of soft biological organisms. However, owing to the current limitations with simulating the dynamics of soft material systems, design and control of soft robots often involve a painstaking trial and error process, and it can be difficult to relate qualitative observations to underlying principles of kinematics, mechanics, and tribology. Progress, therefore, depends on a computational framework for deterministic soft robot modeling that can aid in design, control, and experimental analysis.

Previous efforts to simulate soft robots have focused on Finite Element Method11,12,13,14,15,16, voxel-based discretization17,18, and modeling of slender soft robot appendages using Cosserat rod theory19,20,21. Drawing inspiration from simulation techniques based on discrete differential geometry (DDG) that are widely used in the computer graphics community22, we introduce a DDG-based numerical simulation tool for examining the locomotion of limbed soft robots. The DDG approach starts with discretization of the smooth system into a mass-spring-type system, while preserving the key geometric properties of actual physical objects; this type of simulation tool is naturally suited to account for contact and collision23. In particular, we treat the robot as being composed of multiple slender actuators that can be modeled using elastic rod theories24,25,26,27,28. In order to achieve rapid simulation runtimes, we adapt fast and efficient physically based computational techniques that have gained traction within the computer graphics community to model slender structures, e.g., rods29,30,31, ribbons32, plates33, shells34, viscous threads30,35, and viscous sheets36. Despite the visual realism in these simulation methods, these prior works do not comprehensively capture all the physical ingredients for a physically accurate simulation of fast moving articulated soft robots. Our numerical method integrates these ingredients—frictional contact, material damping, and inertial effects—into a discrete simulation framework to achieve quantitative agreement with experiments. Recently, a DDG-based formulation was used to model a caterpillar-inspired soft robot in which the individual segments of the robot were treated as curved elastic rod elements37. Although promising, this formulation could not accurately capture inertial effects—a key feature of fast moving robots—and did not incorporate the necessary contact and friction laws required to achieve quantitative agreement with experimental measurements.

Here, we employ a discrete representation of a soft robot and incorporate Coulomb frictional contact, inelastic collision with ground, and inertial effects in a physically accurate manner. The mechanical deformation of the robot is associated with local elastic (stretching and bending) energies at each discrete node. We formulate these discrete elastic energies and, subsequently, the discrete equations of motion representing the balance of forces using principles from classical elastic rod theories29,38. Coulomb frictional contact with uneven surface is integrated into the formulation using the modified mass method33, such that a group of constrained equations of motion can be implicitly updated through a second order, symplectic Newmark-beta time integration scheme. As this integration scheme is momentum preserving, it does not suffer from artificial energy loss—a well-known attribute of first order Euler integration used in prior works with discrete rod simulations29—and can capture the essential inertial effects during the dynamic simulation of soft robots. The elastic/inelastic collision between the soft robot and rigid ground can be captured by the rate-dependent viscoelastic behavior of the soft material, i.e., the damping coefficient in Rayleigh’s damping matrix is used to precisely control the recovery factor during collision and rebound39. Finally, the experimentally measured data of a single actuator during one actuating–cooling cycle is fed into our numerical framework for the investigation of soft robotic dynamics. The result is a robust simulation tool that can run faster than real-time on a single thread of a desktop processor. The reliability of this simulation tool for making quantitative predictions is systematically examined using three test cases. First, we demonstrate that three empirically observed motion patterns of a deformable rolling ribbon40 on a declined surface can be captured by our simulator. Next, we build two types of soft robots made of SMA-based limb: a star-shaped rolling robot composed of seven radially oriented limbs and a jumper robot with a single limb. The SMA-based robots were selected because of the ability to achieve rapid dynamic motions in which both material deformation and inertia have a governing role41,42. In order to examine the influence of friction and ground topology, locomotion experiments were performed on flat, inclined/declined, and wavy/undulating surfaces. In all cases, we found reasonable quantitative agreement between experiments and simulations.

Results

Numerical simulation

In this section, we review the numerical framework that incorporates elasticity, contact with uneven surface, friction, and inelastic collision for a comprehensive soft robot simulator. As the motion of the robot remains in 2D, we do not include a twisting energy of the rod, although this can be readily integrated into our framework29. Starting from the discrete representation of elastic energies, we formulate equations of motion at each node and update the configuration of the structure (i.e., position of the nodes) in time. The rod segment between two consecutive nodes is an edge that can stretch as the robot deforms—analogous to a linear spring. The turning angle ϕi (see Fig. 1b) at node xi between two consecutive edges can change—similar to a torsional spring. The elastic energy from the strains in the robot can be represented by the linear sum of two components: stretching energy of each edge and bending energy associated with variation in the turning angle at the nodes. The discrete stretching energy at the edge connecting xi and xi+1 is \(E^s_{i}= \frac{1}{2} EA \epsilon ^2\), where EA is the stretching stiffness (calculated as the product of the material elastic modulus E and actuator cross-sectional area A) and εi = |xi+1xi|/Δl − 1 is the axial stretch. Associated with each turning angle ϕi is the discrete bending energy \(E_i^b = \frac{1}{2}EI\left( {\kappa _i - \bar \kappa _i} \right)^2\Delta l\), where EI is the bending stiffness, κi = 2 tan(ϕi/2)/Δl is the curvature [Fig. 1b], and \(\bar \kappa _i\) is the natural curvature (i.e., curvature evaluated in undeformed configuration). In the special case of a joint node where three edges meet, the bending energy is comprised of two components: one corresponding to the turning angle between the first and second edges and the second one arises from the turning angle between the second and third edges. The total stretching energy of the robot can be obtained simply by summing over all the edges, i.e., \(E^s = {\sum}_i E_i^s\), and, similarly, the total bending energy is \(E^b = {\sum}_i E_i^b\). In both experiments and simulations, we observe that the structure is nearly inextensible and the prominent mode of deformation is bending. We evaluated the bending stiffness by quantifying the shape of an actuator under vertical load, as shown in Supplementary Fig. 1 and Supplementary Methods.

Fig. 1: Discrete kinematic representation of a soft robot.
figure 1

a Geometric discretization of soft rolling robot. b The bending curvature at ith node is κi = 1/Ri = 2tan(ϕi/2)/Δl30. c Coulomb law for frictional contact45.

The elastic stretching (and bending) forces acting on a node xi can be obtained from the gradient of the energies, i.e.,\(- \left[ {\frac{{\partial E^s}}{{\partial x_i}},\frac{{\partial E^s}}{{\partial y_i}}} \right]^T\) (and \(- \left[ {\frac{{\partial E^b}}{{\partial x_i}},\frac{{\partial E^b}}{{\partial y_i}}} \right]^T\)). An implicit treatment of the elastic forces requires calculation of the 2 N × 2 N Hessian matrix of the elastic energies. Other than the seven joint nodes that are connected with three other nodes, a node xi is only coupled with the adjacent nodes xi−1 and xi+1 in the discrete energy formulation. This results in a banded Hessian matrix with 6 × 6 blocks of non-zero entries along the diagonal. The only off-diagonal non-zero entries correspond to the seven joint nodes. The analytical expressions for the gradient and Hessian of the elastic energies can be found in refs. 29,30.

Besides the internal elastic forces, Fs and Fb, the structure would also experience internal damping forces during deformation. We use the Rayleigh damping matrix to formulate the viscoelastic behavior of soft robots, such that the damping force vector is given by39

$${\mathbf{F}}^{\mathrm{d}} = - \left( {\alpha {\Bbb M} + \beta {\Bbb K}} \right){\mathbf{v}},$$
(1)

where \(\alpha ,\beta \in {\Bbb R}^ +\) are damping coefficients, \({\Bbb K} = - \frac{\partial }{{\partial {\mathbf{q}}}}\left( {{\mathbf{F}}^{\mathrm{s}} + {\mathbf{F}}^{\mathrm{b}}} \right)\) is the tangent stiffness matrix, and v is the velocity vector (time derivative of DOF (degree of freedom)). Also, the external gravity forces are denoted by Fg, as well as the external contact forces, Fr. The gradients of these force vectors can be analytically formulated in a manner similar to those of the elastic forces. The sparse nature of the Jacobian matrix is critical for computational efficiency during the solution of the equations of motion, described next.

The DOF vector can be updated from current time step (tk) to the next (tk+1 = tk + h), qk+1 = qk + Δqk+1, by a second order, implicit Newmark-beta time integration39,

$${{\mathrm{\Delta }}{\mathbf{q}}^{k + 1} - h{\mathbf{v}}^k} = \frac{{h^2}}{4}{\Bbb M}^{ - 1}\left( {{\mathbf{F}}^{k + 1} + {\mathbf{F}}^k} \right) \\ {{\mathrm{\Delta }}{\mathbf{q}}^{k + 1}} = \frac{h}{2}\left( {{\mathbf{v}}^{k + 1} + {\mathbf{v}}^k} \right) \\ {{\mathrm{\Delta }}{\mathbf{v}}^{k + 1}} = {\mathbf{v}}^{k + 1} - {\mathbf{v}}^k,$$
(2)

where the velocity vector (time derivative of DOF) is v, superscript k + 1 (and k) denotes evaluation of the quantity at time tk+1 (and tk), \({\Bbb M}\) is the diagonal mass matrix, h is the time step size, and F = (Fs + Fb + Fg + Fd + Fr) is the sum of elastic, damping, and external forces defined before. In the absence of dissipative forces and external contact forces, this method is symplectic and momentum preserving39,43,44—a critical feature for simulation of robots where inertial effects are significant.

As soft robots are often intended for locomotion on unstructured terrain, we require a method to account for contact and friction with the ground. Importantly, the surface normal can vary with the horizontal x axis. We model the nonpenetration constraints and frictional contact forces that resist sliding along interfaces based on Coulomb’s law. At each time step, we apply continuous collision detection to the predicted trajectory to gather contact constraints into a contact set \({\Bbb C}\), shown in Fig. 1c. For these calculations, the velocity \({\mathbf{u}} = [ {{\mathbf{v}}_{2j - 1},{\mathbf{v}}_{2j}} ]^T\) (subscript denotes element number in a vector), and the reaction force \({\mathbf{R}} = [ {{\mathbf{F}}_{2j - 1}^r,{\mathbf{F}}_{2j}^r} ]^T\), at the jth node (the contact point) satisfy the condition

$${\Bbb C}\left( {{\mathbf{u}},{\mathbf{R}}} \right) \Leftrightarrow \left\{ {\begin{array}{*{20}{l}} {{\mathbf{R}} = 0\,{\mathrm{and}}\,u^ \bot > 0\left( {{\mathrm{take}}\,\, {\mathrm{off}}} \right)} \hfill \\ {R_{\parallel} \, < \, \mu R^ \bot \,{\mathrm{and}}\,{\mathbf{u}} = 0\left( {{\mathrm{sticking}}} \right)} \hfill \\ {R _{\parallel}= \mu R^ \bot \,{\mathrm{and}}\,u^ \bot = 0\left( {{\mathrm{sliding}}} \right),} \hfill \end{array}} \right.$$
(3)

where μ = 0.8 is the friction coefficient characterized by experiments (Supplementary Methods), and the superscript (and ) denotes the component along (and perpendicular to) the ground. At the normal and tangential subspaces of a contact node xj, we either know its perpendicular velocity u (u for tangential component) or the perpendicular reaction force R (R for tangential component), so the Coulombic frictional contact law can be treated as a Second Order Linear Complementary Problem (SOLCP)45. We employ the modified mass method33 to solve this SOLCP such that a contact node xj can be free (degrees of freedom is 2, taking off), constrained along the normal to the ground p (degrees of freedom is 1, sliding), or fully constrained (degrees of freedom is 0, sticking). The two modified equations of motion for the jth node (j = 1, …, N) are

$$\left[ {\begin{array}{*{20}{l}} {{\Bbb F}_{2j - 1}} \hfill \\ {{\Bbb F}_{2j}} \hfill \end{array}} \right] \equiv \left[ {\begin{array}{*{20}{l}} {{\mathrm{\Delta }}{\mathbf{v}}_{2j - 1}^{k + 1}} \hfill \\ {{\mathrm{\Delta }}{\mathbf{v}}_{2j}^{k + 1}} \hfill \end{array}} \right] - \frac{h}{{2M_j}}{\mathbf{S}}^{k + 1}\left( {\left[ {\begin{array}{*{20}{l}} {{\mathbf{F}}_{2j - 1}^{k + 1}} \hfill \\ {{\mathbf{F}}_{2j}^{k + 1}} \hfill \end{array}} \right] + \left[ {\begin{array}{*{20}{l}} {{\mathbf{F}}_{2j - 1}^k} \hfill \\ {{\mathbf{F}}_{2j}^k} \hfill \end{array}} \right]} \right) - {\mathrm{\Delta }}{\mathbf{z}}^{k + 1} = 0,$$
(4)

where \({\Bbb F}_{2j - 1}\) is the left hand side of the (2j−1)-th equation of motion, Mj is the mass associated with jth node, Δzk+1 is the change in velocity we want to enforce along the constrained direction(s), and the modified mass matrix is

$${\mathbf{S}}^{k + 1} = \left\{ {\begin{array}{*{20}{l}} {\Bbb I} \hfill & {{\mathrm{if}}\,{\mathrm{ndof}} = 2,} \hfill \\ {\left( {{\Bbb I} - {\mathbf{pp}}^T} \right)} \hfill & {{\mathrm{if}}\,{\mathrm{ndof}} = 1,} \hfill \\ 0 \hfill & {{\mathrm{if}}\,{\mathrm{ndof}} = 0,} \hfill \end{array}} \right.$$
(5)

where ndof is the number of free DOF at jth node and \({\Bbb I}\) is the 2 × 2 identity matrix. Note that when a node is free, Δzk+1 = 0, and Equation (4) reduces to Equation (2). If the node is fully constrained (Sk+1 = 0), Equation (4) reduces to \({\mathrm{\Delta }}{\mathbf{v}}_j^{k + 1} = {\mathrm{\Delta }}{\mathbf{z}}^{k + 1}\) and the change in velocity (as well as the position) is enforced to take the value prescribed by Δzk+1.

The solution to the 2 N equations of motion in Equation 4 starts with an initial guess (Δvk+1)(0) and subsequent Newtons iterations to improve the solution until a desired tolerance is achieved:

$$\left( {{\mathrm{\Delta }}{\mathbf{v}}^{k + 1}} \right)^{(n + 1)} = \left( {{\mathrm{\Delta }}{\mathbf{v}}^{k + 1}} \right)^{(n)} \,-\, {\Bbb J}^{(n)}\backslash {\Bbb F}^{(n)},$$
(6)

where \({\Bbb J}^{(n)} = \frac{{\partial {\Bbb F}}}{{\partial \left( {{\mathrm{\Delta }}{\mathbf{v}}^{k + 1}} \right)}}\) is the Jacobian matrix evaluated at (Δvk+1)(n). The non-trivial terms in the evaluation of this Jacobian are the Hessian matrices of the elastic energies. Owing to the presence of the ground, we need to check whether the new solutions, e.g., qk+1, vk+1, and (Fr)k+1 (computed from force balance), satisfy the following conditions:

  • A node xj cannot fall below the ground.

  • The normal component of reaction force R exerted by the ground on a node xj must be along the outward normal to the surface, e.g., R > 0.

  • The reaction force R should be in the frictional cone zone Kμ (see Fig. 1c); if the reaction force is on the boundary of the cone, this node is allowed to slide along the tangential direction of surface opposite to reaction force, uR < 0.

  • If the tangential velocity u at a sliding node xj changes its direction, (u)k (u)k+1 < 0, this node should be fully constrained.

If one of the above rules is broken, we rewind the simulation, add (or delete) constraints at the contact pair, and re-solve Equation (4) with a new guess.

When an elastic body drops onto a rigid surface, the motion normal to the surface of the contact nodes are constrained, the normal velocities are set to zero, and the tangential velocities are reduced based on impulse theory, Δu = μΔu. If the structure is modeled as an ideal mass-spring system without viscoelasticity, the whole structure will rebound to a certain height and the recovery factor—the ratio of rebound to initial height—is not deterministic. This arises because the structure’s kinetic energy will transfer into elastic potential energy during compression and then convert back to kinetic energy during the rebound phase39. We must account for the rate-dependent viscoelasticity of contact for predictive simulation, where the energy loss of the collision–compression–rebound process results in a deterministic rebound height. In Supplementary Fig. 3 and Supplementary Methods, we show that the decrease in rebound height of the rolling robot can be determined by the parameter β in damping force \({\mathbf{F}}^{\mathrm{d}} = - \left( {\alpha {\Bbb M} + \beta {\Bbb K}} \right){\mathbf{v}}\), such that the recovery factor of collision is also related to β. Physically, β represents a damping that opposes elastic deformation, without penalizing rigid body motion. Opposition to rigid body motion and momentum dissipation can be accounted by the viscosity α.

The overall numerical framework thus accounts for inertia, friction, and collision and shows good convergence with both time and space discretization, as outlined in Supplementary Figs. 4, 5, and Supplementary Methods.

Rolling ribbon

Before examining soft robot locomotion, we first investigate the simpler motion of a circular ribbon on a declined surface in order to test the accuracy of numerical implementation of friction and contact. In the numerical study here, the arc length we chose for the circular ribbon is L0 = 0.3 m, resulting in R = 0.3/2π ≈ 0.048 m (details in Supplementary Fig. 7 and Supplementary Methods). Because of gravity, this close-loop elastic structure will first undergo transient dynamics and then, as shown in Fig. 2a, move with a steady state configuration. The final shape is determined by the ratio Γg = Lg/R of the gravito-bending length scale Lg = (EI/ρgA)1/3 to the ribbon undeformed radius R40. In Fig. 2c, we plot the static configurations of rolling ribbon at different values of Γg. At small values of Γg, the ribbon shows relatively large deformation with large region of contact. As Γg increases, the deformed shape becomes closer to its original undeformed shape and the contact length decreases to reach a single point at Γg = ∞.

Fig. 2: Motion patterns of elastic ribbons.
figure 2

a Three different patterns in rolling ribbons: pure sliding (μ/tan θ = 0), combination of sliding and rotating (0 < μ/tanθ < 1); and pure rotating (μ/tan θ ≥ 1). b The ratio between the route of ribbon boundary point and ribbon centroid, δ = sb/sc, as a function of normalized frictional coefficient μ/tan θ, for different values of normalized ribbon curvature, Γg. c Different typologies of rolling ribbons with different Γg.

Now we turn to the motion of a rolling ribbon. Three different motion patterns exist on a declined surface: pure sliding, combined sliding and rotation, and pure rotation, depending on a dimensionless number, μ/tan θ, where μ is the frictional coefficient and θ is the decline angle. In Fig. 2b, we show the ratio between the distance traveled by a point on the ribbon (red mark in Fig. 2a) and the ribbon centroid, δ, as a function of normalized friction coefficient, μ/tan θ, at different values of Γg. When the normalized frictional coefficient μ/tan θ = 0, the ribbon will slide along the tangential direction of the surface without any rotation, and the path of boundary point is the same as the path of center, δ = 1. If 0 < μ/tan θ < 1, the motion of the ribbon is a combination of sliding and rotation, and the larger the friction, the higher the δ. The ribbon undergoes pure rotation at μ/tan θ ≥ 1 when δ remains fixed at a constant value depending on Γg. At the limiting case of a rigid ribbon, the motion is purely rotational and any point on the ribbon traces a cycloid path, corresponding to δ = 8/2π. We plot the boundary node position as a function of time for all three cases in the Supplementary Fig. 6 to better show their differences. This finding establishes that the simulation can systematically capture elasticity, friction, and their interplay.

Rolling robot

The star-shaped, rolling robot in Fig. 1a is comprised of seven compliant actuators/limbs that are arranged radially. Each limb has a curved part with length lc = 2.2 cm and a straight part with length ls = 0.8 cm. The natural curvature of the curved part is \(\bar \kappa _0 \equiv 1/R_c = 120\) m−1. The material density of the rolling robot is ρ = 1912 kg m−3. The mass center is located at (xc,yc). The height, H ≈ 5 cm, is used as the body length. We then discretize the structure into N nodes, shown schematically in Fig. 1a. This corresponds to a DOF vector, q = [x0, y0, ..., xN−1, yN−1]T, of size 2 N, representing the vertical and horizontal coordinates of each node. Here, the superscript T denotes transposition. The length of each edge—the segment between two consecutive nodes—in this study is Δl ≈ 2.5 mm, resulting in N = 84 nodes (convergence study in Supplementary Fig. 4).

Actuation is incorporated into the simulation by varying natural curvature and bending stiffness with time. This variation is measured through characterization of a single SMA-powered actuator, as described next. The electrically activated SMA wire enables rapid transition between a soft curled unactuated state and a stiff straight-like actuated state41,42. The relative natural curvature \(\bar \kappa /\bar \kappa _0\) and Young’s modulus E/E0 are temperature-dependent, and can change as a function of time during the actuating–cooling process. As shown in Fig. 3, when SMA is actuated for 0.25 s, its natural curvature and Young’s modulus increase linearly in a short time period, t0, followed by a logistic decay until reaching the unactuated state. Notice that the plot here is from experimental fitting, see Supplementary Fig. 2 and Supplementary Methods for details. We use a piece-wise function to describe the natural curvature of SMA actuators:

$$\bar \kappa (t) = \left\{ {\begin{array}{*{20}{l}} {\frac{{(n - 1)t}}{{t_0}}\bar \kappa _0 + \bar \kappa _0 \; {\mathrm{when}} \; t \, < \, t_0} \hfill \\ {\frac{{(1 - n)}}{{1 + e^{ - \tau (t - \bar t)}}}\bar \kappa _0 + n\bar \kappa _0 \; {\mathrm{when}} \; t \, > \, t_0,} \hfill \end{array}} \right.$$
(7)

where \(n = \bar \kappa _{\mathrm{min}}/\bar \kappa _0\) is the ratio between the minimum curvature (at t = t0) and the initial curvature (at t = 0), and \(\tau ,\bar t,t_0\) are numerical parameters obtained from experimental fitting. The change of Young’s modulus of SMA follows a similar piece-wise function. Note that the parameter t0 is not necessarily equal to the actuation time of 0.25 s. As a result, the curvature slightly increases (and Youngs modulus decreases) even when the actuator is being heated (at t0 < t < 0.25 s). The primary reason behind behavior is that the fitting function is constrained to be smooth and monotonic (i.e., either increase, decrease, or remain constant). Although we could separate the fitting into more than two piece-wise functions involving more fitting parameters, this will lead to added complexity with little improvement in fitting accuracy. With these fitting parameters, we can achieve excellent match between experimental measurements and numerical simulations performed on a single actuator (details on the fitting can be found in Supplementary Fig. 2 and Supplementary Methods).

Fig. 3: Actuator characterization.
figure 3

Relative natural curvature \(\bar \kappa /\bar \kappa _0\) and Young’s modulus E/E0 as a function of time during actuating–cooling process of a single SMA actuator.

The simplest scenario is presented in Fig. 4 (also Supplementary Movie 1), where the surface normal is anti-parallel to gravity. Figure 5d plots the x coordinate of the centroid of the robot, xc, with time over four actuation cycles. Note that the different symbols correspond to repeated experimental runs. In our numbering system for the limbs (see Fig. 4), Limb 5 is in contact with the ground at t = 0. Upon actuation of Limb 4, the robot rolls to the right and the contact limb changes from 5 to 6. In the next cycle, Limb 5 (the limb to the left of the contact limb) is actuated. We choose the actuation period Δt = 3 s (0.25 s for actuation and 2.75 s for cooling); the single SMA actuator can totally reshape to its original configuration within 3 s.

Fig. 4: Snapshots of rolling robot.
figure 4

ae Snapshots of rolling robot from simulations and experiments between t = 0.0 s and t = 2.0 s. Limb #4 is actuated for a rolling motion. The width (out-of-plane dimension in this figure) is 18 mm.

Fig. 5: Snapshots of rolling robot in different scenarios.
figure 5

a Inclined surface (θ = +3.0°), b Crest of sinusoidal surface, and c Trough of sinusoidal surface. Normalized x coordinate of the robot centroid with time from experiments (symbols) and simulations (solid lines): d planar surface, θ = 0.0°; e inclined surface, θ = +3.0°; f declined surface, θ = −3.0°; g inclined surface, θ = +6.0°; h sinusoidal surface, crest; and i sinusoidal surface, trough.

Next, we consider planar surfaces that are inclined at an angle θ with respect to the horizontal plane (also see Supplementary Movie 1). Figure 5a compares the simulation and experimental results for θ = +3.0°, and Fig. 5e–g plots the location of the robot centroid at three different values of θ. We find good agreement between experiments and simulation in all the cases. In particular, we observe that when the angle of inclination increases from θ = −3.0° to θ = +3.0°, the distance traveled by the robot decreases in both experiments and simulations. The gait at θ = {−3.0°, +3.0°} is similar to the horizontal planar case described above. Beyond a certain threshold for θ, the robot can no longer move forward owing to the increased role of gravity, e.g., the robot fails to roll up the incline when at θ = +6.0°. The simulation also accurately captures this observation.

We now move to the case of an uneven surface with an outward normal that varies with location. As a representative example shown schematically in Fig. 5b, c, we consider a 3D printed surface that can be described by f(x) = A sin(2πx/λ) with amplitude A = 6.5 mm and period λ = 200 mm. We consider two experimental trials: first, the robot is initially located at the crest of the surface in Fig. 5b; and second, the robot is on the trough in Fig. 5c. Figure 5h, i shows the location of the robot centroid with time from both experiments and simulations. In the crest case, the robot rolls once at the first cycle. However, at the second cycle, the robot rolls multiple times, undergoes oscillatory motion, and settles stay at the trough. On the other hand, if the locomotion starts with the robot at the trough, the robot successfully rolls once in the first two cycles, but fails to roll in the third cycle. All of these observations are captured in both experiments and simulations. However, we should also note that our simulator always under-predicts the motion of the rolling robot. We attribute this to the finite thickness of the actuator elements, which is not accounted for in the model.

Our novel numerical tool can achieve real-time simulation of the soft rolling robot. In Fig. 6, with a fixed number of vertices, N = 84, the computation time linearly scales with time step size h for all the scenarios. The simulations ran on a single thread of AMD Ryzen 1950X CPU @ 3.4 GHz. Also, our simulator can run faster than real time when the time step size h 2.5 ms. Numerical issues associated with a large step size appear at h 10 ms, in which case the computation time is infinite because we cannot get convergence.

Fig. 6: Computational time.
figure 6

The ratio between computational time and wall-clock time as a function of time step size h in different scenarios with N = 84.

Jumper

Finally, we emphasize the generality of the simulation by examining another soft robot with a different geometry. The SMA-based jumper shown in Fig. 7a is an asymmetric circle with radius \(\bar R_0 \approx 5\) mm. Detailed geometric property of Jumper robot can be found in the Supplementary Fig. 7 and Supplementary Methods. When the material is actuated, the whole structure can rise and move forward because of the reaction forces from the ground. To model the tension from the electrical wire connected at the leading edge of the jumper, we apply a force at the first node; the magnitude and duration of the force are obtained from fitting to experimental data (Supplementary Fig. 7). In Fig. 7a, we show snapshots of the jumper at t = {0.000, 0.125, 0.250}s from both experiments and simulations and see qualitative agreement. For quantitative comparison, Fig. 7b, c present experimental and simulation data on the normalized position of the first node on the robot as a function of time. The two sets of results—experiments and simulations—appear to be in strong quantitative agreement, providing further evidence for the physical accuracy of our DDG-based formulation. We should also note that, at time t = 1.5 s, the x position predicted by numerical simulation has a sudden drop, which is not reflected in the experimental data. The mismatch between numerical simulation and experimental observation is owing to the discontinuity in Coulombs formulation, i.e., the jumper robot would move only if the external reaction force is out of the frictional cone.

Fig. 7: Dynamics of the jumper robot.
figure 7

a Snapshots of the jumper robot from experiments and simulations at different time steps (Supplementary Movie 1). b Normalized x position of the first node (marked in a) in jumper robot as a function of time from experiments (symbols) and simulations (solid lines). c Normalized y position of the first node (marked in a) in jumper robot as a function of time from experiments (symbols) and simulations (solid lines).

Discussion

We have introduced a numerical framework based on DER for examining the locomotion of limbed soft robots that is adapted from methods popular in the computer graphics community. To avoid the artificial energy dissipation during the time marching scheme, we replaced the first order, implicit Euler integration by a second order, symplectic Newmark-beta method, for momentum preservation during the dynamic simulation. For the frictional contact between the rigid wall and the soft material, Coulomb’s law was implemented through a modified mass-based method, and this fully implicit framework allows a larger time step for convergence and numerical stability, which is also a prerequisite for real-time simulation. Similarly, the elastic/inelastic collision between the rigid wall and soft robots, related to the rate-dependent viscoelastic behavior of soft material, can be precisely described by the Rayleigh damping matrix. The mechanical response of SMA during actuating–cooling process was first experimentally measured through a single actuator, then fed to the numerical framework to simulate the dynamics of the soft robots. Overall, the simulation can seamless integrate elasticity, actuation, friction, contact, and elastic/inelastic collision to achieve quantitative prediction of the motion of fast moving highly deformable soft robots. The computational efficiency makes it ideally suited for algorithms that iterate over a wide variety of parameters in order to select a robot design or locomotion strategy.

Overall, our results show good quantitative agreement between the simulations and experiments, suggesting that our numerical approach represents a promising step toward the ultimate goal of a computational framework for soft robotics engineering. However, further progress depends on additional experimental validation for a wider range of soft robot designs, locomotion gaits, and environmental conditions. The simulation introduced here also needs some prerequisite experimentally measured data, e.g., material properties of soft materials and their mechanical performance in response to external actuation. It would be meaningful to develop a more general constitutive relations that combines mechanics, electricity, heat, and magnetic field, for the direct simulation of soft robotic dynamics in response to external actuation. Moving forward, it would also be interesting to explore how DDG-based simulation tools that incorporate the formulation presented here can be used to generate optimal locomotion gaits that minimize cost of transport or maximize range for a prescribed energy input.

Methods

Fabrication of shape memory alloy actuators

The fabrication process is similar to the one presented in refs. 42,46. We start the fabrication process by laser-cutting two pieces of thermally conductive tape (H48-2, T-Global) with dimensions of 40 × 18 × 0.5 mm (55 × 18 × 0.5 mm for the jumping robot) and 80 × 55 × 0.5 mm by a CO2 laser-cutting system (30 W VLS 3.50; Universal Laser Systems). Then we apply a layer of elastomer (Ecoflex 00-30, Smooth-On) that is prepared by mixing prepolymer at a 1:1 ratio by mass in a centrifugal mixer (AR-100, THINKY) with a thickness of 0.1 mm on top of the small thermally conductive tape and half-cure it in the oven under 50 °C for 7 minutes. Next, we place the pre-bent Ω shape SMA wire (0.015 inch diameter, 34 × 11 mm; Dynalloy) on top of the elastomer and apply another layer of elastomer with a thickness of 0.5 mm to encapsulate the SMA wire. Meanwhile, we stretch the larger thermally conductive tape (80 × 55 × 0.5 mm) to 150% of its original length and apply a 0.1 mm thick layer of elastomer on top of it. We place both thermally conductive tape in the oven under 50 °C for 7 minutes to half-cure them. After that, we attach the smaller thermally conductive to the middle of the stretched larger thermally conductive tape, clamp them with binder clips and place the bonded structure back to the oven for 10 minutes to fully cure it. Finally, we cut out the actuator along with the outline of the smaller thermally conductive tape.

Experimental setup

All robots and actuators in the experiment and characterization are powered by a desktop power supply (DIGI360, Electro Industries) under a current of 6 A. Each actuator is individually connected to an n-MOSFET (IRL7833, Nfineon for the rolling robot experiment and AO3416, Alpha & Omega Semiconductor for the rest) and the actuation and cooling time are controlled by a single-board microcontroller (Arduino UNO SMD R3, Arduino). The rolling robot and jumper experiment are performed on top of a red linatex sheet (MCM linatex 1.5 mm class 2, Linatex Corp of America).