ofxDabPhysics is an openFrameworks addon for simulating articulated bodies that consist of joints and rigid body parts. The addon is available here. This addon also includes an example for simulating multiple articulated morphologies.

Actuated Morphologies

The simulation models actuated morphologies. These morphologies consist of rigid body parts that are connected to each other via joints. The simplest way to design such morphologies is by using a solid modelling CAD program such as OnShape . As part of the simulation, a small construction set consisting of basic body part shapes has been created and is publicly accessible. A few example morphologies that have been built from these body part shapes are also public available.

Example Body Parts (left) and Articulated Bodies (right) Created with OnShape.

The morphologies created with OnShape can be downloaded and converted into the Unified Robotics Description Format (URDF) using the onshape-to-robot python tool. There is one restriction though: the conversion into URDF can only handle joints with a single rotational degree of freedom. Currently, this rotation is always around a joint’s local z-Axis.

Simulation

The simulation wraps the rigid body dynamics functionality of the Bullet Physics engine. Individual Morphologies are implemented with the “Body” class. A “Body” can consist of “Body Parts”, “Body Joints”, and “Body Motors”. “Body Parts” are associated with a “Body Shape” that defines its collision geometry and inertia. “Body Parts” are connected to each other via “Body Joints”. “Body Joints” can either be passive or active. Active “Body Joints” are referred to as “Body Motors” and exist in three varieties:

  • Spinning Motors (for turning body parts as if they were wheels)
  • Servo Motors (for specifying a target rotation that will be assumed and then hold)
  • Spring Motors (elastic linear or angular springs for which stiffness and damping can be specified)

Simulation Parameters

The most important simulation parameters are:

  • Body Part Mass: The mass of body parts (in kg). The heavier the body parts the more inertia they have. Very small masses cause the simulation to become instable.
  • Body Part Linear Damping: The linear damping of body parts (in Ns/m). Linear damping controls how much the linear motion of a body part is slowed down.
  • Body Part Angular Damping: The angular damping of body parts (in Ns/m). Angular damping controls how much the angular motion of a body part is slowed down.
  • Motor Max Angular Force: The maximum force (in N) body motors can excerpt while rotating around a rotation axis. Currently, only the angular force around the z-axis has an effect. This parameter only affects motors that operate in Servo Mode
  • Motor Max Angular Velocity: The maximum speed (in m/s) at which a motor rotates around a rotation axis. At the moment, only the angular velocity around the z-axis has an effect. This parameter only affects motors that operate in Servo Mode
  • Servo Motor Active: Specifies if a motor operates in Servo mode or not.
  • Servo Angular Target: Specifies the target rotation (Euler angle in radians) that a servo motor should assume. At the moment, only the target rotation around the z-axis has an effect. This parameter only affects motors that operate in Servo Mode
  • Spring Motor Active: Specifies if a motor operates in Spring mode or not.
  • Spring Angular Target: Specifies the target rotation (Euler angle in radians) that a spring motor should assume. At the moment, only the target rotation around the z-axis has an effect. This parameter only affects motors that operate in Spring Mode
  • Spring Angular Stiffness: Specifies the stiffness (in N/m) of a Spring Motor. This value is specified for all three rotation axes. Stiffness affects how strongly a Spring Motor tries to reach and maintain a target rotation
  • Spring Angular Damping: Specifies the damping (in Ns/m) of a Spring Motor. This value is specified for all three rotation axes. Damping affects how quickly a Spring Motor tries to reach a target rotation

Behaviours

Behaviours are not directly part of the simulation. They are implemented as simple routines that change some of the parameters of the simulation. Behaviours can operate on the body parts, body joints, or body motors that are assigned to them. Behaviours possess parameters that control how it is executed. Currently, there exist three different categories of behaviours.

Control Behaviours

Control Behaviours set simulation parameters to user specified values.
Control behaviours involve single “Bodies”.

The following control Control Behaviours are currently available:

  • ForceBehavior: applies an external force to body parts
  • RotationTargetBehavior: applies a target angle to body joints
  • TargetAttractionBehavior: causes body parts to be attracted towards a specified target position in space.
  • SpeedBehavior: causes body parts to move at a specified velocity

Randomization Behaviours

Randomization Behaviours set simulation parameters to random values.
Randomization behaviours involve single “Bodies”.

