4 Main Data Types and Data Files
There are three main types of entities in GraspIt!. The first one is a
Body, which is characterized by having some geometry (a
shape), a transform (its position) and material properties (such as
friction coefficient). The second one is a Robot, which is
comprised of multiple Bodies (such as its links) as well as
information on kinematics, actuation, etc. Finally, a World
groups together instances of the other classes and places them in the
correct positions relative to each other. Each of these classes has
its own data file format, which GraspIt! can load (but, with the
exception of the World, not save to). We will detail all of them in
this section.
There are two main types of bodies that exist in a GraspIt! simulation
world: static bodies (also known as obstacles) and dynamic bodies
(such as robot links and objects). Static objects do not participate
in the dynamics, but provide collision surfaces for dynamic
bodies. Note that this difference mainly applies when the dynamic
engine is being used; otherwise, dynamic bodies can be used as static
bodies as well. This document describes what makes up a basic GraspIt!
body, and what a dynamic body adds to that definition.
Every GraspIt! body has the following data associated with it:
- Geometry:
- this describes the shape of the body. It is stored as
an Inventor scene graph, a format similar to VRML. This structure
can contain pure shape nodes such as cubes, spheres, cylinders, and
cones, as well as sets of 2D polygons that define a
surface. Although GraspIt! (through the Inventor scene graph) can
display all of these geometry types, the collision detection system
only works with triangles. When any body is imported to a GraspIt!
world, it is faceted into triangles, and these are used for
detecting collisions and finding contact points. The units in these
files are assumed to be millimeters. Note that the origin of a
body's coordinate system is the origin of its geometry, as loaded
from a file or created by the user. This can be a tricky aspect, as
the origin of a body's geometry is fairly arbitrary. To counter
this, dynamic bodies also use the notion of center of mass,
explained below. However, the origin of a body's coordinate system
is always the origin of it's geometry.
- Material:
- the material affects the amount of friction possible
at contacts on this body. For each pair of materials we define a
coefficient of friction. When the dynamic engine is not used,
GraspIt! uses a static coefficient of friction for all bodies. When
not using dynamics, this coefficient only affects grasp quality
computations, not the relative motion of the bodies. During the
dynamic simulation, the coefficient of friction affects the relative
motion of the bodies in contact. We also use a dynamic coefficient:
if the relative speed at a contact point exceeds a threshold
currently set at 1mm/sec, a kinetic coefficient of friction is used.
- Transform:
- each body keeps track of the 3D position and
orientation of its body frame relative to the GraspIt! world
coordinate system.
- Name:
- a body's name is currently derived from the its filename,
except in the case robot links, which are named using the robot's
name and their kinematic chain and link numbers.
Dynamic bodies also have the following properties:
- Mass:
- this is expressed in grams.
- Center of mass:
- this is a 3D position expressed relative to the
body coordinate system. There are two main uses for this. The first
one is to provide a stable point for grasp quality computations to
use as reference. The second one is to be used as a reference point
for transformation between forces and torques in dynamics. It should
be more stable than the origin of the body's coordinate system,
which is arbitrary.
- Inertia tensor:
- this is the standard 3x3 mass distribution
matrix. It is expressed relative to a coordinate frame that is
aligned with the coordinate system of the body, but positioned at
the center of mass. When stored in a file, it is scaled by 1/mass so
that changes to the mass can be made by changing only the mass value
above.
- Dynamic state:
- two values, q and v, store the current position
and velocity of the body's center of mass relative to world
coordinates. q is expressed as a 7x1 vector: the first three values
are the position, and the last four are the rotation in quaternion
form. v is expressed as a 6x1 vector: the first three values are the
linear velocity of the body, and the last three are the rotational
velocity. When the dynamics updates each body state, the body
transform is also updated. If a body is moved in the static mode,
the position value of the dynamic state is also updated.
Starting from version 2.1, GraspIt! uses an XML format for storing all
of its data. For Bodies, there are two types of information that are
required: the GraspIt! specific information, such as the parameters
shown above, and the geometry itself. Each Body therefore comes with two files:
- an .xml file that contains all the GraspIt! specific
information, as well as a pointer to the file that contains the
actual geometry.
- the geometry file. Currently, there are a few options for the
geometry file:
- VRML format (.wrl), read in directly through
Coin
- Inventor format (.iv), also read in by Coin
- OFF format (.off), read in by our own parser. This
format was added mainly to be able to directly load objects from the
Princeton Shape Benchmark; we have not tested it extensively on
other files that are not part of the PSB.
Here is an example of a typical Body file ($GRASPIT/models/objects/flask.xml):
<?xml version="1.0" ?>
<root>
<material>glass</material>
<mass>300</mass>
<cog>0 0 0</cog>
<inertia_matrix>4853.0 -1.1196 -6.5156 -1.1196 4853.0 47.542 -6.5156 0.0 2357.6</inertia_matrix>
<geometryFile type="Inventor">flask.iv</geometryFile>
</root>
The format is fully XML adherent, you should be able to also read it
in with any XML parser (such as your web browser). This is the list of
tags that GraspIt! will look for in the Body file:
- <geometryFile> - this is the only mandatory tag. It
contains the path to the geometry file, relative to the directory
where the XML file is placed. It requires an additional specifier
type which can be one of the following:
- Inventor - for VRML (.wrl) and Inventor
(.iv) files
- off - for OFF (.off) files
- <material> - can be any of the materials used in
GraspIt!. If it is missing, a generic material with a mid-range
friction coefficient is assumed. The value is a string identifying
the name of the material. Possible values are: frictionless,
plastic, metal, wood, stone, rubber.
- <youngs> - the Young's modulus of the object, in
MPa. This can be used to simulate soft body contacts and compute
contact frictional torque. See the Soft
Fingers section for details. If this is
missing, GraspIt! will assume the body is rigid, and use the more
common rigid contact model instead.
- Dynamic properties:
- <mass> - the mass of the body, in grams.
- <cog> - center of gravity. The value is composed of 3
entries, showing the coordinates of the center of gravity
relative to the origin of the geometry.
- <inertia_matrix> - the 3x3 inertia tensor of the
object, as a list of 9 doubles
- WARNING: if any of the dynamic parameters are missing,
GraspIt! will attempt to compute it automatically based on the
geometry of the object and assuming uniform mass
distribution. This works reasonably well in most cases, but can
also produce spectacular failures. To have complete control over
the dynamic parameters of you Body, it is best to specify them
explicitly in the file.
For more examples, see the body files included with the distribution,
in $GRASPIT/models/objects.
A Robot is made up of multiple links, connected into kinematic
chains. A link is simply a dynamic body, as described above. A Robot
always has a base link (called "palm" for hands) and one or more
kinematic chains attached to it. Each chain is in turn made up of a
succession of links, connected by joints. In order to define a robot,
two things are needed: the Body files for all the links that are part
of the Robot, plus an overall Robot configuration file, which has all
the kinematic information and references the appropriate body files
for the links. Here we describe the structure of the Robot
configuration file.
Robot configuration files can seem daunting at first, and they are a
bit annoying to get used to. However, you can start from one of the
many robots that are included with this distribution, and use it as a
starting block for your own robot that you are trying to
build. Starting in version 2.1, GraspIt! robot files are now stored in
an XML compatible format.
In general, a Robot configuration file contains the following data:
- the palm - this is simply a pointer to the Body file that
contains the palm.
- degrees of freedom - contained in the XML tag
<dof>. We will discuss them in detail below.
- kinematic chains - contained in the XML tag
<chain>. We will discuss them in detail below.
In this example, we will walk through the file for the Robonaut
hand. The first XML tag, <robot>, encloses the entire
contents of the file. It also has a specified property type,
which tells GraspIt! whether this is a generic robot or hand or a
particular subclass of one of those. A hand should use the "Hand"
type. In some cases, if a robot has special features or its own
inverse kinematics algorithm, it is necessary to use a subclass of
these generic types, such as "Barrett", or "Puma560":
<robot type="Robonaut">
... (rest of Robot file)
</robot>
The next item is the filename for the palm link:
<palm>right_palm.xml</palm>
In each robot file, we have a set of degree of freedom tags
<dof>, each describing one DOF of the robot. Note
that a DOF can be connected to one or more joints in the kinematic
chains, this information will be supplied later in the Robot
configuration file. For more details about DOF's and joints in
GraspIt!, see the Joint Coupling and Underactuated Hands
chapter. Also note that the ORDER in which
<dof> tags appear in the file is important: dof's will later be
referenced by their position in this order!
For each DOF, the XML tag contains the following information:
- a type property of the <dof> tag. Its value is a
letter, showing the DOF type. For the Robonaut hand, all DOF's are
of the type "rigid", depicted by the letter "r". This is the most
common type of DOF in GraspIt!. Unless you are building robots with
coupled joints (multiple joints connected to a single DOF), you can
always use this type of DOF.
- all the other properties of the DOF are stored as sub-tags of
the <dof> tag, as listed below.
- <defaultVelocity> - the default velocity for that DOF during an
autograsp operation. This is used to pre-define the "closing" motion
of a hand. For anthropomorphic hands, these pre-defined directions
tell GraspIt! how to move each DOF in order to "autograsp", or how
to "close the hand". This generally means moving the DOF's of the
MCP, PIP and DIP joints in the "flexing" direction, and no movement
for the abduction - adduction DOFs.
- <maxEffort> - the max force the DOF can apply to each joint it
is connected to. The unit is N * 1.0e6 * mm for torques and N *
1.0e6 for forces.
- <Kp> and <Kd> - the Kp and Kv coefficients for a PD force
controller built into the DOF
- <draggerScale> - the visual scale of the dragger that allows the
user to control this DOF through the GraspIt! GUI.
- a number of optional sub-tags, depending on the DOF type. For
the "rigid" DOF, no more sub-tags are needed.
Here's an example <dof> tag from the Robonaut.xml file:
<dof type="r">
<defaultVelocity>1.0</defaultVelocity>
<maxEffort>5.0e+9</maxEffort>
<Kp>1.0e+10</Kp>
<Kd>1.0e+7</Kd>
<draggerScale>10</draggerScale>
</dof>
Each kinematic chain is stored in the tag
chain. This tag has no properties, and can contain
the following sub-tags:
- <transform> - the transform from the origin of the palm (which
is also the origin of the robot) to the base of this chain, which is
where the first joint in the chain is placed. Note that, anywhere in
GraspIt! XML files, a <transform> tag can have an unspecified number
of sub-tags, each containing a translation, a rotation, or both.
- <joint> - a joint in the chain. This tag can contain the
following information:
- the joint type, as a property. This can be either
"Revolute" or "Prismatic"
- the Denavit-Hartenberg (D-H) parameters of this joint, as
sub-tags:
- <d>
- <a>
- <alpha>
- <theta>
- one of the 4 D-H parameters must be connected to a degree
of freedom of the robot. For revolute joints, this will be
<d>. For prismatic joints, this will be <a>. For example, to
show that a revolute joint is connected to the 5th degree of
freedom of the robot, the XML tag will have the form
<d>d5</d>.
- you can also specify a linear relationship between the DOF
value and the joint value. This is done in the form d#*k+c (no
spaces!). For example, to specify that the value of the joint
will be one third of the second DOF value, plus an offset of
30 degrees, the XML tag will have the form:
<d>d2*0.33+30.0</d>
- the other 3 D-H parameters will have fixed values,
specified in their respective XML tag. Example:
<a>46</a>.
- <minValue> - the lower joint limit for this joint
- <maxValue> - the upper joint limit for this joint
- other optional sub-tags are also possible, but they are not
used in this example file, They can contain things like joint
friction coefficients, spring stiffness etc.
- <link> - a link in this chain.
- this tag has a property called "dynamicJointType". This
property tells us how each link is connected to the one
before. It can be one of the following: "Revolute", "Prismatic",
"Universal", "Ball", or "Fixed". Depending on which one is used,
the chain will take some of the joints from the joint list
above, and put them together to create a connection of that
type. For example:
- Revolute: the link is connected to the one before by
through a single revolute joint
- Universal: the link is connected to the one before by two
revolute joints, usually with perpendicular axes
- Ball: the link is connected to the one before by three
revolute joints, usually with perpendicular axes
- the value of the <link> tag is a pointer to the Body file
which contains the link.
Example of a kinematic chain from the Robonaut.xml file:
<chain>
<transform>
<translation>46.183982 -26.490473 5.890768</translation>
<rotationMatrix>0.56107 -0.820276 -0.111118 0.145778 0.230056 -0.962197 0.814831 0.523661 0.248656</rotationMatrix>
</transform>
<joint type="Revolute">
<theta>d0</theta>
<d>0</d>
<a>6.35</a>
<alpha>90</alpha>
<minValue>-60</minValue>
<maxValue>5</maxValue>
</joint>
<joint type="Revolute">
<theta>d1+8.9</theta>
<d>0</d>
<a>46.8376</a>
<alpha>0</alpha>
<minValue>-30</minValue>
<maxValue>85</maxValue>
</joint>
<joint type="Revolute">
<theta>d2</theta>
<d>0</d>
<a>0</a>
<alpha>0</alpha>
<minValue>0</minValue>
<maxValue>75</maxValue>
</joint>
<link dynamicJointType="Revolute">tyoke.xml</link>
<link dynamicJointType="Revolute">thumbphl.xml</link>
<link dynamicJointType="Revolute">thdph1.xml</link>
</chain>
Finally, the Robot file can contain some optional tags. These usually
includes things such as Eigengrasp information, connection to a Flock
of Birds sensor, etc. These are described in more detail in the
dedicated chapters of this manual.
In GraspIt!, robots and bodies populate a simulation world. This
document describes how these elements can be added or deleted from a
world and describes the format of a world file, which stores the
current state of the world.
When GraspIt! begins the world is empty. The user may either load a
previously saved world by choosing File -> Open, or
populate the new world. To import an obstacle (a static body) or an
object (a dynamic body), use File -> Import Obstacle or
File -> Import Object, and then choose the Body file (see
the previous section on bodies). Note that any Body file (regardless
of whether it's meant for a static or dynamic body) can be loaded as
an obstacle (GraspIt! will just ignore the dynamic
parameters). However, when a body file is imported as an Object,
GraspIt! will automatically instantiate it as a dynamic body. It will
also try to find the dynamic parameters in the body file and, if it
can not find them, assign default values. Be aware that the default
values occasionally have unpredictable results.
To import a robot, use File -> Import Robot, open the
correct robot folder, and select the robot configuration (.xml) file.
To delete a body, select it, and then press the <DELETE> key. To
remove a robot, first select the entire robot (by double-clicking one
of the links when the selection tool is active) and press the <DELETE>
key.
Note: newly imported bodies or robots always appear at the world
origin. You can move existing bodies out of the way before importing a
new one. If you do not, than the newly imported body will overlap with
an old one, and you will have to temporarily toggle collisions in
order to move one of them out of the way.
When the user selects "Save" in the file menu, GraspIt! saves the
current world state in an world file using an XML-compatible
format. This file can contain the following tags:
- <obstacle> - a body to be loaded as obstacle. Contains the
following sub-tags:
- <filename> - a pointer to the file containing the body to be
loaded as an obstacle. The path is relative to $GRASPIT.
- <transform> - the position and orientation of the obstacle in
the simulation world. As always, a <transform> tag can contain
multiple sub-tags, each specifying a translation, rotation or
both. Usually, in World files, transforms are specified with a
single sub-tag, of the type <fullTransform>, which contains a
complete transform encoded as a Quaternion.
- <graspableBody> - a body to be loaded as a Graspable Body. It is
identical to the Obstacle tag. The only difference is that GraspIt!
will load the specified Body as a GraspableBody, initialize its
dynamic properties, and make it part of the dynamic computations.
- <robot> - a Robot to be loaded into this world. Contains the
following sub-tags:
- <filename> - a pointer to the Robot XML file. The path is
relative to $GRASPIT.
- <dofValues> - a string containing the saved values of all
degrees of freedom of the robot. Note that this might mean a
single number per DOF, or more information, depending on the DOF
type.
- <transform> - the position and orientation of the Robot in the
world, as described in the Obstacle case.
- <connection> - indicates a connection between two robots. This
means that one Robot is attached to the end of a kinematic chain of
another Robot, such as a hand attached to a robotic arm. Contains
the following sub-tags:
- <parentRobot> - the index of the parent robot in the world,
which is given by the order in which <robot> tags appear in the
World file.
- <parentChain> - the kinematic chain number on the parent robot
that the other robot is attached to.
- <childRobot> - the index of the child robot in the world,
which is given by the order in which <robot> tags appear in the
World file.
- <mountFilename> (optional) - specifies a body that is
optionally used as a mount piece between the two robots.
- <transform> the constant offset transform between the last
link of the parent's kinematic chain and the base link of the
child robot.
- <camera> (optional) - specifies the world position, orientation
and focal point of the virtual camera.
For an example, take a look at the barrettGlassDyn.xml file
supplied with this GraspIt! distribution.
Starting with version 2.1, GraspIt! loads all of its data (Bodies,
Robots and Worlds) from a new, XML-compatible format. The new version
is not backwards-compatible, meaning that the old data files will no
longer work.
To help with the transition we have included a stand-alone converter
that will convert your old data files to the new format. This
converter is included in $GRASPIT/xmlconverter.
You will need to build the converter separately, starting from the Qt
project file xmlconverter.pro. Here are the steps:
- Windows
- run qmake -t vcapp xmlconverter.pro
- load xmlconverter.vcproj in MS Visual Studio and build.
- Linux
- run qmake xmlconverter.pro
- make
Once you have the executable, you can use it to convert any of the old
GraspIt! data files. Just type xmlconverter [filename]. It
will automatically figure out the type of the file being converted
based on its extension. You can convert the following files:
- Body files (.iv or .wrl). It will create the
XML file that needs to go with the geometry file, and leave the old
geometry file unchanged.
- Robot files (.cfg). It will create your new XML robot
configuration file. It will also attempt to find all the link body
files that the Robot file references and convert them as well.
- World files (.wld). It will create your new XML World
files, but it will not attempt to convert any of the Body or Robot
files that are references therein. We recommend leaving World files
for last, after you have converted your Body and Robot files.
Copyright (C) 2002-2009 Columbia University
| | | 4 Main Data Types and Data Files | Contents |