Compiling

A CMake file is generated along with the source code:

mkdir build
cd build
cmake <path to gen code>
make
sudo make install

The install target will copy the header files in .../<robot_name_lowercase>/rcg2/... so that they can be later included in other sources with

#include <robot_name_lowercase>/rcg2/...

A shared library called lib<robot_name_lowercase>rcg2.so is built and installed in a system folder.

Requirements

In order to build the generated C++ code, you will need

Using the code

Kinematics

Coordinate transforms are public members of a container class. So, for instance

#include <fancy/rcg2/declarations.h>
#include <fancy/rcg2/transforms.h>
#include <fancy/rcg2/rbd_types.h>

int main()
{
    namespace robot = fancy::rcg2;

    robot::Transforms xt;
    robot::JointState q;
    q.setZero();
    xt.update(q);  // update all the transforms in the container

    robot::Vector3 vh;

    // Take a parent-link transform ..
    //   .. use it as an Homogeneous coordinates transform ('XH')..
    xt.m_link2_X_link1. link2_XH_link1() * vh;
    xt.m_link2_X_link1. link1_XH_link2() * vh; // the opposite polarity

    //   .. or as a spatial vector Motion transform ('XM')
    robot::Velocity vm;
    xt.m_link2_X_link1. link2_XM_link1() * vm;

    // Also the individual transforms can be updated with the joint state:
    xt.m_link4_X_link3(q);

    return 0;
}

This example demonstrates:

As one may expect, the update() and the operator() actually compute the coefficients of the matrix according to the given joint state values. 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

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 <fancy/rcg2/declarations.h>
#include <fancy/rcg2/transforms.h>
#include <fancy/rcg2/inertia_properties.h>
#include <fancy/rcg2/inverse_dynamics.h>

int main()
{
    using namespace fancy::rcg2;

    Transforms xt;
    InertiaProperties ip;
    JointState q, qd, qdd, tau;

    InverseDynamics solver(ip, xt);
    solver.id(q, qd, qdd, tau);
    return 0;
}

Parametric robots

See this section about parametric models.

The generated classes for the inertial properties and for the coordinate transforms, will have a method called updateParameters(..) to pass in new values.

The transforms will not be refreshed right away, but any following use of operator(const JointState&) (see above) will then use the new parameters. On the other hand, InertiaProperties updates its data as soon as it receives new parameters.

Warning: the KinDSL robot model format allows to specify the initial default value for the parameters. However, such a value is optional. However, the constructor of InertiaProperties relies on such initial values. Therefore, the user must modify the generated struct for the parameters with appropriate initial values (see the comments in the code), if these are not available in the model.

Automatic Differentiation

The C++ code generated by RobCoGen is generic with respect to the scalar type, by means of a simple, unique typedef. Alternatively, it is possible to generate actual templated code parametric on the scalar type, in place of regular code — use the --template swich.

In both cases, it means the code is suitable for automatic differentiation tools based on operator overloading.

Example on changing the scalar

In the case of non-templated code, changing the scalar type requires to edit the generated rbd_types.h file. This is a sample diff file for the code generated for the sample robot model:


diff --git a/sample/fancy/gen/cpp/rbd_types.h b/sample/fancy/gen/cpp/rbd_types.h
index 72bb831..e1f2891 100644
--- a/sample/fancy/gen/cpp/rbd_types.h
+++ b/sample/fancy/gen/cpp/rbd_types.h
@@ -4,11 +4,12 @@
 #include <iit/rbd/rbd.h>
 #include <iit/rbd/scalar_traits.h>
 #include <iit/rbd/InertiaMatrix.h>
+#include <some other header with your type>
 
 namespace fancy {
 namespace rcg2 {
 
-typedef typename iit::rbd::DoubleTraits ScalarTraits;
+typedef typename CustomTraitsYouHaveToDefine ScalarTraits;
 typedef typename ScalarTraits::Scalar Scalar;
 
 typedef iit::rbd::Core<Scalar> TypesGen;
Non-literal types In case you want to use a scalar type that is not literal, then you must use the --no-constexpr switch when generating the code.

CppAD

Parametrizing the scalar type is unfortunately only necessary but not sufficient to use an AD tool; some additional definitions (i.e. type traits) are required. RobCoGen natively supports CppAD by providing the necessary specific type traits. See here.

Of course, you must have CppAD installed in your system.

Diff file

diff --git a/sample/fancy/gen/cpp/rbd_types.h b/sample/fancy/gen/cpp/rbd_types.h
index 72bb831..e1f2891 100644
--- a/sample/fancy/gen/cpp/rbd_types.h
+++ b/sample/fancy/gen/cpp/rbd_types.h
@@ -4,11 +4,12 @@
 #include <iit/rbd/rbd.h>
 #include <iit/rbd/scalar_traits.h>
 #include <iit/rbd/InertiaMatrix.h>
+#include <iit/robcogen/scalar/cppad.h>
 
 namespace fancy {
 namespace rcg2 {
 
-typedef typename iit::rbd::DoubleTraits ScalarTraits;
+typedef typename iit::robcogen::CppADDoubleTraits ScalarTraits;
 typedef typename ScalarTraits::Scalar Scalar;
 
 typedef iit::rbd::Core<Scalar> TypesGen;

API docs

The generated code normally includes Doxygen comments. 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.