The following Randomization Behaviours are currently available:

  • RandomForceBehavior: applies random external forces to body parts
  • RandomRotationTargetBehavior: applies random target angles to body joints

Group Behaviours

Group Behaviours involve multiple “Bodies” and cause them to react to each other.
Group behaviours are associated with several “Bodies”.

The following Group Behaviours are currently available:

  • CohesionBehavior: “Body Parts” of multiple bodies are attracted to each other’s positions. An evasion behaviour can be created from a CohesionBehavior by setting the behaviour parameters accordingly (see further below)
  • AlignmentBehavior: “Body Parts” of multiple bodies align their linear and rotational velocity with each other.

Behaviour Parameters

Each behaviour has its own parameters, assigned entities, and effects.
One parameters is common to all behaviours.

  • Parameter “active“: controls if a behaviour is applied or not, one bool value.

Most of the other parameters are unique to each behaviour.

  • ForceBehaviour:
    Entities: Body Parts
    Effect: External force impacts on body parts
    • Parameter “dir“: directional components of force vector, three float values
    • Parameter “amp“: amplitude of force vector, one float value
    • Parameter “maxAmp“: maximum amplitude of force vector, one float value
    • Parameter “appInterval“: time interval (in millisecs) at which a behaviour is applied, one float value
  • RandomForceBehavior:
    Entities: Body Parts
    Effect: Randomized external forces impact on body parts
    • Parameter “minDir“: minimum directional components of force vector, three float values
    • Parameter “maxDir“: maximum directional components of force vector, three float values
    • Parameter “minAmp“: minimum amplitude of force vector, one float value
    • Parameter “maxAmp“: maximum amplitude of force vector, one float value
    • Parameter “randInterval“: time interval (in millisecs) at which force vectors are randomized, one float value
    • Parameter “appInterval“: time interval (in millisecs) at which a behaviour is applied, one float value
  • RotationTargetBehavior:
    Entities: Body Joints
    Effect: set target rotation for body joints
    • Parameter “target“: target joint rotation as Euler angles (in radians), three float values
    • Parameter “speed“: step size at which joint rotation is changed towards target angles, one float value
    • Parameter “appInterval“: time interval (in millisecs) at which a behaviour is applied, one float value
  • RandomRotationTargetBehavior:
    Entities: Body Joints
    Effect: set random target rotations for body joints
    • Parameter minTarget“: minimum rotation angles as Euler angles (in radians) for target rotation, three float values
    • Parameter maxTarget“: maximum rotation angles as Euler angles (in radians) for target rotation, three float values
    • Parameter “speed“: step size at which joint rotation is changed towards target angles, one float value
    • Parameter “randInterval“: time interval (in millisecs) at which target rotations are randomized, one float value
    • Parameter “appInterval“: time interval (in millisecs) at which a behaviour is applied, one float value
  • SpeedBehavior:
    Entities: Body Parts
    Effect: creates external forces that cause body parts to move at a specified speed
    • Parameter “speed“: speed at which body parts are supposed to move, one float
    • Parameter “amount“: strength of the external forces
  • TargetAttractionBehavior:
    Entities: Body Parts
    Effect: creates an attraction force that pushes body parts towards (or away) from a specified position in space
    • Parameter “targetPos“: attraction position in space, three floats
    • Parameter “maxDist“: upper distance threshold to attraction position below which an attraction force is created, one float
    • Parameter “minAmp“: minimum amplitude of attraction force (when parts are close to attraction position): one float
    • Parameter “maxAmp“: maximum amplitude of attraction force (when parts are far from attraction position): one float
    • Parameter “appInterval“: time interval (in millisecs) at which a behaviour is applied, one float value
  • CohesionBehavior:
    Entities: Bodies and Body Parts
    Effect: creates attraction forces that cause body parts in different bodies to be pushed towards (or away) from each other
    • Parameter “minDist“: lower distance threshold above which attraction forces are created, one float value
    • Parameter “maxDist“: upper distance threshold below which attraction forces are created, one float value
    • Parameter “amount”: strength of attraction force, one float value
  • AlignmentBehavior:
    Entities: Bodies and Body Parts
    Effect: creates forces that cause linear and/or rotational velocities of body parts in different bodies to align with each other
    • Parameter “minDist“: lower distance threshold above which alignment forces are created, one float value
    • Parameter “maxDist“: upper distance threshold below which alignment forces are created, one float value
    • Parameter “linearAmount“: strength of forces for aligning linear velocities, one float value
    • Parameter “angularAmount“: strength of forces for aligning angular velocities, one float value
    • Parameter “amount“: strength of attraction force

