Skip to main content
Advertisement
Browse Subject Areas
?

Click through the PLOS taxonomy to find articles in your field.

For more information about PLOS Subject Areas, click here.

  • Loading metrics

Review on generic methods for mechanical modeling, simulation and control of soft robots

Abstract

In this review paper, we are interested in the models and algorithms that allow generic simulation and control of a soft robot. First, we start with a quick overview of modeling approaches for soft robots and available methods for calculating the mechanical compliance, and in particular numerical methods, like real-time Finite Element Method (FEM). We also show how these models can be updated based on sensor data. Then, we are interested in the problem of inverse kinematics, under constraints, with generic solutions without assumption on the robot shape, the type, the placement or the redundancy of the actuators, the material behavior… We are also interested by the use of these models and algorithms in case of contact with the environment. Moreover, we refer to dynamic control algorithms based on mechanical models, allowing for robust control of the positioning of the robot. For each of these aspects, this paper gives a quick overview of the existing methods and a focus on the use of FEM. Finally, we discuss the implementation and our contribution in the field for an open soft robotics research.

1 Introduction

Providing modeling and control methods for soft robots has been the topic of many recent works. This problem, which looked like a challenge a few years ago, now has technical solutions, even if they sometimes remain incomplete. The scope of this document is to provide a global view on model-based methods for soft robots. These robots being composed of deformable material, we are particularly interested in methods which account for a mechanical modeling of these deformations based on numerical schemes such as Finite Element Methods. We will recall that solutions exist to obtain real-time computation for these models. Then, we will examine how—once the bases of modeling posed—inverse modeling and control methods can be derived.

2 Soft robot modeling

Theoretically, soft robots have an infinite number of degrees of freedom. This makes them difficult to model analytically without strong assumptions. This section provides a quick review of modeling, from simplified analytical models to more generic, physics based, numerical models.

2.1 Analytical models

The main advantage of analytical models is that they are very fast to compute and can be derived easily for control law proofs. Their main limitation is their simplifying assumptions, which will be detailed in the following parts.

2.1.1 Pseudo Rigid Body Model.

Rod-like robots can be modeled using the Pseudo-Rigid Body Model. Using this method, continuous elongated robots, such as steerable catheters used in surgical robotics, are approximated by a n-link rigid manipulator with a torsional spring in each link. This model assumes there is only bending and no torsion in the robot [1, 2].

2.1.2 Constant Curvature Model.

The Constant Curvature Model is a simplifying approach to allow closed form kinematics and enable computing the Jacobian of a soft continuum robot. The main assumptions are that there is zero torsion—meaning that the deflection is always planar—and that the bending section always takes the shape of a circular arc—constant curvature [3].

The main advantage of this type of modeling is that it can be derived into Denavit-Hartenberg parameters, Frenet-Serret frames, an integral representation or exponential coordinates. This allows to use control laws adapted from rigid robotics.

Piecewise constant curvature models are used for robots shaped by continuously bending actuators or tendons, concentric tube robots, and steerable needles. Initially, they were the most used in the Soft Robotics literature [4]. Examples of applications include a cable-driven octopus arm [5] and a pneumatic soft gripper [6]. Though this model has been extended to handle dynamics [7] it still has major shortcomings. Especially this model is not valid if the robot is subject to external forces which are out of its plane, such as gravity [8].

2.2 Numerical models

Numerical models discretize the geometry into a mesh and use a numerical solver, which always makes approximations. Numerical models are, in theory, less precise than analytical models but in the case of continuum mechanics for deformable solids, it’s often the opposite. As there is no analytical solution for most of the cases, analytical models are only used in continuum mechanics for very simplified shapes, constitutive laws and boundary conditions, far from the deformations obtained on soft robots.

2.2.1 Cosserat rod theory.

To address some of the shortcomings of the models presented before, physics based models of deformation were proposed. Cosserat geometrically exact models for instance, based on Cosserat rod theory, were developed to model these same elongated robots with a much improved accuracy [9] and in a mathematical framework close to rigid robot models (local coordinates and integration of motions using the Lie group).

Using Cosserat models, deformable objects are represented as a space curve and a coordinate frame of director vectors is associated to each point. These models can handle kinematics and dynamics of objects undergoing large deformations such as threads in surgical simulations [10] and of various soft robots, ranging from an octopus arm [11] to underwater bio-inspired robots [12, 13]. The model is based on the deformation of a center line and sections perpendicular to this line are considered rigid. Therefore, one limitation is that not all deformations are taken into account. In addition, while the model simplifies the expression of strain forces, complex numerical approaches are needed to integrate the dynamics. But this approach makes possible to physically model the deformations, in particular by taking into account the constitutive law of the materials.

2.2.2 Finite element modeling.

As illustrated in previous parts, it is difficult to obtain an analytical mechanical model for soft robots and some models that keep an analytical description of the geometry, like Cosserat rods, are limited to specific shapes of robots. Moreover, most of these models, do not yet model contacts precisely.

The Finite Element Method (FEM) is a numerical method for solving Partial Differential Equations, which can be used to model soft robots [14]. This method can handle generic shapes and constitutive materials. It can also model contact interactions between the soft robot and other objects in the environment, soft or rigid [15]. This method is very well known and widely used in industry, in particular for simulating multiphysics. It is very appealing in the design process of complex systems (such as soft robots), with a easy loop between CAD and numerical tests. The Finite Element Method was shown to be the most realistic in simulating soft robots mechanics as it describes non-linearities better and can model interactions between different materials within the same robot [16, 17].

The main drawback of using this method is its computation cost. Various methods have been developed to model and simulate soft deformable objects in real time, for instance using GPU computation in the context of haptic rendering [18, 19]. Fast implementation of the Finite Element Method to model soft and deformable objects are abundant in the Computer Graphics community [20, 21] and in the Surgical Simulation community [18, 22, 23]. Examples of applying this method to soft robots include [14, 2431], and to haptic devices [19, 32]. FEM can also be leveraged to optimize the shape and mechanical properties of a soft robot or its actuation [3335].

