Basic usage¶
Installation¶
Download the source code from GitHub and place it in your working directory.
Initialization¶
Add the library to the MATLAB path by running the ./src/initToolbox.m
script.
1run('./src/initToolbox.m')
Note
The script has to be executed every time a new instance of MATLAB is started.
Introduction to Jelly¶
Suppose we want to model a 3D continuum soft robot of two bodies modeled under the Piecewise Constant Curvature (PCC) hypothesis.
Each body has rest length , base and tip radius
and
, respectively,
and mass density
.
Furthermore,
is the Young modulus,
the Poisson ratio and
the material damping coefficient.
Finally, use
Gaussian for the numerical computation of the kinematics and the integrals.
To create such robot two main ingredients are needed:
Two joints that connect the robot bodies;
Two 3D PCC bodies.
Create two fixed joints to connect the first body to the robot base and second body to the first.
1%Allocate the joints and store them in a cell array
2Joints = {FixedJoint(); FixedJoint()};
Now, create two 3D PCC bodies by using the PCC3D
class.
1%Rest length
2L = 0.3;
3%Base radius
4R_base = 0.01;
5%Tip radius
6R_tip = 0.01;
7%Mass density
8rho = 1062;
9%Young modulus
10E = 6.66*1e6;
11%Poisson ratio
12nu = 0.5;
13%Material damping
14eta = 0.1;
15%Number of Gaussian points
16N_Gauss = 10;
17%Create a vector of parameters
18BodyParameters = [L; R_base; R_tip; rho; E; nu; eta; N_Gauss];
19%Allocate the bodies and store them in a cell array
20Bodies = {PCC3D(BodyParameters); PCC3D(BodyParameters)};
In Jelly, a robot is modeled by the BodyTree
class, which is a serial assembly of
joints
and bodies
.
To build the robot create a BodyTree
instance.
1Robot = BodyTree(Joints, Bodies);
Now, use the Robot
object to compute some dynamic terms.
1%Configuration variables and time derivatives
2q = [0; -pi; 0; pi/3; pi/4; -0.01];
3dq = zeros(Robot.n, 1);
4ddq = zeros(Robot.n, 1);
5%Generalized actuation force
6tau = ones(Robot.n, 1);
7
8%Evaluate the inverse dynamics
9Robot.InverseDynamics(q, dq, ddq)
10
11%Evaluate the forward dynamics
12Robot.ForwardDynamics(q, dq, tau)
13
14%Evaluate the mass matrix
15Robot.MassMatrix(q)