- The generated Octave code has no external dependencies
- Robot data and solvers are wrapped in handle classes or pure functions
- The source files are created in the namespace (a "plus folder")
rcg2, although this is configurable
Basic API is best illustrated by an example. This code is taken from an init function which is also generated, to help the user setting up the workspace:
robot.mic = rcg2.ModelInertiaConstants();
robot.mip = rcg2.ModelInertiaParameters();
robot.mgc = rcg2.ModelGeometryConstants();
robot.mgp = rcg2.ModelGeometryParameters();
% Container of the inertial properties
robot.ip = rcg2.InertiaProperties(robot.mic, robot.mip);
% Container of the spatial motion vectors coordinate transforms
robot.xm = rcg2.MotionTransforms(robot.mgc, robot.mgp);
% Computation of composite inertias and the JSIM
robot.jsim = rcg2.CompositeInertia(robot.ip, robot.xm);
This snippet runs the inverse dynamics solver (for a fixed base robot):
dof = 5; % depends on your model
q = rand(dof,1);
qd = rand(dof,1);
qdd = rand(dof,1);
robot.xm.updateAll(q); % forward kinematics on the full tree
tau = rcg2.inverseDynamics(robot.ip, robot.xm, qd, qdd);
Parameteric robots
In case of a parametric robot model, the API does not change, and only the internals of the containers for the inertial properties and the coordinate transforms are affected.
The following refers to the sample robot model "Fancy" included in the source package of RobCoGen, whose first link has parametric mass:
robot = rcg2.init();
display( robot.ip.link1.mass );
params = rcg2.ModelInertiaParameters();
params.m1 = 2;
robot.ip.updateParameters(params);
display( robot.ip.link1.mass );
Any such change in the inertial or geometrical properties of the robot will be reflected in the solvers' output, because the container is either passed as an argument, or because a handle to it is stored in the solver's class.
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.