Another promising method for speeding up the simulation is Model Order Reduction [36, 37]. Using Model Order Reduction, Thieffry has shown the simulation is fast enough to use it for dynamic control [30, 38, 39] (see also section 3.4). Finally, recent works in surgical simulation explore using machine learning to learn the deformations of soft organs and tissues [40, 41].

2.3 Online update of the models

Whatever the model used for the robot, an objective in robotics is to be able to update it according to the information retrieved from sensors placed on the robot. In rigid robotics, for example, a sensor is placed on the joints to measure their position and update the kinematic model. In soft robotics, the difficulty is that the system theoretically has an infinite number of degrees of freedom and it is therefore theoretically impossible to measure the complete state of the system.

However, in practice, analytical models described above and Cosserat-type models have a relatively small state, which for instance allows using visual servoing to update the model [42, 43] or more localized sensing like multi-magnet tracking [44]. Resistive, capacitive, inductive or optical sensors have been also developed more widely in soft robotics [45] and are usually coupled with analytical models to couple the physical measure to the deformation, like in [46] for capacitive sensing. However, it is often difficult to combine information from various types of sensors with these models.

FEM models allow multi-physics coupling and such a model can be used to integrate or merge multi-sensor information [47]. However, with these numerical models, the state of the robot is usually much larger and can not be fully sensed. In [26], a condensation of the FEM model is used to write a kinematic model of the soft-robot in a reduced space. The full model is then updated through visual servoing on a reduced number of feature points of the robot, allowing closed loop control (see also section 3.2.2). This approach is extended in [48] to capture deformations and deduce external loads applied on a soft structure. An other possible strategy for FEM is to use model-order reduction to obtain a good dynamic model with a reduced size. Then, it is shown in [39] that the information obtained from a magnetic tracking system can update a state-observer in a context of dynamic control (see also section 3.4).

Despite this work, which shows significant progress, the updating of soft robots models based on a sensor system remains a very open problem.

3 Soft robot control

3.1 Control methods using Forward Kinematics

3.1.1 Direct control.

In the case of direct control, forward kinematic models can be used to validate a robot’s design, as a proof of concept, to study the robot’s controllability, and to optimize the placement of sensors. Examples of direct control of soft robots include a pneumatic actuated snake-like robot [49] and a caterpillar inspired robot actuated by shape memory alloy actuators [50]. Both use periodic electrical wave signals inputted to the actuators, generating different gaits.

3.1.2 Learning based control.

As soft robots can be tricky to model, a tempting solution is to adopt a “model-free” approach and learn the control policy directly [51]. Several Reinforcement Learning algorithms have been used for continuum robot control (such as catheter navigation in medical robotics [52]) and soft robotics control. Applications include manipulation and navigation tasks. A recent survey of these applications to soft robotics can be found in [53]. A subset of these applications can be found in the following table.

3.2 Control methods using Inverse Kinematics and Inverse Dynamics

3.2.1 Analytical methods.

Analytical solutions require a low computational cost and often reliably offer a global solution. In the case of rigid robotics, robots are often designed to guarantee there exists a solution to the inverse kinematics problem. For soft robots, obtaining such guarantees on an analytical inverse kinematics model requires strong assumptions on the robot’s geometry. As an example, for rod-like robots, the Constant Curvature Model or the Piecewise Constant Curvature Model provide analytical Inverse Kinematics Solutions [4]. Application examples include steerable concentric tubes [62] and a multi section continuum trunk [63].

3.2.2 Jacobian based.

In the context of rigid robotics, the Jacobian matrix is defined as the differential relationship between actuator variables and end-effector position. One popular way to solve the inverse kinematics problem is to invert this matrix. With some specific assumptions, this Jacobian matrix can be extended to soft robotics.

In the example of a conical manipulator driven by cables [43], the Jacobian matrix can be defined as the relationship between the 2D position of the robot’s tip and the cable tensions. Authors then propose a control method based on the Jacobian inverse to solve the Inverse Kinematics problem.

Assuming that the robot’s workspace has no singular configuration, that the actuators are not constrained and that they can build a FEM-based simulation which is an observer of the robot, Zhang and coauthors define a FEM-based Jacobian matrix and design a closed-loop controller for a parallel soft robot using Jacobian pseudo-inverse [26, 64].

To control a deformable needle inside soft tissues, the Finite Element method is also used to compute a Jacobian matrix of the coupled system and the Jacobian pseudo-inverse [65, 66].

3.2.3 Optimization based methods.

3.2.3.1 Problem formulation. The Inverse Kinematics problem can be formulated as a constrained optimization problem. This formulation can handle a large number of degrees of freedom, and singularities can be handled by adding constraints. This framework also handles actuator constraints and many design variables can be included. This formulation is widely used in rigid robotics and computer graphics [67]. Numerous ways of solving such constrained optimization problems have been developed.

3.2.3.2 Non linear programming. A constrained optimization problem is non linear if either the objective function or at least one constraint is a non linear function. In the computer graphics community, constrained optimization has been used to compute muscle actuation to animate a face [68], or optimize actuator placement and the material configuration of deformable objects [20] and plush toys [21], as well as the actuation to obtain given deformations.

3.2.3.3 Quadratic programming. If the objective function has a quadratic form and the constraints are linear, then the constrained optimization problem is a Quadratic Program.

In the Computer Graphics community, such a formulation has been used for instance to model and animate tendons and muscles in human hands. Given the motion of the bones, they use Quadratic Programming to compute the corresponding muscle activation and the force transmission via the tendons [69].

In the context of surgical simulation, a Quadratic Program is used to register the movements and deformations of deformable glands due to weight loss during radiotherapy [23].