Communication

Communication with the simulation is based on the Open Sound Control (OSC) protocol. Communication can be used both for receiving information from the simulation and for remotely controlling aspects of the simulation.

Communication – Receiving OSC Messages from the Simulation

For each “Body” in the simulation, information about the position and rotation of the body joint is sent via OSC.

The joint positions are sent in absolute coordinates. All joint positions are packed into a single OSC message. The format of the OSC message is as follows:

/physics/joint/pos <String: body_name> <Float: joint1_posx> <Float: joint1_posy> <Float: joint1_posz> <Float: joint2_posx> <Float: joint2_posy> <Float: join2_posz> ...

The joint rotations are sent as absolute orientations represented as quaternions. All joint rotations are packed into a single OSC message. The format of the OSC message is as follows:

/physics/joint/rot <String: body_name> <Float: joint1_rotx> <Float: joint1_roty> <Float: joint1_rotz> <Float: joint1_rotw> <Float: joint2_rotx> <Float: joint2_roty> <Float: join2_rotz> <Float: joint2_rotw> ...

In addition, the joint rotations are also sent as relative orientations represented as Euler angles. All joint rotations are packed into a single OSC message. The format of the OSC message is as follows:

/physics/joint/relrot <String: body_name> <Float: joint1_rotx> <Float: joint1_roty> <Float: joint1_rotz> <Float: joint2_rotx> <Float: joint2_roty> <Float: join2_rotz> ...

Communication – Sending OSC Messages to the Simulation

OSC messages that are sent to the simulation can be used to modify a variety of simulation and behaviour parameters.

OSC Messages for Controlling General Simulation Parameters

The OSC messages for controlling general simulation parameters are structured in the same way. The address part of a message specifies the parameter that is modified. The single numerical argument specifies the value that is assigned to the parameter.

// Strength of Gravity
/physics/sim/gravity <Float: value>

// Size of Simulation Step
/physics/sim/timestep <Float: value>

// Number of Simulation Substeps
/physics/sim/substeps <Float: value>

OSC Messages for Controlling Body Part Parameters

The OSC messages for controlling body part parameters are more diverse in their structure than those for general simulation parameters. The address part of a message still specifies the parameter that is modified. But the arguments vary in number and data type. The parameters of body parts are addressed in one of four different ways, depending on the arguments used in the OSC message. If the OSC message contains only numerical arguments, then the message controls the corresponding parameter of all bodies and all body parts in the simulation. If the OSC message contains as first argument a string and as remaining arguments numerical values, then the string is interpreted either as name of a body or name of a body part (whichever exists in the simulation). In the first case, the parameters of all body parts of a single body will be changed. In the second case the parameters of a single body part in all bodies is changed. If the OSC message contains as first two arguments strings and as remaining arguments numerical values, then the first string is interpreted as body name and the second string as part name. Accordingly, only the parameter of a single body and single body part is changed. In the following documentation of the OSC messages, only the last type of message is written. The other message types can easily be obtained by removing some or all of the string arguments.

// Mass of Body Part
/physics/part/mass <String: body_name> <String: part_name> <Float: value>

// Damping of Linear Motion of Body Part
/physics/part/lineardamping <String: body_name> <String: part_name> <Float: value>

// Damping of Rotational Motion of Body Part
/physics/part/angulardamping <String: body_name> <String: part_name> <Float: value>

// Regular Friction of Body Part
/physics/part/friction <String: body_name> <String: part_name> <Float: value>
	
// Rolling Friction of Body Part
/physics/part/rollingfriction <String: body_name> <String: part_name> <Float: value>

// Bounciness of Body Part
/physics/part/restitution <String: body_name> <String: part_name> <Float: value>

OSC Messages for Controlling Body Joint Parameters

The parameters of body joints are also addressed in one of four different ways, depending on the arguments used in the OSC message. The principle is the same as for body parts.

// Error Tolerance of Joint Limits
/physics/joint/angularstoperp <String: body_name> <String: joint_name> <Float: rotx>  <Float: roty>  <Float: rotz>

