Overview
The generated C++ code is organized in classes within the namespace
iit::<robot name>
.
All the vectors and matrices are implemented with types defined in the
iit-rbd
library, which is shipped with the distribution of RobCoGen.
Internally, the Eigen library is used.
The generated code comes with some Doxygen comments, so please use Doxygen to generate further and up-to-date documentation. Changes in the generated code due to new versions of RobCoGen might not be reflected immediately in this pages, whereas Doxygen documentation is more likely to be consistent with the code.
Compiling
A CMake file can be generated along with the source code. In the output folder do the usual CMake procedure (assuming a Unix shell):
mkdir build
cd build
cmake -D EIGEN_ROOT=<path to eigen> ..
make
sudo make install
The install target will copy the header files in
/usr/local/include/iit/robots/<robot_name_lowercase>/...
so that they can be later included in other sources with
#include <iit/robots/<robot_name_lowercase>/...
The shared library is called libiitgen<robot_name_lowercase>.so
and it
is copied in /usr/local/lib
.
Requirements
Libraries that need to be installed in order to build the generated C++ code.
Eigen
If Eigen is not installed in a "standard" directory, make sure to
set the CMake cache variable EIGEN_ROOT
, before running CMake.
The variable must be such that $EIGEN_ROOT/Eigen/Dense/
is a valid path.
The cache variable defaults to an environment variable with the same name.
The iit::rbd
headers
The iit_rbd
library is a set of header files with common functionality
required by the generated C++. The library is included in the distribution of
RobCoGen. Please install the iit_rbd
headers in your system include path
(the library includes a trivial install.sh
script, for Linux distributions).
Please generate the Doxygen documentation from the source code for more information.
Using the code
Kinematics
Coordinate transforms and Jacobians are public members of container classes. So, for instance
#include <iit/robots/fancy/declarations.h>
#include <iit/robots/fancy/transforms.h>
iit::Fancy::MotionTransforms xm;
iit::Fancy::JointState q;
q = ... // set the joint status
std::cout << xm.fr_link2_X_fr_link3(q) << std::endl;
The previous example also demonstrates the use of operator(const JointState&)
.
As one may expect, the operator actually performs
the computations required to update the content of the matrix with the given
joint status. This procedure is optimized in that only the non-constant elements
of the matrix are recomputed, and the trigonometric functions are computed only
once for each update.
Dynamics
All the dynamics related classes are inside the namespace dyn
, nested in the
robot namespace (actually the name of this namespace can be changed in the
configuration file related to C++).
Dynamics algorithms are wrapped inside dedicated classes with a simple interface.
So far, such classes are ForwardDynamics
, InverseDynamics
and JSIM
(the
Joint-Space Inertia Matrix). Other classes include the InertiaProperties
which is just a container of all the inertia properties of the links of the
robot.
The constructor of the classes wrapping a dynamics algorithm usually requires an instance of the inertia properties as well as an instance of the coordinate transforms container (see the previous section about Kinematics). Here is an example, which refers again to the robot Fancy:
#include <iit/robots/fancy/declarations.h>
#include <iit/robots/fancy/transforms.h>
#include <iit/robots/fancy/inertia_properties.h>
#include <iit/robots/fancy/inverse_dynamics.h>
using namespace iit::Fancy;
// [...]
JointState q, qd, qdd, tau;
// [...]
MotionTransforms transforms;
dyn::InertiaProperties inertias;
dyn::InverseDynamics invdyn(inertias, transforms);
invdyn.id(tau, q, qd, qdd); // compute the inverse-dynamics joint forces
Parameteric robots
The generated classes InertiaProperties
, XXXTransforms
and Jacobians
have a method called updateParameters(..)
which takes a constant reference
to a container of parameter values (a struct
). In case of a
parametric robot model, this container is non-empty,
and defines a field for each model parameter.
It is the responsibility of the user's program to call updateParameters(..)
whenever needed, passing whatever desired values. All the transforms and
Jacobians will not be refreshed right away, but any following use of
operator(const JointState&)
(see above) will use the new parameters. On the
other hand, InertiaProperties
will update its data as soon as it receives
new parameters.
Warning: the parametrization feature of RobCoGen is not mature yet. For
example, the tool lacks a mechanism to specify in the robot model the initial,
default value of the parameters. However, the constructor of InertiaProperties
relies on such initial values. Therefore, the user must modify the generated
dynamics_parameters.h
with appropriate initial values (see the comments in the
code).
Versions before
Two additional headers are generated in case of a
parametric robot model:
0.5.0
kinematics_parameters.h
and dynamics_parameters.h
. These headers define
some data types to hold the values of the robot parameters as well as two
abstract interfaces declaring getter methods for the same parameters.
The figure below illustrates the role of such interfaces and also shows how the class of a generic dynamics algorithm fits the picture.
Basically, the class containing the inertia properties and the
classes containing the coordinate transform are generated with an
additional dependency on the aforementioned interfaces (in the form of one more
argument for the constructor). An additional member function update_parameters()
forces them to fetch new parameter values, by querying the getters interface.
For maximum flexibility, it is the user responsibility to provide a concrete implementation of the interfaces and use it when constructing the other objects. RobCoGen does not impose any strategy for the resolution of the parameters to actual values.
For more information please refer directly to the generated code and to its Doxygen documentation.
Automatic Differentiation
Starting from version 0.5.1, the C++ code generated by RobCoGen uses a custom
Scalar
type, which makes the code suitable for
automatic differentiation tools based on operator overloading.
At the moment, Scalar
is defined by a typedef
(defaulting to double
)
and it is not a template parameter, thus it is not possible to have multiple
instances of the generated code with different scalar types, at the same time.
This will probably change in future releases. Nonetheless, it is possible to
change the scalar type consistently across all the generated code.
Version 0.4ad.0
Version 0.4ad.0 of RobCoGen was developed primarily to experiment with automatic differentiation, and it generates fully templated code. However, it is a fork of an old baseline and lacks some of the fixes of main stream releases 0.5.x.CppAD
Parametrizing the scalar type is unfortunately only necessary but not sufficient to use an AD tool, as some additional definitions (i.e. type traits) are required. RobCoGen natively supports CppAD by providing the necessary traits specifically for the CppAD scalar types.
To change the scalar type to, say, the CppAD double, edit the generated
rbd_types.h
file and add this include:
#include <iit/robcogen/scalar/cppad.h>
(this header is installed with the iit-rbd
library). Then,
replace the line
typedef typename iit::rbd::DoubleTraits ScalarTraits;
with
typedef typename iit::robcogen::CppADDoubleTraits ScalarTraits;
and then recompile. Of course, having CppAD installed in your system is a prerequisite.