Skip to content

Sorotoki - a MATLAB toolkit for soft robotics


Github page is still under construction. Not all documentation is present at the this stage of development.

CircleCI MATLAB Static Badge Discord GitHub

Sorotoki is an open-source MATLAB toolkit for soft robotics that aims to facilitate the development of novel research in the field by providing a comprehensive set of tools for design, modeling, and control. The toolkit includes a diverse array of scientific disciplines relevant to soft robotics, such as continuum mechanics, dynamic systems and control theory, topology optimization, and computer graphics. The Sorotoki toolkit aims to make it easier for new researchers to learn about soft robotics by providing a range of tools that cover various important aspects of the field. This can significantly reduce the amount of time and effort required to get up to speed on the topic.

What can Sorotoki do?

Sorotoki has grown significantly since its inception and now offers a wide range of functionalities tailored to various aspects of soft robotics. For example, suppose you are inspired by the multi-gait soft crawler developed by Shepard et al.1 -- See video. Or you want to simulate the incredibly dexterous soft gripper developed by Suzumori et al.2 -- See video. Can we model such systems easily? Well.... Short answer: no. As matter of fact, simplifying the (infinite-dimensional) dynamics of soft robots is no easy feat. It has been an active topic of research for the better part of the last two decades. Ironically, studying "soft" robotics is incredibly "hard".

Sorotoki, however, can simplify the process of design, modeling and control for soft robots. Our aim is to make research into soft robotics more accessable by dividing the problem into smaller, more manageable steps. Multi-physics solvers are included into Sorotoki and can accessed with minimal programming complexity.

Simulation of multi-gait crawling soft robot undergoing an undulating motion. The model is inspired by the work of Shepard et al. (2011). Original soft robot can be found here: Youtube video
Simulation of multi-finger soft gripper grasping a beaker and manipulating a M10 boltscrew. The model is inspired by the work of Suzumori et al. (1989). Original soft gripper can be found here: Youtube video
But, is it easy to code?

Well, absolutely! Sorotoki is aimed at removing complexity -- not only for soft robots but also for coding your problems! See the following example codes below:

List of functionalities

To summarize, some of the functionalities included in the toolkit are listed below:

  • Design: Implicit modeling using signed distance functions (SDFs), 2D-3D mesh generation, computational design using gradient-based optimization
  • Modeling: Finite Element Models (FEM), high-efficiency reduced-order soft beam models (Lagrangian or port-Hamiltonian), easy programmable interconnections of a network of dynamical (soft robot) systems
  • Control: Real-time (pneumatic) control platform using Raspberry Pi, vision-based sensing algorithms using Intel Realsense Depth camera
  • Visualization: Fast and responsive 3D graphics rendering, mesh deformation modifiers (scaling, rotation, bending, twisting, mirroring), Forward Kinematic/Inverse Kinematic-rigging
  • Accessibility: Minimal programming environment (i.e, focused on expressing complex problems with minimal lines of code).
  • Open hardware: Four 3D-printable soft robots (e.g., soft hand, soft manipulator), and control interface).

Short examples

Example 1: PneuNet deformations

A classic example in soft robotics is the PneuNet soft bending actuator. The PneuNet (pneumatic network) belongs to a class of soft actuators that, due to a geometrically induced stiffness differential, undergoes bending when pressurized. The geometry of the PneuNet is developed (and popularized) by Mosadegh et al.3 , but historically it is much older4. To model the PneuNet actuator, consider the following numerical example. Assuming plane strain, we can simulate the nonlinear bending characteristics of the Pneunet actuator using the super-short code below (only 10 lines of code!):

Code for simulation
% generate mesh from image
msh = preset.mesh.pneunet;

% finite element solver (FEM)
fem = Fem(msh,'TimeStep', 1e-2);

% boundary conditions
fem = fem.addMaterial(NeoHookean(1, 0.4));
fem = fem.addGravity();
fem = fem.addPressure('allhole', 30 * 1e-3);
fem = fem.addSupport('left', [1,1]);

