Overview
RobCoGen generates functions without any external dependency.
Functions in the form initXXX()
return the initial value of some quantity,
like the coordinate transforms or the Jacobian matrices. Functions named
updateXXXX()
usually take the return value of the initialization function
plus the appropriate joint-status vectors.
For example:
xm = initMotionTransforms();
q = rand(dofs,1);
xm = updateMotionTransforms(xm, q);
xm.fr_link2_X_fr_link3; % this is an updated 6x6 coordinate transform
q = rand(dofs,1);
xm = updateMotionTransforms(xm, q);
xm.fr_link2_X_fr_link3; % it is now different, in general
Another example:
ip = inertiaProperties(); %
xm = initMotionTransforms(); % call these functions once
q = rand(dofs,1);
qd = rand(dofs,1);
qdd = rand(dofs,1);
xm = updateMotionTransforms(xm, q);
tau = inverseDynamics(ip, xm, qd, qdd); % inverse dynamics joint forces
qdd = rand(dofs,1);
tau = inverseDynamics(ip, xm, qd, qdd); % different forces
Constant folding
If the code was generated after disabling constant-folding, then the examples above would not work. In that case, use something like this:
kk = modelConstants();
xm = initMotionTransforms( kk );
ip = inertiaProperties( kk );
% ...
xm = updateMotionTransforms( xm, q, [], kk );
Therefore, at the moment, constant-folding affects the signature of some of the generated functions.
Parameteric robots
In case of a parametric robot model, one more argument with the actual value of the parameters must be supplied to some functions. This argument must be a struct whose fields are named as the parameters in the robot model.
The following example assumes that the mass of two robot links is a parameter;
l1_mass
and l2_mass
are the identifiers used in the input robot model (the
.kindsl
file):
pp.l1_mass = 1;
pp.l2_mass = 1.5;
kk = modelConstants();
ip = inertiaProperties( kk, pp);
Warning: Octave code does not implement any particular check on varying inertia properties. That means, for example, that if the user parametrizes only the mass of a link and not its tensor, changing the mass alone effectively corresponds to changing the dimensions of the rigid body.
Kinematics parameters are further divided into two categories, lengths and angles:
kk = modelConstants();
xh = initHomogeneousTransforms( kk );
q = rand(dofs,1);
pp.angles.jB_rx = pi/2; % e.g. the x-rotation of the reference frame of joint B
pp.lengths.jC_ty = 0.35; % e.g. y-coordinate of the reference frame of joint C
xh = updateHomogeneousTransforms(xh, q, pp, kk);