-
Notifications
You must be signed in to change notification settings - Fork 13
XML format
- Add a driver and set camera, window location using DRIVER tags
<DRIVER>
<camera position="0 0 10" target="0 0 0" up="0 1 0" />
<window location="0 0" size="640 480" />
</DRIVER>
- Add Primitives, RigidBodies, Integrators, etc. within MOBY tags
<MOBY>
<!-- Example Primitive -->
<Box id="b1" xlen="2" ylen="0.001" zlen="2" density="10.0" />
</MOBY>
- Primitives that are available to add to a simulation include Sphere, Box, TriangleMesh, Cylinder, Cone, Heightmap, Plane
- Example use of each primitive, showing specific options:
<MOBY>
<Sphere id="sphere" radius="0.1" />
<Box id="box" xlen="1.0" ylen="1.0" zlen="1.0" />
<!-- the cylinder's axis is aligned with the y-axis -->
<Cylinder id="cylinder" height="1.0" radius="1.0" />
<!-- the plane's equation is y=0 -->
<Plane id="plane" />
<!-- the axis of revolution is the z-axis -->
<Torus id="torus" major-radius=".7" minor-radius=".3" />
</MOBY>
All primitives take the following attributes:
-
id[required] the unique identifier for the primitive -
massthe mass of the primitive (behavior undefined ifdensityalready specified) -
densitythe density of the primitive (behavior undefined ifmassalready specified) -
positionthe translational offset of the primitive -
rpythe roll-pitch-yaw orientation of the primitive (behavior undefined ifaangleorquatalready specified) -
quatthe unit quaternion orientation (qw,qx,qy,qz) of the primitive (behavior undefined ifaangleorrpyalready specified) -
aanglethe axis-angle orientation of the primitive (behavior undefined ifaangleorquatalready specified)
- To add a gravity force:
<GravityForce id="" accel="0 -9.81 0" />
- Add a RigidBody to the simulation and link it to a primitive through visualization-id
- Add CollisionGeometry or InertiaFromPrimitive through your primitive's id
<MOBY>
<Sphere id="s1" radius=".5" density="1.0" />
<RigidBody id="sphere" enabled="true" position="0 .5000 0" visualization-id="s1" linear-velocity="1 0 0" angular-velocity="1 2 3">
<InertiaFromPrimitive primitive-id="s1" />
<CollisionGeometry primitive-id="s1" />
</RigidBody>
</MOBY>
The RigidBody tag takes the following attributes:
-
id[required] the unique identifier for the rigid body -
enabledif "false", then the rigid body is treated as having infinite inertia. If the rigid body is a link within an articulated body defined in reduced coordinates (seeRCArticulatedBodybelow),enabled="false"is only valid if the link is a base link (changes the base from "floating" to "fixed"). The default value isenabled="true") -
massthe mass of the rigid body (behavior undefined ifdensityor one or moreInertiaFromPrimitivetags already specified) -
inertiathe 3x3 inertia matrix of the rigid body (MATLAB/Octave format, or one or moreInertiaFromPrimitivetags already specified) -
positionthe location of the rigid body's reference frame (not necessarily its center-of-mass, applied after rotation specified byrpy/quat/aangle) -
rpythe roll-pitch-yaw orientation of the rigid body's reference frame (behavior undefined ifaangleorquatalready specified) -
quatthe unit quaternion orientation (qw,qx,qy,qz) of the rigid body's reference frame (behavior undefined ifaangleorrpyalready specified) -
aanglethe axis-angle orientation of the rigid body's reference frame (behavior undefined ifaangleorquatalready specified) -
inertial-relative-comthe offset of the body's inertial frame from its reference frame (applied after rotation specified byinertia-relative-aangle'/inertia-relative-rpy/inertia-relative-quat` if any) -
inertial-relative-rpythe relative roll-pitch-yaw orientation of the rigid body's inertial frame (behavior undefined ifinertial-relative-aangleorinertial-relative-quatalready specified) -
inertial-relative-quatthe unit quaternion describing the relative orientation (qw,qx,qy,qz) of the rigid body's inertial frame (behavior undefined ifinertial-relative-aangleorinertial-relative-rpyalready specified) -
inertial-relative-aanglethe axis-angle orientation of the rigid body's inertial frame (behavior undefined ifinertial-relative-aangleorinertial-relative-quatalready specified) -
linear-velocitythe linear velocity of the rigid body at its center-of-mass -
angular-velocitythe angular velocity of the rigid body, defined in the global frame -
visualization-idthe identifier of the primitive used for visualizing the rigid body (only applicable if Moby is used with OpenSceneGraph) -
visualization-filenamethe filename of the geometric description used for visualizing the rigid body (only applicable if Moby is used with OpenSceneGraph)
The RigidBody tag accepts the following child nodes:
-
Visualizationone or more tags used for visualization-
visualization-idthe identifier of the primitive used for visualizing the rigid body (only applicable if Moby is used with OpenSceneGraph, behavior unspecified ifvisualization-idalso specified) -
visualization-filenamethe filename of the geometric description used for visualizing the rigid body (only applicable if Moby is used with OpenSceneGraph, behavior unspecified ifvisualization-filenamealso specified) -
visualization-rel-originthe translation offset of the geometry used for visualizing the rigid body (only applicable if Moby is used with OpenSceneGraph) -
visualization-rel-rpythe relative orientation of the geometry, specified using roll-pitch-yaw, used for visualizing the rigid body (only applicable if Moby is used with OpenSceneGraph, behavior is undefined ifvisualization-rel-quatalso specified) -
visualization-rel-quatthe relative orientation of the geometry, specified as a unit quaternion (qw qx qy qz) used for visualizing the rigid body (only applicable if Moby is used with OpenSceneGraph, behavior is undefined ifvisualization-rel-rpyalso specified)
-
-
CollisionGeometryone or more tags used for computing geometric intersections and computing points of contact between rigid bodies-
primitive-id(required) the primitive used for intersection checking -
relative-originrelative offset of the primitive -
relative-aanglerelative orientation of the primitive, defined in axis-angle orientation (behavior undefined ifrelative-rpyalso specified) -
relative-rpyrelative orientation of the primitive, defined using roll-pitch-yaw (behavior undefined ifrelative-aanglealso specified)
-
-
InertiaFromPrimitiveone or more tags used for computing the inertia of a rigid body-
primitive-id(required) the primitive used to compute the inertia -
relative-originrelative offset of the primitive used to compute the inertia (applied after rotation specified byrelative-aangle'/relative-rpy` if any) -
relative-aanglerelative orientation of the primitive used to compute the inertia, defined in axis-angle orientation (behavior undefined ifrelative-rpyalso specified) -
relative-rpyrelative orientation of the primitive used to compute the inertia, defined using roll-pitch-yaw (behavior undefined ifrelative-aanglealso specified)
-
An RCArticulatedBody is an articulated body defined in reduced (minimal or almost minimal) coordinates. The dynamics for such bodies can be computed rapidly if joints admit few degrees-of-freedom (ex. revolute, prismatic, universal). Reduced coordinates also have the advantage of not requiring any constraint stabilization (as long as there are no kinematic loops) and straightforward provision of Jacobian matrices used in robotics applications. Reduced coordinates become less computationally efficient when used with joints with greater degrees-of-freedom (spherical, ball-and-socket).
- Such articulated bodies are constructed by embedding rigid bodies and joints within, as below:
<RCArticulatedBody id="" floating-base="false" fdyn-algorithm="crb" fdyn-algorithm-frame="link" rpy="0.0 0.05 0.0" translate="0.45,0,0" >
<RigidBody id="BASE" color="0 0 0 0" position="0 0 -0.02" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="base" compliant="false">
</RigidBody>
<PrismaticJoint id="shaker" location="0 0 0" inboard-link-id="BASE" outboard-link-id="SLIDE1" axis="1 0 0"/>
<!-- the body -->
<RigidBody id="SLIDE1" color="0 0 0 0" position="0 0 0" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="slide1-viz" compliant="false">
<CollisionGeometry primitive-id="slide1" />
<InertiaFromPrimitive primitive-id="slide1-viz" />
</RigidBody>
<FixedJoint id="fj1" location="0 0 0" inboard-link-id="SLIDE1" outboard-link-id="SLIDE2" />
<RigidBody id="SLIDE2" color="0 0.5 0 1" position="0 0.055 0.01" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="slide2-viz" compliant="false">
<CollisionGeometry primitive-id="slide2" />
<InertiaFromPrimitive primitive-id="slide2-viz" />
</RigidBody>
<!-- ... -->
<!-- full example Moby/example/parts-feeder/feeder.xml -->
</RCArticulatedBody>
The RCArticulatedBody tag takes the following attributes:
-
id[required] the unique identifier for the articulated body -
urdf-filenamethe filename to read a URDF from -
fdyn-algorithmthe forward dynamics algorithm, valid choices are "crb" (the Composite Rigid Body Algorithm) and "fsab" (the Featherstone Articulated Body Algorithm) -
fdyn-algorithm-framethe frame that forward dynamics is computed in. Different choices have slight advantages for efficiency, as described in Featherstone's "Robot Dynamics Algorithms" book. Valid choices are "global", "link", "linkinertia", "linkcom", and "joint". These values can be experimented with, but the user is unlikely to see substantial practical performance differences. "global" should be avoided, however, because of issues with floating point arithmetic described in Featherstone's book. -
translatethe 3D translation vector applied to the articulated body's base (and all links emanating from it, applied after rotation specified by `rpy' if any) -
rpythe roll-pitch-yaw orientation applied to the articulated body's base (and all links emanating from it)
- The following joint types are available: FixedJoint, PrismaticJoint, RevoluteJoint, SphericalJoint, UniversalJoint, PlanarJoint (cannot be embedded within a RCArticulatedBody), and Gears
- Joints can be explicit (embedded within an RCArticulatedBody) or implicit (embeddable within an RCArticulatedBody or can connect two bodies together)
- Joints are added between two rigid bodies by specifying the joint's inboard-link-id and outboard-link-id
<!-- taken from the example above -->
<RigidBody id="SLIDE1" color="0 0 0 0" position="0 0 0" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="slide1-viz" compliant="false">
<CollisionGeometry primitive-id="slide1" />
<InertiaFromPrimitive primitive-id="slide1-viz" />
</RigidBody>
<FixedJoint id="fj1" location="0 0 0" inboard-link-id="SLIDE1" outboard-link-id="SLIDE2" />
<RigidBody id="SLIDE2" color="0 0.5 0 1" position="0 0.055 0.01" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="slide2-viz" compliant="false">
<CollisionGeometry primitive-id="slide2" />
<InertiaFromPrimitive primitive-id="slide2-viz" />
</RigidBody>
Joints can take the following attributes:
-
id[required] the unique identifier for the joint -
visualization-idthe identifier of the primitive used for visualizing the joint (only applicable if Moby is used with OpenSceneGraph) -
visualization-filenamethe filename of the geometric description used for visualizing the joint (only applicable if Moby is used with OpenSceneGraph) -
lower-limitsrigid lower limit(s) on the joint (not valid for FixedJoint or Gears) -
upper-limitsrigid upper limit(s) on the joint (not valid for FixedJoint or Gears) -
qsets the initial configuration of the joint (moves the attached bodies, not valid for FixedJoint or Gears) -
qdthe initial velocity(-ies) of the joint degrees-of-freedom (not valid for FixedJoint or Gears) -
q-tarelabels the configuration of the joint degrees-of-freedom (does not move the attached bodies, not valid for FixedJoint or Gears) -
restitution-coeffPoisson-type restitution coefficient in [0,1] applied to joints that collide with their limits -
inboard-link-id(required) the link of the rigid body that is the inboard link of this joint (distinction between inboard/outboard only relevant forRCArticulatedBodytypes) -
outboard-link-id(required) the link of the rigid body that is the outboard link of this joint (distinction between inboard/outboard only relevant forRCArticulatedBodytypes) -
locationthe global location of this joint (only used for initializing the body)
Each joint tag accepts the following child nodes:
-
Visualizationone or more tags used for visualization-
visualization-idthe identifier of the primitive used for visualizing the joint (only applicable if Moby is used with OpenSceneGraph, behavior unspecified ifvisualization-idalso specified) -
visualization-filenamethe filename of the geometric description used for visualizing the joint (only applicable if Moby is used with OpenSceneGraph, behavior unspecified ifvisualization-filenamealso specified) -
visualization-rel-originthe translation offset of the geometry used for visualizing the joint (only applicable if Moby is used with OpenSceneGraph) -
visualization-rel-rpythe relative orientation of the geometry, specified using roll-pitch-yaw, used for visualizing the joint (only applicable if Moby is used with OpenSceneGraph, behavior is undefined ifvisualization-rel-quatalso specified) -
visualization-rel-quatthe relative orientation of the geometry, specified as a unit quaternion (qw qx qy qz) used for visualizing the joint (only applicable if Moby is used with OpenSceneGraph, behavior is undefined ifvisualization-rel-rpyalso specified)
-
The inboard link of a planar joints must be a disabled rigid body (see attribute enabled of RigidBody)
The planar joint takes one unique attribute:
-
normalthe global axis of rotation
Enforces a torque/speed relationship for one degree of freedom joints. Unlike many other popular forms of simulating joints, incorporates gyroscopic forces.
The gear joint takes one unique attribute:
** TODO: fix this **
-
gear-ratiothe ratio of the movement of the inboard link to the outboard link
Two types of simulators can be created: Simulator and TimeSteppingSimulator. The latter permits contact between bodies. The former is provided for speed in robotics applications that can leverage it. The time stepping simulator computes, and steps precisely to, contacting configurations (if any).
Both Simulator and TimeSteppingSimulator accept the following attributes:
-
id[required] the unique identifier for the simulator -
current-timethe current time of the simulator [0,infinity] -
dissipator-idan optional kinetic energy dissipation mechanism for promoting simulation stability
Both Simulator and TimeSteppingSimulator accept the following child nodes:
-
DynamicBody-
dynamic-body-idthe unique identifier of aRigidBodyorRCArticulatedBodyobject
-
-
ImplicitConstraint-
joint-idthe unique identifier of an implicit joint constraining two bodies
-
-
RecurrentForce-
recurrent-force-idthe unique identifier of a force applied in a recurrent manner to bodies (like gravity)
-
TimeSteppingSimulator accepts the following attributes:
-
min-step-sizethe time stepping simulator will not take steps below this size
TimeSteppingSimulator accepts the following child node:
-
ContactParameters-
object1-id(required) -
object2-id(required) -
epsilonthe coefficient [0,1] of restitution (Poisson restitution model) -
mu-coulombthe coefficient of Coulomb friction [0,infinity] -
mu-viscousthe coefficient of viscous friction [0,infinity] -
friction-cone-edgesthe number of edges in the polygonal approximation to the friction cone -
compliancethe compliance of the contact [0,infinity], zero is equivalent to a fully rigid contact
-
Example:
<MOBY>
<TimeSteppingSimulator id="simulator">
<DynamicBody dynamic-body-id="sphere" />
<DynamicBody dynamic-body-id="ground" />
<RecurrentForce recurrent-force-id="gravity" />
<ContactParameters object1-id="ground" object2-id="sphere" epsilon="0" mu-coulomb="10" mu-viscous="0" friction-cone-edges="8" />
</TimeSteppingSimulator>
</MOBY>