% magic
fem = fem.solve();

% take away message: simplicity > complexity
Code for plotting

Once a simulation is completed, there exist simple command to export the simulation as a .gif file. We can simple use the command below. This sets the frames-per-second (FPS), the axis for the replay video, and gif = true to make a gif file.

fem.replay('fps',60,...
           'axis',[-33, 120 -86 21],...
           'gif',true)
Example 2: Fitting hyper-elastic materials

Soft robots own their name to soft materials. It is therefore of paramount importance that the constitutive material models reflect the mechanical nature truthfully. However, finding the "true" material parameters for these material models can be challenging without the proper tools. Sorotoki is equipped with tools for hyper-elastic material fitting. Consider for instance the cubic Yeoh model:

\[ \Psi_{\textrm{YH}}(I_1; \pi) = \sum_{i = 1}^3 \pi_i (I_1 - 3)^{i} \]

where \(I_1 = {\lambda_1}^2 + {\lambda_2}^2 + {\lambda_3}^2\) is the first strain invariant, and \(\pi\) a vector of unknown material parameters. For uniaxial tension, we have that \(\lambda_1 = \lambda\) and \(\lambda_2 = \lambda_3 = 1/{\lambda^2}\). Therefore, the stress along the uniaxial tension test is given by \( \sigma_{11} = 2 \left(\lambda^2 - \frac{1}{\lambda} \right)\Psi' \) with \(\Psi'\) the partial derivative of \(\Psi\) with respect to \(I_1\). Luckily, these uniaxial stress-strain relations are included in every hyperelastic material model of Sorotoki. Simply call S = material.uniaxial(x). The optimal material parameters \(\pi\) can then be easily found using standard optimization routines such as fmincon. See the example below.

Code for simulation
% CODE: Example 2 -- Material fitting using fmincon
[lam, str] = materialDataBase('DragonSkin10');

% define objective (Yeoh model)
obj = @(Pi) Objective(Pi,lam,str);

Pi0 = [0.0, 0.0, 0.0];  % initial guess
lb  = [1e-6, -2,  -2];  % lower bounds
ub  = [Inf, Inf, Inf];  % upper bounds

opt = optimoptions(@fmincon,'FiniteDifferenceStepSize',1e-12,  
                            'Algorithm','sqp-legacy');

fig(101,[9,9]);
Pi = fmincon(Obj,Pi0,[],[],[],[],lb,ub,[],opt);

function obj = Objective(Pi,X,Y)
    Q   = diag(Y.^-2);   % weighting - emphasis low strains  
    E   = Y - YeohMaterial(Pi).uniaxial(X); % stress resid.

    % quadratic lost function
    obj = E(:).' * Q * E(:);

    cla;
    plot(x, y, 'Color', color_light_gray); hold on;
    plot(x, YeohMaterial(Pi).uniaxial(x), ...
            'Color', color_visited_alt);
    ylabel('engineering stress $\sigma_{11}$');    
    xlabel('stretch $\lambda$');
end
Example 3: Task-space controller for soft manipulator

The next example shows the implementation of model-based controllers in Sorotoki. Consider a soft tentacle of length \(L = 100\) mm, radius \(R = 5\) mm, and a tapering of \(75\%\). We assume the tentacle is composed of NeoHookean material.

\[\tau = J_v^\top\left[k_p (X_d - X) - k_d \dot{X}\right] + \nabla_q \mathcal{V}\]

where \(J_v(q) := \lfloor J(q,L) \rfloor_3\) is the linear velocity part of the manipulator Jacobian matrix at the tip (\(\sigma = L\)), \(\nabla_q \mathcal{V}\) is simply the gradient of the potential energy w.r.t to its states \(q\), \(X\) and \(X_d\) the end-effector position and the desired position, respectively. Note that the end-effector velocity is given by \(\dot{X} = J_v(q) \dot{q}\) (which Sorotoki pre-computes).

