Building a robot

Object Factory

A robot model is handled using the class dynamicRobot, and it is build using the following components:

A humanoid robot (humanoidDynamicRobot) is a particular robot which has in addition the following components:

All those components are created using an object factory. The class ObjectFactory provides such a factory.

Building a humanoid robot

Creating an empty humanoid robot is therefore very simple:

dynamicsJRLJapan::ObjectFactory robotDynamicsObjectConstructor; 
CjrlHumanoidDynamicRobot * aHDR = robotDynamicsObjectConstructor.createHumanoidDynamicRobot();

Building a revolute joint

The same way a joint can be created by specifying the pose of the joint when the robot is at state $ {\bf x} = [{\bf r} \; {\bf q} \; \dot{\bf r} \; \dot{\bf q} \; \ddot{\bf r} \; \ddot{\bf q}]= [{\bf 0} \; {\bf 0} \; {\bf 0} \; {\bf 0} \; {\bf 0} \; {\bf 0}]$. Therefore if the first joint is at the origin of the reference frame, the following code snippet can be used:

matrix4d pose;
MAL_S4x4_MATRIX_SET_IDENTITY(pose);

// Create Joint 1
CjrlJoint* j1=0;
j1 = anObjectFactory->createJointRotation(pose);

IMPORTANT: It is assumed that the revolute joint axis is aligned with the $x$-axis of its own frame. This normalization is very similar to the one of Davit-Hartenberg, and is compatible with KineoWorks. The position of the joint and the kinematic tree specified below allow the library to derive all the needed parameters automatically.

Building a revolute joint

The same way a body can be build

// Create Link 1
CjrlBody* l1=0;
l1= anObjectFactory->createBody();

The body mass is specified with:

l1->mass(m_SetOfParameters.m[0]);

The inertia matrix can be specified using:

matrix3d I;
MAL_S3x3_MATRIX_SET_IDENTITY(I);
l1->inertiaMatrix(I);

Finally the center of mass for the body l1 is written:

vector3d lc ;
lc(0) = 0.0;
lc(1) = 0.0;
lc(2) = 0.25;
l1->localCenterOfMass(lc);

A body is related with the joint which is the parent of all the other joints on the body. It is specified with:

// Relate joint1 and link1
j1->setLinkedBody(*l1);

Specifying the kinematic tree

The library handles robots as kinematic trees. Therefore each joint has a father or is the root of the robot kinematic tree.

Specifying the root

To specify the root of the kinematic for the humanoid robot created above:

// Joint 1 is root of the tree.
aHDR->rootJoint(*j1);

Adding a child in the kinematic chain

A joint is set as the son of another joint with:

CjrlJoint* j2=0;
j2 = anObjectFactory->createJointRotation(pose);
j1->addChildJoint(*j2);

Initialization

In order to compute quantities, it is important to initialize the internal structure of the library by calling the following method:

aHDR->initialize();