Rigid Body Dynamics Library
Addon: rbdl_luamodel

Lua Models

The Addon LuaModel allows to load Models that are specified as Lua scripts. Lua is an open-source light-weight scripting language (http://www.lua.org). This addon is not enabled by default and one has to enable it by setting BUILD_ADDON_LUAMODEL to true in when configuring the RBDL with CMake.

This addon comes with a standalone utility that can show various information of a lua model such as degree of freedom overview or model hierarchy. It is located in addons/luamodel/rbdl_luamodel_test. Use the -h switch to see available options.

Note: this addon is not even remotely as thoroughly tested as the RBDL itself so please use it with some suspicion.

Format Overview

Models have to be specified as a specially formatted Lua table which must be returned by the script, i.e. if the model is specified in the table "model = { ... }" the script has to return this when executed. Within the returned table, rbdl_luamodel goes through the table "frames" and builds the model from the individual Frame Information Tables (see further down for more information about those).

A valid file could look like this:

model = {
frames = {
{
<frame 1 information table>
},
{
<frame 2 information table>
}
}
}
return model

Apart from the frames you can also specify gravity in the model file.

Example:

model = {
gravity = {0., 0., -9.81}
frames = {
...
}
}

Finally, several constraint sets can be defined for the model.

Example:

model = {
constraint_sets = {
constraint_set_1_name = {
{
...
},
{
...
},
},
constraint_set_2_name = {
...
},
},
}
Note
The table frames must contain all Frame Information Tables as a list and individual tables must not be specified with a key, i.e.
frames = {
some_frame = {
...
},
{
..
}
}
is not possible as Lua does not retain the order of the individual frames when an explicit key is specified.

Frame Information Table

The Frame Information Table is searched for values needed to call Model::AddBody(). The following fields are used by rbdl_luamodel (everything else is ignored):

name (required, type: string):
Name of the body that is being added. This name must be unique.
parent (required, type: string):
If the value is "ROOT" the parent frame of this body is assumed to be the base coordinate system, otherwise it must be the exact same string as was used for the "name"-field of the parent frame.
body (optional, type: table)
Specification of the dynamical parameters of the body. It uses the values (if existing):
mass (scalar value, default 1.),
com (3-d vector, default: (0., 0., 0.))
inertia (3x3 matrix, default: identity matrix)
to create a RigidBodyDynamics::Body.
joint (optional, type: table)
Specifies the type of joint, fixed or up to 6 degrees of freedom. Each entry in the joint table should be a 6-d that defines the motion subspace of a single degree of freedom.
Default joint type is a fixed joint that attaches the body rigidly to its parent.
3-DoF joints are described by using strings. The following 3-DoF joints are available:
  • "JointTypeSpherical": for singularity-free spherical joints
  • "JointTypeEulerZYX": Euler ZYX joint
  • "JointTypeEulerXYZ": Euler XYZ joint
  • "JointTypeEulerYXZ": Euler YXZ joint
  • "JointTypeTranslationXYZ": Free translational joint
Examples:
joint_fixed = {}
joint_translate_x = { {0., 0., 0., 1., 0., 0.} }
joint_translate_xy = {
{0., 0., 0., 1., 0., 0.},
{0., 0., 0., 0., 1., 0.}
}
joint_rotate_zyx = {
{0., 0., 1., 0., 0., 0.},
{0., 1., 0., 0., 0., 0.},
{1., 0., 0., 0., 0., 0.},
}
joint_rotate_euler_zyx = { "JointTypeEulerZYX" }
joint_frame (optional, type: table)
Specifies the origin of the joint in the frame of the parent. It uses the values (if existing):
r (3-d vector, default: (0., 0., 0.))
E (3x3 matrix, default: identity matrix)
for which r is the translation and E the rotation of the joint frame

Constraint Information Table

The Constraint Information Table is searched for values needed to call ConstraintSet::AddContactConstraint() or ConstraintSet::AddLoopConstraint(). The employed fields are defined as follows. Please note that different fields may be used for different constraint types.

constraint_type (required, type: string)
Specifies the type of constraints, either 'contact' or 'loop', other values will cause a failure while reading the file.
name (optional, type: string)
Specifies a name for the constraint.

The following fields are used exclusively for contact constraints:

body (required, type: string)
The name of the body involved in the constraint.
point(optional, type: table)
The position of the contact point in body coordinates. Defaults to (0, 0, 0).
normal(optional, type: table)
The normal along which the constraint acts in world coordinates. Defaults to (0, 0, 0).
normal_acceleration(optional, type: number)
The normal acceleration along the constraint axis. Defaults to 0.

The following fields are used exclusively for loop constraints:

predecessor_body (required, type: string)
The name of the predecessor body involved in the constraint.
successor_body (required, type: string)
The name of the successor body involved in the constraint.
predecessor_transform (optional, type: table)
The transform of the predecessor constrained frame with respect to the predecessor body frame. Defaults to the identity transform.
sucessor_transform (optional, type: table)
The transform of the sucessor constrained frame with respect to the sucessor body frame. Defaults to the identity transform.
axis (optional, type: table)
The 6d spatial axis along which the constraint acts, in coordinates relative to the predecessor constrained frame. Defaults to (0,0,0,0,0,0).
enable_stabilization(optional, type: bool, default: false)
Whether Baumgarte stabilization should be enabled or not.
stabilization_parameter(optional, type: number)
The stabilization parameter T_stab for the Baumgarte stabilization (see RBDL documentation on how this parameter is used). Defaults to 0.1.

Example

Here is an example of a model:

--[[
-- This is an example model for the RBDL addon luamodel. You need to
-- enable RBDL_BUILD_ADDON_LUAMODEL to be able to use this file.
--]]
print ("This is some output from the model file")
inertia = {
{1.1, 0.1, 0.2},
{0.3, 1.2, 0.4},
{0.5, 0.6, 1.3}
}
pelvis = { mass = 9.3, com = { 1.1, 1.2, 1.3}, inertia = inertia }
thigh = { mass = 4.2, com = { 1.1, 1.2, 1.3}, inertia = inertia }
shank = { mass = 4.1, com = { 1.1, 1.2, 1.3}, inertia = inertia }
foot = { mass = 1.1, com = { 1.1, 1.2, 1.3}, inertia = inertia }
bodies = {
pelvis = pelvis,
thigh_right = thigh,
shank_right = shank,
thigh_left = thigh,
shank_left = shank
}
joints = {
freeflyer = {
{ 0., 0., 0., 1., 0., 0.},
{ 0., 0., 0., 0., 1., 0.},
{ 0., 0., 0., 0., 0., 1.},
{ 0., 0., 1., 0., 0., 0.},
{ 0., 1., 0., 0., 0., 0.},
{ 1., 0., 0., 0., 0., 0.}
},
spherical_zyx = {
{ 0., 0., 1., 0., 0., 0.},
{ 0., 1., 0., 0., 0., 0.},
{ 1., 0., 0., 0., 0., 0.}
},
rotational_y = {
{ 0., 1., 0., 0., 0., 0.}
},
fixed = {}
}
model = {
gravity = {0., 0., -9.81},
frames = {
{
name = "pelvis",
parent = "ROOT",
body = bodies.pelvis,
joint = joints.freeflyer,
},
{
name = "thigh_right",
parent = "pelvis",
body = bodies.thigh_right,
joint = joints.spherical_zyx,
joint_frame = {
r = {0.0, -0.15, 0.},
E = {
{1., 0., 0.},
{0., 1., 0.},
{0., 0., 0.}
}
}
},
{
name = "shank_right",
parent = "thigh_right",
body = bodies.thigh_right,
joint = joints.rotational_y,
joint_frame = {
r = {0.0, 0., -0.42},
},
},
{
name = "foot_right",
parent = "shank_right",
body = bodies.thigh_right,
joint_frame = {
r = {0.0, 0., -0.41}
},
},
{
name = "thigh_left",
parent = "pelvis",
body = bodies.thigh_left,
joint = joints.spherical_zyx,
joint_frame = {
r = {0.0, 0.15, 0.},
E = {
{1., 0., 0.},
{0., 1., 0.},
{0., 0., 0.}
}
}
},
{
name = "shank_left",
parent = "thigh_left",
body = bodies.thigh_left,
joint = joints.rotational_y,
joint_frame = {
r = {0.0, 0., -0.42},
},
},
{
name = "foot_left",
parent = "shank_left",
body = bodies.thigh_left,
joint_frame = {
r = {0.0, 0., -0.41},
},
},
}
}
return model

Example with constraints

Here is an example of a model including constraints:

--[[
-- This is an example model for the RBDL addon luamodel. You need to
-- enable RBDL_BUILD_ADDON_LUAMODEL to be able to use this file.
--]]
m1 = 2
l1 = 2
r1 = 0.2
Izz1 = m1 * l1 * l1 / 3
m2 = 2
l2 = 2
r2 = 0.2
Izz2 = m2 * l2 * l2 / 3
bodies = {
virtual = {
mass = 0,
com = {0, 0, 0},
inertia = {
{0, 0, 0},
{0, 0, 0},
{0, 0, 0},
},
},
link1 = {
mass = m1,
com = {l1/2, 0, 0},
inertia = {
{1, 0, 0},
{0, 1, 0},
{0, 0, Izz1},
},
},
link2 = {
mass = m2,
com = {l2/2, 0, 0},
inertia = {
{1, 0, 0},
{0, 1, 0},
{0, 0, Izz2},
},
},
}
joints = {
revZ = {
{0, 0, 1, 0, 0, 0},
},
trnXYZ = {
{0, 0, 0, 1, 0, 0},
{0, 0, 0, 0, 1, 0},
{0, 0, 0, 0, 0, 1},
},
}
model = {
gravity = {0, 0, 0},
configuration = {
axis_front = { 1., 0., 0.},
axis_right = { 0., -1., 0.},
axis_up = { 0., 0., 1.},
},
frames = {
{
name = 'base',
parent = 'ROOT',
body = bodies.virtual,
joint = joints.trnXYZ,
},
{
name = 'l11',
parent = 'base',
body = bodies.link1,
joint = joints.revZ,
},
{
name = 'l12',
parent = 'l11',
body = bodies.link2,
joint = joints.revZ,
joint_frame = {
r = {l1, 0, 0},
},
},
{
name = 'l21',
parent = 'base',
body = bodies.link1,
joint = joints.revZ,
},
{
name = 'l22',
parent = 'l21',
body = bodies.link2,
joint = joints.revZ,
joint_frame = {
r = {l1, 0, 0},
},
},
},
constraint_sets = {
loop_constraints = {
{
constraint_type = 'loop',
predecessor_body = 'l12',
successor_body = 'l22',
predecessor_transform = {
E = {
{1, 0, 0},
{0, 1, 0},
{0, 0, 1},
},
r = {l2, 0, 0},
},
successor_transform = {
E = {
{1, 0, 0},
{0, 1, 0},
{0, 0, 1},
},
r = {0, 0, 0},
},
axis = {0, 0, 0, 1, 0, 0},
stabilization_parameter = 0.1,
name = 'linkTX',
},
{
constraint_type = 'loop',
predecessor_body = 'l12',
successor_body = 'l22',
predecessor_transform = {
E = {
{1, 0, 0},
{0, 1, 0},
{0, 0, 1},
},
r = {l2, 0, 0},
},
successor_transform = {
E = {
{1, 0, 0},
{0, 1, 0},
{0, 0, 1},
},
r = {0, 0, 0},
},
axis = {0, 0, 0, 0, 1, 0},
stabilization_parameter = 0.1,
name = 'linkTY',
},
},
all_constraints = {
{
constraint_type = 'contact',
body = 'base',
point = {0, 0, 0},
normal = {1, 0, 0},
name = 'baseTX',
normal_acceleration = 0,
},
{
constraint_type = 'contact',
body = 'base',
normal = {0, 1, 0},
name = 'baseTY',
},
{
constraint_type = 'contact',
body = 'base',
normal = {0, 0, 1},
name = 'baseTZ',
},
{
constraint_type = 'loop',
predecessor_body = 'l12',
successor_body = 'l22',
predecessor_transform = {
E = {
{1, 0, 0},
{0, 1, 0},
{0, 0, 1},
},
r = {l2, 0, 0},
},
successor_transform = {
E = {
{1, 0, 0},
{0, 1, 0},
{0, 0, 1},
},
r = {0, 0, 0},
},
axis = {0, 0, 0, 1, 0, 0},
stabilization_parameter = 0.1,
name = 'linkTX',
},
{
constraint_type = 'loop',
predecessor_body = 'l12',
successor_body = 'l22',
predecessor_transform = {
E = {
{1, 0, 0},
{0, 1, 0},
{0, 0, 1},
},
r = {l2, 0, 0},
},
successor_transform = {
E = {
{1, 0, 0},
{0, 1, 0},
{0, 0, 1},
},
r = {0, 0, 0},
},
axis = {0, 0, 0, 0, 1, 0},
stabilization_parameter = 0.1,
name = 'linkTY',
},
},
},
}
return model