Skip to content

The AMBF Description Format

Adnan Munawar edited this page Apr 17, 2019 · 8 revisions

The AMBF Description Format uses YAML to specify Bodies, Joints, Lights, Cameras and Sensors. The format has been developed to make it easier for users to develop complex interconnected robots and mechanisms with fully customizable dynamic parameters while keeping the syntax easy and human readable. On one hand, this format has been inspired by URDF (Unified Robot Description Format) and SDF (Simulation Description Format) while on the other it's has been developed to address the key limitations and complexities of both URDF and SDF. The first and foremost goal of the format is the choice or markup language (YAML). In our experience, YAML is much easier to read and modify.

The Anatomy of the AMBF Format

In general, the current version 0.1 of the AMBF Format can specify the following objects

  • Rigid Bodies (Kinematic and Dynamic)
    • Cartesian Controllers for these Bodies
  • Soft Bodies
  • Joints
    • Types of Joints
      • Prismatic or Slider Joints
      • Revolute, Hinge or Continous Joints
      • Point To Point or P2P Constraints
      • Fixed Joints
      • Linear Springs
      • Torsion or Angular Springs
    • Joint Controllers
  • Multiple Cameras as Viewports
  • Lights
  • Sensors
    • Types of Sensors
      • Proximity Sensors (using Ray Tracing)

Delving Deeper into the AMBF Format

We can start by examining a very basic example of a multibody defined by the AMBF Format. This multibody Consists of two Rigid Bodies and a Joint.

bodies: [BodyA, BodyB]
joints: [JointA]
high resolution path: ./high_res/
low resolution path: ./low_res/
namespace: /ambf/env/

BodyA:
  name: base_plate
  mesh: base_plate.STL
  mass: 5.0
  location:
    orientation: {p: -0.0, r: 0.0, y: 0.0}
    position: {x: 1.0, y: 0.0, z: -1.0}
  color: orange_tomato

BodyB:
  name: latch
  mesh: latch.STL
  mass: 0.3
  location:
    orientation: {p: 1.571, r: -0.0, y: 0.0}
    position: {x: 1.0, y: -0.85, z: -1.0}
  inertial offset:
    orientation: {p: 0, r: 0, y: 0}
    position: {x: 0.0, y: -0.162, z: -0.003}
  color: red_crimson

JointA:
  name: hinge_AB
  parent: BodyA
  child: BodyB
  parent axis: {x: 1.0, y: 0.0, z: 0.0}
  parent pivot: {x: 0.0, y: -0.85, z: 0.0}
  child axis: {x: 0.0, y: 0.0, z: 1.0}
  child pivot: {x: 0.0, y: 0.0, z: 0.0}
  type: revolute

Let's start examining the different subsections of this config file. We can call each section a data-block. Towards this end, this config file can be broken down into four data-blocks which are explained below

  1. Header or Global Data-Block
  2. BodyA Data-Block
  3. BodyB Data-Block
  4. JointA Data-Block

The whole concept of AMBF revolves around the asynchronous concept of data-blocks. The data blocks can potentially be split into different config files and should work independently of each other even though they can be related to each other by constraints. More on this later.

The Header Data-Block

Let's inspect the Header Data-Block which is redefined in the following snippet.

bodies: [BodyA, BodyB]
joints: [JointA]
high resolution path: ./high_res/
low resolution path: ./low_res/
namespace: /ambf/env/

The Header Data-Block is the entry point of all Multibody config files and is parsed first and foremost. It contains global variables that can be used to save editing parameters locally and thus improving the readability of the remaining config file. We shall examine the context one by one.

  • bodies:

This bodies field is an associative array that contains the names of bodies in the config file that need to be loaded. The config file can have many bodies and not all bodies might require loading so they can be conveniently removed from the bodies array. This is useful for debugging and making sure individual sub-components can be tested in isolation.

  • joints:

Similar to the bodies field, joint is an associative array as well that contains the names of joints in the config file. Only the joints defined in this array are loaded whereas the config file itself can have many additional joints defined.

  • high resolution path:

The high resolution path is the folder path to the location of high-resolution visual meshes. This path can be either absolute or relative (based on the location of the config file).

  • low resolution path:

The low resolution path is the folder path to the location of low-resolution collision meshes. This path can be either absolute or relative (based on the location of the config file).

  • namespace:

The namespace is appended to the start of all bodies and joints in the config file. This helps in defining namespaces for different robots/mechanisms as well as avoiding naming conflicts between the identical body names in different config files.

There are additional optional parameters that can be set the Header Data-Block that are discussed later.

The Body Data-Block

The Body Data-Block, as the name indicates, is used to define a body. The parameters defined in the data-block are explained below.

  • name

This name is the set to specify the topic name for this body. This name is prepended with the namespace parameter.

  • mesh

This specifies the mesh file for this body. If the mesh is empty, this body shall be treated without collision. The mesh name is combined with the high resolution path to get the visual mesh and with low resolution path to get the collision mesh.

  • mass: 0.3

This is the mass of the body. If the mass is set to 0, the body is kinematic.

  • location:

This is the initial location of the body in the world frame. This location will of course change as the simulation goes on and the body interacts with other objects in the simulation

  • inertia:

This is the principal inertia of the object. If not specified. It is computed internally by utilizing the collision mesh's geometry

  • inertial offset:

This is the inertial offset from the mesh origin. This helps in giving the user the ability to define a mesh's origin at a convenient location without having to place it at the body's center of mass. The inertial offset can then be added. If the inertial offset if not specified, it is computed internally by the AMBF Framework based on the collision mesh's geometry.

  • color:

There are three different ways of specifying the color for a body. You can either use the color key and then specify a color from the ambf/ambf_models/descriptions/color/colors.yaml

  • color rgba:

Instead of picking a color name as in the field above. You can specify the raw color value using:

color rgba: {r: 0.5, g: 0.5, b: 0.5, a: 1.0}.
  • color components:

For even greater control of color. You can use the color components key:

color components:
    ambient: {level: 1.0}
    diffuse: {r: 0.955, g: 0.4814, b: 0.3072}
    specular: {r: 1.0, g: 1.0, b: 1.0}
    transparency: 1.0

The Joint Data-Block

The items in the joint data block are explained below.

  • name:

  • parent:

  • child:

  • parent axis:

  • parent pivot:

  • child axis:

  • child pivot:

  • joint limits:

  • controller:

  • type:

  • offset:

Clone this wiki locally