// Softness of Joint Limits
/physics/joint/angularstopcfm <String: body_name> <String: joint_name> <Float: rotx>  <Float: roty>  <Float: rotz>

// Minimum Rotation of Joint
/physics/joint/angularlowerlimit <String: body_name> <String: joint_name> <Float: rotx>  <Float: roty>  <Float: rotz>

// Maximum Rotation of Joint
/physics/joint/angularupperlimit <String: body_name> <String: joint_name> <Float: rotx>  <Float: roty>  <Float: rotz>

OSC Messages for Controlling Body Motor Parameters

The parameters of body motors are also addressed in one of four different ways, depending on the arguments used in the OSC message. The principle is the same as for body parts.

// Rotational Motor Active
/physics/motor/angularactive <String: body_name> <String: motor_name> <Int: value>

// Bounciness of Rotational Motor
/physics/motor/bounce <String: body_name> <String: motor_name> <Float: value>

// Damping of Rotational Motor
/physics/motor/damping <String: body_name> <String: motor_name> <Float: value>

// Maximum Force Executed by Rotational Motor
/physics/motor/maxangularforce <String: body_name> <String: motor_name> <Float: rotx> <Float: roty> <Float: rotz>

// Maximum Velocity of Rotational Motor
/physics/motor/angularvelocity <String: body_name> <String: motor_name> <Float: rotx> <Float: roty> <Float: rotz>

// Servo Mode Active
/physics/motor/angularservoactive <String: body_name> <String: motor_name> <Int: value>

// Servo Rotation
/physics/motor/angularservoposition <String: body_name> <String: motor_name> <Float: rotx> <Float: roty> <Float: rotz>

// Spring Mode Active
/physics/motor/angularspringactive <String: body_name> <String: motor_name> <Int: value>

// Spring Angular Rest Length
/physics/motor/angularspringrestlength <String: body_name> <String: motor_name> <Float: rotx> <Float: roty> <Float: rotz>

// Spring Angular Stiffness
/physics/motor/angularspringstiffness <String: body_name> <String: motor_name> <Float: rotx> <Float: roty> <Float: rotz>

// Spring Angular Damping: 
/physics/motor/angularspringdamping <String: body_name> <String: motor_name> <Float: rotx> <Float: roty> <Float: rotz>

OSC Messages for Controlling Behaviour Parameters

The OSC messages for modifying behaviour parameters follows a slightly different approach than those previously described. Since different behaviours possess different parameters, the address part of the OSC message doesn’t specify the parameter itself, instead, one of the arguments is used to name the parameter. The parameters of behaviours are addressed in one of two different ways, depending on the arguments used in the OSC message. If the OSC message contains as first two arguments strings and as remaining arguments numerical values, then the first string is interpreted as behaviour name and the second string as parameter name. If the OSC message contains as first three arguments strings and as remaining arguments numerical values, then the first string is interpreted as body name, the second string as behaviour name, and the last string as parameter name. Again, only the last message type is written in the documentation.

OSC messages for controlling parameters that are common to all behaviours

// Behavior Active:
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: active> <Int: value>

OSC messages for controlling parameters of the Speed behaviour

// Movement Speed:
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: speed> <Float: value>

// Movement Amount:
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: amount> <Float: value>

OSC messages for controlling parameters of the Force behaviour

// Force Direction
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: dir> <Float: rotx> <Float: roty> <Float: rotz>

// Force Amplitude
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: amp> <Float: value>

// Application Interval
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: appInterval> <Float: value>

OSC messages for controlling parameters of the Rotation Target behavior

// Rotation Angle
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: target> <Float: rotx> <Float: roty> <Float: rotz>

// Rotation Speed
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: speed> <Float: value>

// Application Interval
/physics/behavior/parameter <String: body_name> <String: behavior_name> <String: appInterval> <Float: value>

Communication – Sending OSC Messages to the Visualisation

OSC messages can also be sent to the visualisation part of the simulation to change the manner in which the articulated morphologies are rendered as 3D graphics.

OSC Messages for Controlling the Camera

All OSC messages for controlling the properties of a perspective camera are structured in the same way. The address part of a message specifies the parameter that is modified. The numerical arguments specifies the values that are assigned to the parameter.

// Camera Projection
/visuals/camera/projection <Float: value> <Float: value> <Float: value> <Float: value>

// Camera Position
/visuals/camera/position <Float: value> <Float: value> <Float: value>