Finally, Quadratic Programming is applied to the control of soft robots using cable and pneumatic actuation in [70] and the results are validated using simulated and real robots. The same control algorithms have also been used to create haptic interfaces [32] and have been extended to use hydraulic actuators [71]. Finally, using two simulations running in parallel, a closed loop controller can be designed. The first simulation is computing the Inverse Kinematics and is used to calculate the actuation. The second simulation, also based on a quadratic program, uses the information of sensors, computes the Forward Kinematics and is used as a state estimator [27].

3.2.4 Learning based methods.

Recently, Machine Learning techniques have shown great success in regression problems, essentially learning a mapping between input features and output features. It is possible to create a dataset of robot configurations and postures. If one has access to accurate simulations, this process can be sped up by running several simulations in parallel to generate the data. A Machine Learning algorithm is then trained to learn the Inverse Kinematics of the robot, meaning the mapping between the actuator variables and the robot pose. The main advantage of these methods is that they are very fast to provide a solution to the IK problem, and thus enable real time control. This method has been extensively studied for computer graphics [67] and rigid robotics [72].

3.2.4.1 Feed forward neural network. Several works have used feed-forward neural networks to learn the mapping between the end-effector pose and the actuator variables. This method has been applied to controlling a soft robot based on Inverse Dynamics [73]. It has also been applied to the control of a soft arm [74, 75] and soft manipulators [76, 77].

3.2.4.2 Gaussian Process Regression. Another way to learn the IK or ID mapping is to rely on statistical methods such as Gaussian Process Regression. The computer graphics community have used these methods to generate natural looking poses of humanoid figures [78, 79]. Gaussian Process Regression has also been applied to rigid robotics [72] and most recently to soft robots to learn the modeling error [80] or the Inverse Kinematics used for control [81].

3.3 Inverse Kinematics with contacts handling

One of the main advantages of soft robots over rigid ones is their intrinsic safety when interacting with the environment. Thus most use cases of deformable robots involve contacts between the robot and its surroundings. Control strategies should therefore account for contacts.

3.3.1 Jacobian based.

A model-less approach can be used for controlling a continuum manipulator’s end effector position [82]. The robot’s Jacobian is first estimated offline by moving each actuator in increments and observing the resulting end effector displacement. The Jacobian is then updated online using measurements of actuators and end effector positions and solving a constrained optimization problem. This control algorithm can handle environments with unknown obstacles.This work was extended to also handle force control [83].

3.3.2 Optimization based.

Optimizing trajectories of rigid systems with a large number of links and actuators can be done using Quadratic Programming. One of the key aspects is including the contacts in a way that doesn’t render the search space discontinuous or too local minima prone. [84] proposes to include the contact forces as decision variables in the optimization and use a complementarity formulation. [85] models contacts as continuous variables. Using these strategies they are able to generate complex motions of several simulated rigid link mechanisms.

In Computer Graphics, a common problem is that of moving a deformable object in a realistic manner. Automating part of this animation process requires modeling the physics of the objects and the contacts with the environment. Several works use penalty-based contact models and solve a Quadratic Program to optimize the shape of the deformable characters and generate plausible motions [86, 87].

In the case of soft robots, external contacts will create deformations that will potentially modify the robot kinematic relationship between inputs and outputs. There is therefore a total coupling of the contacts with the inverse model of the robot. In this case, Signorini’s law can be used to model contacts and a Quadratic Program with Complementarity Constraints can be built. This method has been demonstrated on several robots, both simulated and real, for navigation, locomotion and manipulation tasks. This framework also computes the IK at interactive rates [24, 88].

3.4 Dynamic control

Kinematic controllers are sometimes not sufficient to perform high speed tasks, or to compensate for vibrations for instance. To tackle these issues dynamic controllers have been designed.

3.4.1 Existing approaches and state of the art.

To manage the dynamics, Quadratic Programming can still be used by using a dynamic model of the soft robot. This makes it possible, offline, to plan its trajectory. An open-loop approach is presented in [29]. In [89], a Sequential Quadratic Program is used to solve the inverse dynamics of a fluid powered soft manipulator and iterative learning control is leveraged to perform trajectory optimization.

In order to perform closed loop control, real time performance has to be obtained. Several closed loop controllers based on the constant curvature or piecewise constant curvature models extended to dynamics have been proposed. Authors of [90] use the PCC hypothesis to describe their soft robot with Denavit-Hartenberg parameters and then use a dynamic controller designed for rigid robotics to control their system. This work has been continued using synergistic control and an extended controller from rigid robotics [91].

In [92], authors use the Koopman operator to construct a linear model of a soft arm actuated by pressure. Using this linear model they can perform Model Predictive Control by iteratively solving a quadratic program.

Based on a Cosserat model for statics and a Lagrangian model for dynamics [93], use Ritz and Ritz-Galerkin approaches to design a dynamic controller for a continuum manipulator and compares the results with several other models.

As stated before these models make the hypothesis of no deformation of the robot section, only the centerline of the robot deforms. This makes it possible to have models that are very quick to calculate.

In a more general design case, the use in real time of a FEM type numerical model, even if calculated in real time, is not fast enough for a real time control of the dynamics (the calculation must be faster than the eigenfrequencies of the robot). However, by applying Model Order Reduction techniques on FEM models, classical tools of control theory can be used to control the dynamical behavior of soft robots in simulation [30], and on real robots actuated by cables [39, 94] or pneumatics [95]. Stability can also be guaranteed using Lyapunov theory [38] with a proof of robustness to modeling errors generated by the reduction. This work was extended to use a reduced non linear model of the robot by leveraging a Linear Parameter Varying model [31].

3.4.2 Current limitations and challenges.

Dynamic models can be used offline for trajectory calculation. By using dynamic models with few state variables (whether simplified or reduced), it is possible to build low-level controllers for robots with guaranteed robustness. Recent progresses in this challenge of dynamic control of soft robots are really impressive.

However, for performance reasons, these approaches do not yet integrate a correct management of contacts and interactions with the environment, which is essential for robot dynamics.

Moreover, the challenge ahead is undoubtedly to increase the performances of soft robots that are still poor. It can be done by combining mechanical design and control strategies. These two being generally separated.