Code for simulation
% CODE: Example 2 -- Task-space controller
% assign desired setpoint
Xd  = [30; 10; 10]; 

% build continuum shape
POD = chebyspace(60, 3);            % POD basis
shp = Shapes(POD,[0,3,3,0,0,0], ... % pure bending XY
                'Material', NeoHookean(0.01,0.3));

% geometry and boundary conditions
shp = shp.setRadius(5);   % R = 5 mm
shp = shp.setRamp(0.75);  % R is reduced by 75% at s=L
shp = shp.addGravity();

% assign controller
shp.system.Controller = @(x) Control(x,Xd);

% magic ;)
shp = shp.simulate();

% task-space controller (called by solver)
function tau = tau(mdl,Xd)
  J = shp.system.Jacobian(4:6,:,end);
  ve = shp.system.Velocity(4:6,:,end);
  fe = shp.system.fElastic;
  fg = shp.system.fBody;
  x  = shp.system.Backbone(1:3,4,end);

  [kd, kp] = deal(5e-6);

  tau = fe + fg + kp * J.'*(Xd(:) - x) - kd * J.' * ve;
end
Code for plotting
% Example 2b: plotting Model data
% for loop over Model log files
for ii = 1:numel(mdl.Log.t)  

    shp = shp.render(mdl.Log.x(ii,1:6)); % render shape

    if ii == 1, % render setpoint Xd
      plotpoint(Xd);  
    end

    axis([0 100 -5, 5, -10, 30]);
    view(30,30);
    drawnow;
end
Example 4: Open-loop control of soft hand

% CODE: Example 3 -- Open-loop controller
% connect to controller board
brd = Bdog('pi','192.168.0.2','pwd', ...
           'NVeab',3);

% set board update frequency
brd = brd.set('Frequency',120);

% phase offset per finger
phi = @(k) (k-1)*pi/6;

%% execute control loop for T=10s
while brd.loop(10)
    T = ones(5,1) * brd.t;

    Pd = zeros(1,6);
    Pd(1:5) = 80 * sign(sin(4 * T - phi(1:5).')) * ...
              smoothstep(t-1);

    brd.setInput(Pd);
end

% disconnect system
brd.disconnect();

How to cite?

If you are planning on using Sorotoki in your (academic) work, please consider citing the toolkit

@misc{Caasenbrood2020,
  author = {Caasenbrood, Brandon},
  title = {Sorotoki - A Soft Robotics Toolkit for MATLAB},
  year = {2020},
  publisher = {GitHub},
  journal = {GitHub repository},
  howpublished = {\url{https://github.com/BJCaasenbrood/SorotokiCode}},
}

  1. Shepherd, R. F., Ilievski, F., Choi, W., Morin, S. A., Stokes, A. A., Mazzeo, A. D., ...Whitesides, G. M. (2011). Multigait soft robot. Proc. Natl. Acad. Sci. U.S.A., 22123978. Retrieved from https://pubmed.ncbi.nlm.nih.gov/22123978 doi: https://doi.org/10.1073/pnas.1116564108  

  2. Suzumori, K., Iikura, S., & Tanaka, H. (1991). Development of flexible microactuator and its applications to robotic mechanisms. Proceedings. 1991 IEEE International Conference on Robotics and Automation. IEEE. doi: https://doi.org/10.1109/ROBOT.1991.131850 

  3. Mosadegh, B., Polygerinos, P., Keplinger, C., Wennstedt, S., Shepherd, R. F., Gupta, U., ...Whitesides, G. M. (2014). Pneumatic Networks for Soft Robotics that Actuate Rapidly. Adv. Funct. Mater., 24(15), 2163–2170. doi: https://doi.org/10.1002/adfm.201303288 

  4. 1981 - Robot Arm with Pneumatic Gripper - Nikolai Teleshev (Russian) - cyberneticzoo.com. (2012, April 08). Retrieved from http://cyberneticzoo.com/bionics/1981-robot-arm-with-pneumatic-gripper-nikolai-teleshev-russian