// Camera Rotation (in Euler Angles)
/visuals/camera/rotation <Float: value> <Float: value> <Float: value>

OSC Messages for Controlling the Appearance of Body Shapes

The OSC messages for controlling the parameters of the appearance of body shapes exist in two variations. In both cases, the address part specifies the parameter to be modified. The variations differ with regards to the number of arguments. If the message contains only numerical arguments, then the corresponding parameters of all visual body shapes are affected. If the message contains as first argument a string and the remaining arguments are numerical, then the string is interpreted as name of the body shape whose parameter is modified. In the following documentation of the OSC messages, only the last type of message is written.

// Transparency of Body Shape
/visuals/shape/transparency <String: shape_name> <Float: value>

// Ambience Scale of Body Shape
/visuals/shape/ambientscale <String: shape_name> <Float: value>

// Diffuse Scale of Body Shape
/visuals/shape/diffusescale <String: shape_name> <Float: value>

// Specular Scale of Body Shape
/visuals/shape/specularscale <String: shape_name> <Float: value>
	
// Specular Pow of Body Shape
/visuals/shape/specularpow <String: shape_name> <Float: value>

// Ambience Colour (HSB format) of Body Shape
/visuals/shape/ambientcolor <String: shape_name> <Float: value> <Float: value> <Float: value>

// Diffuse Colour (HSB format) of Body Shape
/visuals/shape/diffusecolor <String: shape_name> <Float: value> <Float: value> <Float: value>

Programming Tutorial

The addon provides a large number of classes for a range of different purposes. To provide a better overview, the classes are grouped into the following categories: Simulation, Behaviours, Visualisation, Communication, Import.

The core classes for the simulation are:

  • dab::physics::BodyShape
  • dab::physics::BodyPart
  • dab::physics::BodyJoint
  • dab::physics::UniversalJoint
  • dab::physics::BodyMotor
  • dab::physics::UniversalMotor
  • dab::physics::Body
  • dab::physics::Simulation

The classes for implementing body behaviours are:

  • dab::physics::Behavior
  • dab::physics::ForceBehavior
  • dab::physics::RandomForceBehavior
  • dab::physics::RandomRotationTargetBehavior
  • dab::physics::RandomTorqueBehavior
  • dab::physics::RotationTargetBehavior
  • dab::physics::SpeedBehavior
  • dab::physics::TargetAttractionBehavior
  • dab::physics::TorqueBehavior
  • dab::physics::VolumeBehavior
  • dab::physics::NeighborBehavior
  • dab::physics::AlignmentBehavior
  • dab::physics::CohesionBehavior

The classes for visualising the simulation are:

  • dab::vis::BodyTransform
  • dab::vis::BodyShape
  • dab::vis::BodyPart
  • dab::vis::Body
  • dab::vis::Camera
  • dab::vis::BodyVisualization

The classes for communicating with the simulation are:

  • dab::Com::OscControl
  • dab::Com::PhysicsOscControl
  • dab::Com::VisualsOscControl

The classes for importing body specification files are:

  • dab::geom::MeshManager
  • dab::UrdfImporter
  • dab::UrdfParser

In the following, those classes that are frequently used and directly exposed to the user are explained in some detail.

dab::physics::Simulation

The Simulation class stores all instances of bodies, parts, shapes, joints, motors, and behaviours. It also provides functions for creating these instances. Instances can be created either from scratch or by copying existing instances. The simulation also wraps some of the functionality of the underlying Bullet Physics engine.

The Simulation class is implemented as Singleton from which a single instance can be obtained as follows:

dab::physics::Simulation& physics = dab::physics::Simulation::get();

General parameters of the simulation can be set as follows:

dab::physics::Simulation& physics = dab::physics::Simulation::get();
physics.setTimeStep(0.1);
physics.setSupSteps(20);
physics.setGravity(glm::vec3(0.0, 0.0, 0.0));

The simulation runs in its own thread which can be started as follows:

dab::physics::Simulation::get().start();

Other functions provided by the simulation such as the creation of instances of classes such as BodyShape are explained as part of the description of these classes.

dab::physics::Body

An instance of the Body class represents an articulated body that has a name and consists of parts, joints, motors, and behaviours. One of the parts (typically the first one) represents the root of the body. The position and rotation of the body is identical with the position and rotation of the root part.

A body can be created for example as follows:

dab::physics::Simulation& physics = dab::physics::Simulation::get();
std::shared_ptr<dab::physics::Body> groundBody = physics.addBody("ground");

Such a body is empty in that it doesn’t yet contain any parts, joints, etc. The Simulation class provides functions to add these components to a body.

If a body has already been created, then a new body with the same properties and the same parts, joints, and behaviours, but with a different name can be created by duplication the existing body. The procedure to do so is as follows:

dab::physics::Simulation& physics = dab::physics::Simulation::get();
std::shared_ptr<dab::physics::Body> newBody = physics.copyBody("existingBody", "newBody");

dab::physics::BodyShape

An instance of the BodyShape class represents a named shape of a body part. The same named shape can be used by multiple body parts. The shape is used to determine the inertia and spatial extension of a body part. The latter is used to detect and resolve collisions between body parts. Different geometrical primitives can be used as body shapes. These primitives are implemented by subclassing the BodyShape class. The following subclasses exist:

  • BodyPlaneShape : an infinite plane specified by a name and a surface normal
  • BodySphereShape: a sphere specified by a name and a radius
  • BodyBoxShape: a box specified by a name and a width, height, and depth.
  • BodyCylinderShape: a cylinder specified by a name and a radius and height.
  • BodyCapsuleShape: a capsule specified by a name and a radius and height.
  • BodyConeShape: a cone specified by a name and a radius and height.
  • BodyConvexMeshShape: a convex mesh specified by a name, a mesh name, and a vector of vertex positions.
  • BodyCompoundShape: a compound shape that contains child shapes. When created, it is specified by a name only. Child shapes can be added afterwards.

As example, a box shape of size 20x20x1 can be created as follows:

dab::physics::Simulation& physics = dab::physics::Simulation::get();
std::shared_ptr<dab::physics::BodyBoxShape> groundShape = physics.addBoxShape("groundShape", glm::vec3(20.0, 20.0, 1.0));

dab::physics::BodyPart

An instance of a BodyPart class represents a named rigid body part. A body part is associated with a body shape. A body part can only be created after the shape to which it is associated already exists.

A body part can be created as follows:

dab::physics::Simulation& physics = dab::physics::Simulation::get();
std::shared_ptr< dab::physics::BodyPart> groundObject = physics.addBodyPart("ground", "ground", "GroundShape", true, 0.0);

Some functions for setting parameters of a body part are:

//continuation from previous code block

groundObject->setPosition(glm::vec3(0.0, 0.0, 6.0));
groundObject->setRotation(glm::quat(glm::vec3(-PI / 2.0, 0.0, 0.0)));
groundObject->setResitution(0.0);
groundObject->setFriction(0.1);
groundObject->setLinearDamping(0.3);

dab::physics::BodyJoint

An instance of a BodyJoint class represents a named constraint between two body parts. A body joint is associated with two body parts. A body joint can only be created after the body parts that are associated with it already exists. Creating a body joint involves not only assigning two existing body parts to it but also specifying the position and rotation of the joint in the relative coordinate system of the first body part and specifying the position and rotation of the second body part in the relative coordinate system of the joint. Mastering these coordinate systems is not easy. It is much easier to import an entire body with all its joint specification from an URDF file. The procedure for doing this is explained further below.

dab::physics::UniversalJoint

The BodyJoint class cannot directly be used. Instead, the joint class UniversalJoint is used in the simulation. The UniversalJoint class is derived from the BodyJoint class. Instances of the UniversalJoint class possess six degrees of freedom (3 degrees for translation and 3 degrees for rotation). Each of these degrees of freedom can be constrained individually.

Some function calls for constraining the degrees of freedom of a universal joint are:

bodyJoint->setLinearLowerLimit( { -1.0, -1.0, -1.0 } );
bodyJoint->setLinearUpperLimit( { 1.0, 1.0, 1.0 } );
bodyJoint->setAngularLowerLimit( { 0.0, 0.0, -PI/2.0 } );
bodyJoint->setAngularLowerLimit( { 0.0, 0.0, PI/2.0 } );

dab::physics::Motor

An instance of a BodyMotor class represents an actively actuated joint. A body motor is associated with a body joint. A body motor can only be created after the body joint that is associated with it already exists.

dab::physics::UniversalMotor