4 Implementation

This paper presents several existing methods to model and control soft robots but emphasizes the use of real-time FEM. This section focus on existing implementation of this approach.

4.1 SOFA

To model and simulate robots using the Finite Element Method, we use the free and open source software SOFA [96]. SOFA uses the theory of continuum mechanics for the material modeling, constraints are solved using Lagrange multipliers and contact interactions are handled using Signorini’s law [24]. Internal forces are computed based on a user chosen deformation law. Several deformation laws are available: linear options such as Hook’s law, as well as non linear strain-stress relationships or plastic deformations for instance. Several plugins are also available to extend SOFA’s functionalities for multiple applications, ranging from medical simulation to haptics. Some of these plugins are useful to soft robotics and will be described further.

4.2 SoftRobots and SoftRobots.Inverse plugins

SOFA was first intended for medical simulation. The SoftRobots plugin was introduced in 2017 to model and simulate deformable robots and their environment in SOFA [25]. The plugin takes advantage of the model of continuum mechanics and the Finite Element Method implemented in SOFA to apply them to simulating deformable robots. It also combines previous works on inverse FEM simulation [22, 32], soft robot control [14, 97] and real time simulation [18]. The SoftRobots.Inverse plugin allows for optimization-based inverse model control of soft robots based on Quadratic Programming, and can handle contacts [24].

4.3 Model Order Reduction

As expressed before, one of the main issues with the Finite Element Method is the computation cost. When using this method, the user must compromise some accuracy to be able to achieve real time simulation. This can take the form of using a coarser mesh, or a larger simulation timestep.

To address this issue, several approaches have been proposed to reduce the model. The objective here is to find a model with fewer variables which faithfully describes the behavior of the full order model according to some measure. Note that different measures may lead to different reduced models.

A plugin for Model Order Reduction is available in SOFA [36]. Using this plugin, the simulation can be made fast enough for dynamic control [30, 31, 38, 39, 94]

4.4 Hardware platforms

In order to test the algorithms, several hardware platforms have been designed. These platforms aim to test a broad variety of actuators and to represent a diversity of use cases. Most of these robots are presented in [70] and [24].

The most recent results include holding and manipulating a deformable cup with a silicone elephant trunk using Quadratic Programming [88] and a dynamic closed loop controller based on a reduced model of this same robot was proposed in [39, 94] to cancel the vibrations. Authors also compare open loop and closed loop control. A view of this robot holding a cup can be found in Fig 1.

thumbnail
Fig 1. Soft gripper based on an elephant trunk holding a deformable cup.

https://doi.org/10.1371/journal.pone.0251059.g001

Authors of [28] show the full pipeline starting from the design of a soft manipulator called Echelon 3, then modeling and simulating it using FEM. This allows to derive forward and inverse models, used to design open loop and closed loop controllers. These controllers are then experimentally validated and compared on the physical prototype and a haptic feedback loop is created. A picture of the physical prototype can be found in Fig 2.

5 Conclusion

The last decade has seen huge progress on low level control of soft robots, to the point that it is now no longer a question of whether we can control a specific soft robot, but to what degree of precision.

Performance of soft robots are not yet to the level of rigid robots though, and some work still remains to be done on design optimization, design of controllers especially dynamic ones and sensors.

Thanks to the use of models of soft robots for low level control, the higher level control and decision making policies are very close to those already implemented for rigid robotics or other fields such as autonomous driving. Indeed we can now use trajectory optimization or Model Predictive Control on soft robots.

In this context, the usefulness of FEM and more generally of physics-based numerical models computed in real time, has been demonstrated: it unifies the modelling from design to control and allows interactions with the environment to be taken into account. In the future, these methods will probably be coupled with learning approaches to correct modeling errors, to complete the control with higher-level decisions and to obtain more automatically the numerical model of the robot in its environment.

Acknowledgments

Disclaimer: This paper conveys the authors’ views, which are that Finite Element Methods should be more widespread in the soft robotics community. Indeed it is the authors’ belief that those methods allow to bridge the gap between rigid and soft robots, thus allowing to use common robotic tools, such as inverse models, kinematic and dynamic control. The computation time of these models has been greatly reduced by improvements in algorithms and increase in computation power, which supports their use in robotics.

References

  1. 1. Greigarn T, Cavusoglu MC. Task-space motion planning of MRI-actuated catheters for catheter ablation of atrial fibrillation. In: 2014 IEEE/RSJ International Conference on Intelligent Robots and Systems. Chicago, IL, USA: IEEE; 2014. p. 3476–3482. Available from: http://ieeexplore.ieee.org/document/6943047/.
  2. 2. Khoshnam M, Patel RV. A pseudo-rigid-body 3R model for a steerable ablation catheter. In: 2013 IEEE International Conference on Robotics and Automation. Karlsruhe, Germany: IEEE; 2013. p. 4427–4432. Available from: http://ieeexplore.ieee.org/document/6631205/.
  3. 3. Ganji Y, Janabi-Sharifi F, Cheema AN. Robot-assisted catheter manipulation for intracardiac navigation. International Journal of Computer Assisted Radiology and Surgery. 2009;4(4):307–315.
  4. 4. Webster RJ, Jones BA. Design and Kinematic Modeling of Constant Curvature Continuum Robots: A Review. The International Journal of Robotics Research. 2010;29(13):1661–1683.
  5. 5. Hesheng Wang, Weidong Chen, Xiaojin Yu, Tao Deng, Xiaozhou Wang, Pfeifer R. Visual servo control of cable-driven soft robotic manipulator. In: 2013 IEEE/RSJ International Conference on Intelligent Robots and Systems. Tokyo: IEEE; 2013. p. 57–62. Available from: http://ieeexplore.ieee.org/document/6696332/.
  6. 6. Marchese AD, Komorowski K, Onal CD, Rus D. Design and control of a soft and continuously deformable 2D robotic manipulation system. In: 2014 IEEE International Conference on Robotics and Automation (ICRA). Hong Kong, China: IEEE; 2014. p. 2189–2196. Available from: http://ieeexplore.ieee.org/document/6907161/.
  7. 7. Falkenhahn V, Hildebrandt A, Neumann R, Sawodny O. Model-based feedforward position control of constant curvature continuum robots using feedback linearization. In: 2015 IEEE International Conference on Robotics and Automation (ICRA). Seattle, WA, USA: IEEE; 2015. p. 762–767. Available from: http://ieeexplore.ieee.org/document/7139264/.
  8. 8. Renda F, Boyer F, Dias J, Seneviratne L. Discrete Cosserat Approach for Multisection Soft Manipulator Dynamics. IEEE Transactions on Robotics. 2018;34(6):1518–1533.
  9. 9. Trivedi D, Lotfi A, Rahn CD. Geometrically Exact Models for Soft Robotic Manipulators. IEEE Transactions on Robotics. 2008;24(4):773–780.
  10. 10. Pai DK. STRANDS: Interactive Simulation of Thin Solids using Cosserat Models. Computer Graphics Forum. 2002;21(3):347–352.
  11. 11. Renda F, Giorelli M, Calisti M, Cianchetti M, Laschi C. Dynamic Model of a Multibending Soft Robot Arm Driven by Cables. IEEE Transactions on Robotics. 2014;30(5):1109–1122.
  12. 12. Renda F, Giorgio-Serchi F, Boyer F, Laschi C. Modelling cephalopod-inspired pulsed-jet locomotion for underwater soft robots. Bioinspiration & Biomimetics. 2015;10(5):055005.
  13. 13. Renda F, Giorgio-Serchi F, Boyer F, Laschi C, Dias J, Seneviratne L. A unified multi-soft-body dynamic model for underwater soft robots. The International Journal of Robotics Research. 2018;37(6):648–666.
  14. 14. Duriez C. Control of elastic soft robots based on real-time finite element method. In: 2013 IEEE International Conference on Robotics and Automation. Karlsruhe, Germany: IEEE; 2013. p. 3982–3987. Available from: http://ieeexplore.ieee.org/document/6631138/.
  15. 15. Duriez C, Cotin S, Lenoir J, Neumann P. New approaches to catheter navigation for interventional radiology simulation. Computer Aided Surgery. 2006;11(6):300–308.
  16. 16. Bartlett NW, Tolley MT, Overvelde JTB, Weaver JC, Mosadegh B, Bertoldi K, et al. A 3D-printed, functionally graded soft robot powered by combustion. Science. 2015;349(6244):161–165. pmid:26160940
  17. 17. Polygerinos P, Wang Z, Overvelde JTB, Galloway KC, Wood RJ, Bertoldi K, et al. Modeling of Soft Fiber-Reinforced Bending Actuators. IEEE Transactions on Robotics. 2015;31(3):778–789.
  18. 18. Courtecuisse H, Allard J, Kerfriden P, Bordas SPA, Cotin S, Duriez C. Real-time simulation of contact and cutting of heterogeneous soft-tissues. Medical Image Analysis. 2014;18(2):394–410.
  19. 19. Courtecuisse H, Adagolodjo Y, Delingette H, Duriez C. Haptic rendering of hyperelastic models with friction. In: 2015 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). Hamburg, Germany: IEEE; 2015. p. 591–596. Available from: http://ieeexplore.ieee.org/document/7353432/.
  20. 20. Skouras M, Thomaszewski B, Coros S, Bickel B, Gross M. Computational design of actuated deformable characters. ACM Transactions on Graphics. 2013;32(4):1.
  21. 21. Bern JM, Chang KH, Coros S. Interactive design of animated plushies. ACM Transactions on Graphics. 2017;36(4):1–11.
  22. 22. Coevoet E, Reynaert N, Lartigau E, Schiappacasse L, Dequidt J, Duriez C. Introducing Interactive Inverse FEM Simulation and Its Application for Adaptive Radiotherapy. In: Golland P, Hata N, Barillot C, Hornegger J, Howe R, editors. Medical Image Computing and Computer-Assisted Intervention – MICCAI 2014. vol. 8674. Cham: Springer International Publishing; 2014. p. 81–88. Available from: http://link.springer.com/10.1007/978-3-319-10470-6_11.
  23. 23. Coevoet E, Reynaert N, Lartigau E, Schiappacasse L, Dequidt J, Duriez C. Registration by interactive inverse simulation: application for adaptive radiotherapy. International Journal of Computer Assisted Radiology and Surgery. 2015;10(8):1193–1200.
  24. 24. Coevoet E, Escande A, Duriez C. Optimization-Based Inverse Model of Soft Robots With Contact Handling. IEEE Robotics and Automation Letters. 2017;2(3):1413–1419.
  25. 25. Coevoet E, Morales-Bieze T, Largilliere F, Zhang Z, Thieffry M, Sanz-Lopez M, et al. Software toolkit for modeling, simulation, and control of soft robots. Advanced Robotics. 2017;31(22):1208–1224.
  26. 26. Zhang Z, Dequidt J, Kruszewski A, Largilliere F, Duriez C. Kinematic modeling and observer based control of soft robot using real-time Finite Element Method. In: 2016 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). Daejeon, South Korea: IEEE; 2016. p. 5509–5514. Available from: http://ieeexplore.ieee.org/document/7759810/.
  27. 27. Bieze TM, Largilliere F, Kruszewski A, Zhang Z, Merzouki R, Duriez C. Finite Element Method-Based Kinematics and Closed-Loop Control of Soft, Continuum Manipulators. Soft Robotics. 2018;5(3):348–364.
  28. 28. Morales Bieze T, Kruszewski A, Carrez B, Duriez C. Design, implementation, and control of a deformable manipulator robot based on a compliant spine. The International Journal of Robotics Research. 2020; p. 027836492091048.
  29. 29. Lismonde A, Sonneville V, Brüls O. Trajectory planning of soft link robots with improved intrinsic safety * *The publication is funded by the European Regional Development Fund (ERDF) within European Union’s INTERREG V A-program Greater Region, project Robotix Academy.In addition, the first author would like to acknowledge the Belgian Fund for Research training in Industry and Agriculture for its financial support (FRIA grant). IFAC-PapersOnLine. 2017;50(1):6016–6021.
  30. 30. Thieffry M, Kruszewski A, Goury O, Guerra TM, Duriez C. Dynamic Control of Soft Robots. 2017; p. 5.
  31. 31. Thieffry M, Kruszewski A, Guerra TM, Duriez C. LPV Framework for Non-Linear Dynamic Control of Soft Robots using Finite Element Model. 2020; p. 8.
  32. 32. Largilliere F, Coevoet E, Sanz-Lopez M, Grisoni L, Duriez C. Stiffness rendering on soft tangible devices controlled through inverse FEM simulation. In: 2016 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). Daejeon, South Korea: IEEE; 2016. p. 5224–5229. Available from: http://ieeexplore.ieee.org/document/7759768/.
  33. 33. Runge G, Raatz A. A framework for the automated design and modelling of soft robotic systems. CIRP Annals. 2017;66(1):9–12.
  34. 34. Morzadec T, Marcha D, Duriez C. Toward Shape Optimization of Soft Robots. In: 2019 2nd IEEE International Conference on Soft Robotics (RoboSoft). Seoul, Korea (South): IEEE; 2019. p. 521–526. Available from: https://ieeexplore.ieee.org/document/8722822/.
  35. 35. Vanneste F, Goury O, Martinez J, Lefebvre S, Delingette H, Duriez C. Anisotropic Soft Robots Based on 3D Printed Meso-Structured Materials: Design, Modeling by Homogenization and Simulation. IEEE Robotics and Automation Letters. 2020;5(2):2380–2386.
  36. 36. Goury O, Duriez C. Fast, Generic, and Reliable Control and Simulation of Soft Robots Using Model Order Reduction. IEEE Transactions on Robotics. 2018;34(6):1565–1576.
  37. 37. Chenevier J, González D, Aguado JV, Chinesta F, Cueto E. Reduced-order modeling of soft robots. PLOS ONE. 2018;13(2):e0192052.
  38. 38. Thieffry M, Kruszewski A, Guerra TM, Duriez C. Reduced Order Control of Soft Robots with Guaranteed Stability. In: 2018 European Control Conference (ECC). Limassol: IEEE; 2018. p. 635–640. Available from: https://ieeexplore.ieee.org/document/8550298/.
  39. 39. Thieffry M, Kruszewski A, Duriez C, Guerra Tm. Control Design for Soft Robots based on Reduced Order Model. IEEE Robotics and Automation Letters. 2018; p. 1–1.
  40. 40. Mendizabal A, Tagliabue E, Brunet JN, Dall’Alba D, Fiorini P, Cotin S. Physics-based Deep Neural Network for Real-Time Lesion Tracking in Ultrasound-guided Breast Biopsy. 2019; p. 14.
  41. 41. Mendizabal A, Márquez-Neila P, Cotin S. Simulation of hyperelastic materials in real-time using deep learning. Medical Image Analysis. 2020;59:101569.
  42. 42. Wang H, Chen W, Wang C, Wang X, Pfeifer R. Dynamic modeling and image-based adaptive visual servoing of cable-driven soft robotic manipulator. IFAC Proceedings Volumes. 2014;47(3):11884–11889.
  43. 43. Giorelli M, Renda F, Calisti M, Arienti A, Ferri G, Laschi C. A two dimensional inverse kinetics model of a cable driven manipulator inspired by the octopus arm. In: 2012 IEEE International Conference on Robotics and Automation. St Paul, MN, USA: IEEE; 2012. p. 3819–3824. Available from: http://ieeexplore.ieee.org/document/6225254/.
  44. 44. Wang J, Lu Y, Zhang C, Song S, Meng MQH. Pilot study on shape sensing for continuum tubular robot with multi-magnet tracking algorithm. In: 2017 IEEE International Conference on Robotics and Biomimetics (ROBIO). IEEE; 2017. p. 1165–1170.
  45. 45. Wang H, Totaro M, Beccai L. Toward perceptive soft robots: Progress and challenges. Advanced Science. 2018;5(9):1800541.
  46. 46. Fassler A, Majidi C. Soft-matter capacitors and inductors for hyperelastic strain sensing and stretchable electronics. Smart Materials and Structures. 2013;22(5):055023.
  47. 47. Navarro SE, Goury O, Zheng G, Bieze TM, Duriez C. Modeling novel soft mechanosensors based on air-flow measurements. IEEE Robotics and Automation Letters. 2019;4(4):4338–4345.
  48. 48. Zhang Z, Dequidt J, Duriez C. Vision-Based Sensing of External Forces Acting on Soft Robots Using Finite Element Method. IEEE Robotics and Automation Letters. 2018;3(3):1529–1536.
  49. 49. Onal CD, Rus D. Autonomous undulatory serpentine locomotion utilizing body dynamics of a fluidic soft robot. Bioinspiration & Biomimetics. 2013;8(2):026003.
  50. 50. Umedachi T, Vikas V, Trimmer BA. Highly deformable 3-D printed soft robot generating inching and crawling locomotions with variable friction legs. In: 2013 IEEE/RSJ International Conference on Intelligent Robots and Systems. Tokyo: IEEE; 2013. p. 4590–4595. Available from: http://ieeexplore.ieee.org/document/6697016/.
  51. 51. George Thuruthel T, Falotico E, Manti M, Pratesi A, Cianchetti M, Laschi C. Learning Closed Loop Kinematic Controllers for Continuum Manipulators in Unstructured Environments. Soft Robotics. 2017;4(3):285–296.
  52. 52. Behr T, Pusch TP, Siegfarth M, Hüsener D, Mörschel T, Karstensen L. Deep Reinforcement Learning for the Navigation of Neurovascular Catheters. Current Directions in Biomedical Engineering. 2019;5(1):5–8.
  53. 53. Bhagat S, Banerjee H, Ho Tse Z, Ren H. Deep Reinforcement Learning for Soft, Flexible Robots: Brief Review with Impending Challenges. Robotics. 2019;8(1):4.
  54. 54. Zhu Y, Mottaghi R, Kolve E, Lim JJ, Gupta A, Fei-Fei L, et al. Target-driven Visual Navigation in Indoor Scenes using Deep Reinforcement Learning. arXiv:160905143 [cs]. 2016;.
  55. 55. Chen YF, Everett M, Liu M, How JP. Socially Aware Motion Planning with Deep Reinforcement Learning. arXiv:170308862 [cs]. 2018;.
  56. 56. Zhang J, Tai L, Boedecker J, Burgard W, Liu M. Neural SLAM: Learning to Explore with External Memory. arXiv:170609520 [cs]. 2017;.
  57. 57. Gupta S, Tolani V, Davidson J, Levine S, Sukthankar R, Malik J. Cognitive Mapping and Planning for Visual Navigation. arXiv:170203920 [cs]. 2019;.
  58. 58. Gu S, Holly E, Lillicrap T, Levine S. Deep Reinforcement Learning for Robotic Manipulation with Asynchronous Off-Policy Updates. arXiv:161000633 [cs]. 2016;.
  59. 59. Levine S, Finn C, Darrell T, Abbeel P. End-to-End Training of Deep Visuomotor Policies. arXiv:150400702 [cs]. 2016;.
  60. 60. Finn C, Tan XY, Duan Y, Darrell T, Levine S, Abbeel P. Deep Spatial Autoencoders for Visuomotor Learning. arXiv:150906113 [cs]. 2016;.
  61. 61. Tzeng E, Devin C, Hoffman J, Finn C, Abbeel P, Levine S, et al. Adapting Deep Visuomotor Representations with Weak Pairwise Constraints. arXiv:151107111 [cs]. 2017;.
  62. 62. Sears P, Dupont P. A Steerable Needle Technology Using Curved Concentric Tubes. In: 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems. Beijing, China: IEEE; 2006. p. 2850–2856. Available from: http://ieeexplore.ieee.org/document/4058826/.
  63. 63. Neppalli S, Csencsits MA, Jones BA, Walker ID. Closed-Form Inverse Kinematics for Continuum Manipulators. Advanced Robotics. 2009;23(15):2077–2091.
  64. 64. Zhang Z, Bieze TM, Dequidt J, Kruszewski A, Duriez C. Visual servoing control of soft robots based on finite element model. In: 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). Vancouver, BC: IEEE; 2017. p. 2895–2901. Available from: http://ieeexplore.ieee.org/document/8206121/.
  65. 65. Adagolodjo Y, Goffin L, De Mathelin M, Courtecuisse H. Robotic Insertion of Flexible Needle in Deformable Structures Using Inverse Finite-Element Simulation. IEEE Transactions on Robotics. 2019;35(3):697–708.
  66. 66. Baksic P, Courtecuisse H, Duriez C, Bayle B. Robotic needle insertion in moving soft tissues using constraint-based inverse Finite Element simulation. 2020; p. 9.
  67. 67. Aristidou A, Lasenby J, Chrysanthou Y, Shamir A. Inverse Kinematics Techniques in Computer Graphics: A Survey: Inverse Kinematics Techniques in Computer Graphics. Computer Graphics Forum. 2018;37(6):35–58.
  68. 68. Sifakis E, Neverov I, Fedkiw R. Automatic Determination of Facial Muscle Activations from Sparse Motion Capture Marker Data. 2005; p. 9.
  69. 69. Sueda S. Musculotendon Simulation for Hand Animation. 2008; p. 8.
  70. 70. Duriez C, Coevoet E, Largilliere F, Morales-Bieze T, Zhang Z, Sanz-Lopez M, et al. Framework for online simulation of soft robots with optimization-based inverse model. In: 2016 IEEE International Conference on Simulation, Modeling, and Programming for Autonomous Robots (SIMPAR). San Francisco, CA, USA: IEEE; 2016. p. 111–118. Available from: http://ieeexplore.ieee.org/document/7862384/.
  71. 71. Rodriguez A, Coevoet E, Duriez C. Real-time simulation of hydraulic components for interactive control of soft robots. In: 2017 IEEE International Conference on Robotics and Automation (ICRA). Singapore, Singapore: IEEE; 2017. p. 4953–4958. Available from: http://ieeexplore.ieee.org/document/7989575/.
  72. 72. Nguyen-Tuong D, Peters J. Model learning for robot control: a survey. Cognitive Processing. 2011;12(4):319–340.
  73. 73. Braganza D, Dawson DM, Walker ID, Nath N. A Neural Network Controller for Continuum Robots. IEEE Transactions on Robotics. 2007;23(6):1270–1277.
  74. 74. Giorelli M, Renda F, Ferri G, Laschi C. A feed-forward neural network learning the inverse kinetics of a soft cable-driven manipulator moving in three-dimensional space. In: 2013 IEEE/RSJ International Conference on Intelligent Robots and Systems. Tokyo: IEEE; 2013. p. 5033–5039. Available from: http://ieeexplore.ieee.org/document/6697084/.
  75. 75. Giorelli M, Renda F, Calisti M, Arienti A, Ferri G, Laschi C. Neural Network and Jacobian Method for Solving the Inverse Statics of a Cable-Driven Soft Arm With Nonconstant Curvature. IEEE Transactions on Robotics. 2015;31(4):823–834.
  76. 76. Polydoros AS, Nalpantidis L, Kruger V. Real-time deep learning of robotic manipulator inverse dynamics. In: 2015 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). Hamburg, Germany: IEEE; 2015. p. 3442–3448. Available from: http://ieeexplore.ieee.org/document/7353857/.
  77. 77. Thuruthel TG, Falotico E, Cianchetti M, Laschi C. Learning Global Inverse Kinematics Solutions for a Continuum Robot. In: Parenti-Castelli V, Schiehlen W, editors. ROMANSY 21—Robot Design, Dynamics and Control. vol. 569. Cham: Springer International Publishing; 2016. p. 47–54. Available from: http://link.springer.com/10.1007/978-3-319-33714-2_6.
  78. 78. Grochow K, Martin SL, Hertzmann A, Popovic Z. Style-Based Inverse Kinematics. 2004; p. 10.
  79. 79. Holden D, Saito J, Komura T. Learning an inverse rig mapping for character animation. In: Proceedings of the 14th ACM SIGGRAPH / Eurographics Symposium on Computer Animation—SCA’15. Los Angeles, California: ACM Press; 2015. p. 165–173. Available from: http://dl.acm.org/citation.cfm?doid=2786784.2786788.
  80. 80. Beckers T, Hirche S. Keep soft robots soft—a data-driven based trade-off between feed-forward and feedback control. arXiv:190610489 [cs, eess]. 2019;.
  81. 81. Fang G, Wang X, Wang K, Lee KH, Ho JDL, Fu HC, et al. Vision-Based Online Learning Kinematic Control for Soft Robots Using Local Gaussian Process Regression. IEEE Robotics and Automation Letters. 2019;4(2):1194–1201.
  82. 82. Yip MC, Camarillo DB. Model-Less Feedback Control of Continuum Manipulators in Constrained Environments. IEEE Transactions on Robotics. 2014;30(4):880–889.
  83. 83. Yip MC, Camarillo DB. Model-Less Hybrid Position/Force Control: A Minimalist Approach for Continuum Manipulators in Unknown, Constrained Environments. IEEE Robotics and Automation Letters. 2016;1(2):844–851.
  84. 84. Posa M, Tedrake R. Direct Trajectory Optimization of Rigid Body Dynamical Systems through Contact. In: Frazzoli E, Lozano-Perez T, Roy N, Rus D, editors. Algorithmic Foundations of Robotics X. vol. 86. Berlin, Heidelberg: Springer Berlin Heidelberg; 2013. p. 527–542. Available from: http://link.springer.com/10.1007/978-3-642-36279-8_32.
  85. 85. Mordatch I, Todorov E, Popović Z. Discovery of complex behaviors through contact-invariant optimization. ACM Transactions on Graphics. 2012;31(4):1–8.
  86. 86. Junggon Kim, Pollard NS. Direct Control of Simulated Nonhuman Characters. IEEE Computer Graphics and Applications. 2011;31(4):56–65.
  87. 87. Coros S, Martin S, Thomaszewski B, Schumacher C, Sumner R, Gross M. Deformable Objects Alive! 2012; p. 9.
  88. 88. Coevoet E, Escande A, Duriez C. Soft robots locomotion and manipulation control using FEM simulation and quadratic programming. In: 2019 2nd IEEE International Conference on Soft Robotics (RoboSoft). Seoul, Korea (South): IEEE; 2019. p. 739–745. Available from: https://ieeexplore.ieee.org/document/8722815/.
  89. 89. Marchese AD, Tedrake R, Rus D. Dynamics and trajectory optimization for a soft spatial fluidic elastomer manipulator. In: 2015 IEEE International Conference on Robotics and Automation (ICRA). Seattle, WA, USA: IEEE; 2015. p. 2528–2535. Available from: http://ieeexplore.ieee.org/document/7139538/.
  90. 90. Della Santina C, Katzschmann RK, Biechi A, Rus D. Dynamic control of soft robots interacting with the environment. In: 2018 IEEE International Conference on Soft Robotics (RoboSoft). Livorno: IEEE; 2018. p. 46–53. Available from: https://ieeexplore.ieee.org/document/8404895/.
  91. 91. Santina CD, Pallottino L, Rus D, Bicchi A. Exact Task Execution in Highly Under-Actuated Soft Limbs: An Operational Space Based Approach. IEEE Robotics and Automation Letters. 2019;4(3):2508–2515.
  92. 92. Bruder D, Gillespie B, Remy CD, Vasudevan R. Modeling and Control of Soft Robots Using the Koopman Operator and Model Predictive Control. arXiv:190202827 [cs]. 2019;.
  93. 93. Sadati SMH, Naghibi SE, Walker ID, Althoefer K, Nanayakkara T. Control Space Reduction and Real-Time Accurate Modeling of Continuum Manipulators Using Ritz and Ritz–Galerkin Methods. IEEE Robotics and Automation Letters. 2018;3(1):328–335.
  94. 94. Thieffry M, Kruszewski A, Guerra TM, Duriez C. Trajectory Tracking Control Design for Large-Scale Linear Dynamical Systems With Applications to Soft Robotics. IEEE Transactions on Control Systems Technology. 2019; p. 1–11.
  95. 95. Katzschmann RK, Thieffry M, Goury O, Kruszewski A, Guerra TM, Duriez C, et al. Dynamically Closed-Loop Controlled Soft Robotic Arm using a Reduced Order Finite Element Model with State Observer. In: 2019 2nd IEEE International Conference on Soft Robotics (RoboSoft). Seoul, Korea (South): IEEE; 2019. p. 717–724. Available from: https://ieeexplore.ieee.org/document/8722804/.
  96. 96. Allard J, Cotin S, Faure F, Duriez C, Delingette H, Grisoni L. SOFA—an Open Source Framework for Medical Simulation. 2008; p. 7.
  97. 97. Bosman J, Bieze TM, Lakhal O, Sanz M, Merzouki R, Duriez C. Domain decomposition approach for FEM quasistatic modeling and control of Continuum Robots with rigid vertebras. In: 2015 IEEE International Conference on Robotics and Automation (ICRA). Seattle, WA, USA: IEEE; 2015. p. 4373–4378. Available from: http://ieeexplore.ieee.org/document/7139803/.