The BodyMotor class cannot directly be used. Instead, the joint class UniversalMotor is used in the simulation. The UniversalMotor class is derived from the BodyMotor class. Instances of the UniversalMotor class are extremely versatile. As has been mentioned in the beginning, there exist three different modes in which motors can operate in: as spinning motors, as servo motors, or as spring motors. This mode can be different for each degree of freedom. It is possible to change the modes on the fly, but care must be taken since such a change might cause instabilities in the simulation. Also, it must be taken into account that some of these modes are mutually exclusive while other work only in tandem. The spring mode is mutually exclusive. A degree of freedom can only be in spring mode if its spinning and servo modes are turned off. The spinning mode is also mutually exclusive. For the servo mode to function, the spinning mode must be turned on but the spring mode must be turned off.

Some functions calls for changing the operation mode of a motor are as follows:

// set spinning mode of motor
bodyMotor->setLinearActive( {false, true, false} );
bodyMotor->setAngularActive( {true, false, false} );

// set servo mode of motor
bodyMotor->setLinearServoActive( {false, true, false} );
bodyMotor->setAngularServoActive( {false, false, false} );

// set spring mode of motor
bodyMotor->setLinearSpringActive( {false, false, true} );
bodyMotor->setAngularSpringActive( {false, false, true} );

dab::physics::UrdfImporter

The easiest method to create an articulated body for simulation is to import it from an URDF file. When importing an URDF file, all body shapes, parts, joints, motors are automatically created and configured according to the specifications in the URDF file. Some example URDF files are provided together with the addon.

An example function call to import an URDF file is as follows

dab::UrdfImporter& urdfImporter = dab::UrdfImporter::get();
		urdfImporter.loadURDF(ofToDataPath("3d_models/arm_6joints_base/robot.urdf"));

dab::physics::Behavior

An instance of a Behavior class provides a named method for altering some of the properties of the body parts, joints, or motors that are assigned to it. All these components must exist before the behavior is instantiated. The Behavior class doesn’t do anything. Behaviours that have an effect are all implemented as subclasses of the basic Behavior class. These subclasses are instantiated by passing the name of the body, the name of the behaviour, and three lists containing the names of the body parts, body joints, and body motors. These lists can be empty if no associated parts, joints, or motors are needed.

dab::physics::RandomForceBehavior

An instance of a RandomForceBehavior applies random external forces to body parts. Such a behaviour can for example be created as follows:

// retrieve part names of a body
const std::vector<std::shared_ptr<dab::physics::BodyPart>>& bodyParts = physics.body("onshape")->parts();

std::vector<std::string> partNames = {};
for (auto bodyPart : bodyParts) partNames.push_back(bodyPart->name());
std::vector<std::string> jointNames = {};
for (auto bodyJoint : bodyJoints) jointNames.push_back(bodyJoint->name());

// create behaviour with only the last part assigned to it
std::shared_ptr<dab::physics::RandomForceBehavior> randomTipBehaviour = dab::physics::Simulation::get().addBehavior<dab::physics::RandomForceBehavior>("onshape", "random_tip", { partNames[partNames.size() - 1] }, {}, {});

// set behaviour parameters
randomTipBehaviour->set("active", false);
randomTipBehaviour->set("minDir", { -1.0f, -1.0f, -1.0f });
randomTipBehaviour->set("maxDir", { 1.0f, 1.0f, 1.0f });
randomTipBehaviour->set("minAmp", 1.0f);
randomTipBehaviour->set("maxAmp", 1.0f);
randomTipBehaviour->set("appInterval", 1.0f);
randomTipBehaviour->set("randInterval", 5000.0f);

Other Behavior classes can be instantiated in a similar manner. The example provided as part of the addon contains corresponding code.

dab::vis::BodyVisualization

The BodyVisualisation class handles the graphical depiction of the articulated morphologies. The visualisation creates a simple OpenGL-based 3D graphics that changes in accordance to the motions of the articulated morphologies. For this purpose, the visualisation stores instances of visual proxy classes for the simulated bodies, body parts and body shapes. Furthermore, the visualisation involves a dynamic camera, custom shaders that employ a simple illumination model, and material properties that affect the appearance of body shapes.

The BodyVisualisation class is implemented as Singleton from which a single instance can be obtained as follows:

dab::vis::BodyVisualization& visuals = dab::vis::BodyVisualization::get();

The BodyVisualisation must be told which shaders to load to render the simulation. This can be done for instance as follows:

visuals.loadShader("shaders/vis_shape_shader.vert", "shaders/vis_shape_shader.frag");

The BodyVisualisation class has a “draw” function that can be called within the “draw” function of the ofApp class.

dab::vis::BodyVisualization::get().draw();

The BodyVisualisation class also provides functions for creating visual equivalents of shapes, bodies, and parts. These instances are based on their physical equivalents and can therefore only be created when the physical equivalents already exist. The use of these creation functions is explained as part of the description of these classes.

dab::vis::Camera

An instance of the Camera class operates as a simple perspective camera that possesses a position and rotation in space. These camera properties can be changed for example as follows:

dab::vis::BodyVisualization& visuals = dab::vis::BodyVisualization::get();
visuals.camera()->setProjection(glm::vec4(20.0, 1.0, 0.1, 200.0));
visuals.camera()->setPosition(glm::vec3(0.0, -4.0, -3.9));
visuals.camera()->setRotation(glm::vec3(-80.0, 0.0, -24.0));

dab::vis::BodyShape

An instance of the BodyShape class defines the visual properties of the corresponding physical body shape it is associated with. A visual body shape can be creates as follows:

dab::vis::BodyVisualization& visuals = dab::vis::BodyVisualization::get();
std::shared_ptr<dab::vis::BodyShape> visGroundShape = visuals.addBodyShape("GroundShape");

dab::vis::Material

An instance of the Material class defines the illumination properties for the body shapes it is associated with. This involves ambient colour, diffuse colour, and specular colour, scaling factors for the contribution of each of these colours, specular shininess, and overall transparency. The diffuse and specular colours are identical. Setting the diffuse colour automatically also specifies the specular colour. Settings these material properties can be done as follows:

visGroundShape->material().setTransparency(0.5);
visGroundShape->material().setAmbientScale(0.2);
visGroundShape->material().setDiffuseScale(0.5);
visGroundShape->material().setSpecularScale(1.0);
visGroundShape->material().setSpecularPow(4.0);
visGroundShape->material().setAmbientColor(glm::vec3(0.5, 0.5, 0.5));
visGroundShape->material().setDiffuseColor(glm::vec3(1.0, 1.0, 1.0));

dab::vis::Body

An instance of the Body class handles the association with the physical equivalent of a body and stores visual instances for each body part in the physical body. A visual body is created as follows.

dab::vis::BodyVisualization& visuals = dab::vis::BodyVisualization::get();
std::shared_ptr<dab::vis::Body> visGroundBody = visuals.addBody("ground");
		std::shared_ptr<dab::vis::BodyPart> visGroundPart = 

If a visual body has already been created that contains the visual equivalents of body parts, then a new body with the same properties but a different name can be created by duplication the existing body. There procedure to do so is as follows:

dab::vis::BodyVisualization& visuals = dab::vis::BodyVisualization::get();
visuals.copyBody("onshape", "onshape2");

dab::vis::BodyPart

An instance of the BodyPart class defines the spatial transformation required to visualise the physical body part that it is associated with. A visual body part is created as follows:

dab::vis::BodyVisualization& visuals = dab::vis::BodyVisualization::get();
std::shared_ptr<dab::vis::BodyPart> visGroundPart = visuals.addBodyPart("ground", "ground", "GroundShape");

dab::com::OscControl

The OscControl class handles the communication between the simulation and other software applications. The communication is based on the OSC protocol. The OSCControl class is implemented as Singleton from which a single instance can be obtained as follows:

dab::com::OscControl& oscControl = dab::com::OscControl::get();

In order to receive and send OSC messages, a receiver and sender has to be created. The OscControl provides corresponding creation functions. These functions take as argument the name of the receiver or sender and a port number for the receiver and an ip address and port number for the sender. Once a receiver has been created, control classes for parsing the incoming OSC messages have to be added. There exist two control classes, one for parsing OSC messages for controlling the simulation and one for parsing OSC messages for controlling the visualisation. The code for doing all of this is as follows:

dab::com::OscControl& oscControl = dab::com::OscControl::get();

oscControl.createReceiver("OscControlReceiver", 9003);
oscControl.createPhysicsControl("OscControlReceiver");
oscControl.createVisualsControl("OscControlReceiver");

oscControl.createSender("OscPhysicsSender", "127.0.0.1", 9005);