underworlds: Cascading Social Situation Assessment for Robots

_images/screenshot-l2tor.jpg

underworlds is a distributed and lightweight framework that facilitates building and sharing models of the physical world surrounding a robot amongst independent software modules.

These modules, also called clients, can be for instance geometric reasoners (that compute topological relations between objects), motion planner, event monitors, viewers… any software that need to access a geometric (based on 3D meshes of objects) and/or temporal (based on events) view of the world.

Note

The list of official underworlds clients is here: Clients registry. Feel free to look at the source code of these clients, and to use them as starting point for your owns.

One of the main feature of underworlds is the ability to store many parallel worlds: past models of the environment, future models, models with some objects filtered out, models that are physically consistent, etc.

_images/overview.svg

This package provides the underworlds server, a Python client library, and a set of tools to interact with the system (viewers, scene loader, etc.).

Documentation Overview

You can read below details about underwords: the Main concepts, the Scenes and nodes.

You may then want to check the installation instructions: Installation.

If you want to know more about the core tools, check this page: underwords Core Tools.

If you are looking for a guide to write your own client application: How to write an underworlds client.

If you want to read about the underworlds client-server protocol (for instance, to add bindings with another language), head here: The client-server protocol.

Finally, the full Performances is also available.

Main concepts

At very high-level, underworlds can be seen as a shared (across threads and process) datastructure that represents on one hand geometric scenes (made of 3D meshes for instance) and on the other hand the history of these scenes as timelines. A pair (3D scene, timeline) forms a world.

_images/world.svg

A world is a 3D scene and its history, represented as a timeline

underworlds allows to create, alter, query, compare these worlds, their scences and timelines in a distributed fashion: one application (an underworlds client) can track the 3D position of humans around the robot, while another detect some objects on tables, while a third exposes the current pose of the robot itself. A fourth module can query these models to perform some motion planning, and a fifth one can performs geometric reasoning using a physics engine, and so on.

_images/worlds-chains-1.svg

Combining several processes in a cascade of worlds

The core library comes with a few useful components that can be used as starting points for your own components.

uwds-load for instance opens a static 3D model (like a FBX file) and adds it to a specific world. Let’s see how this example work.

The interesting part of the loading takes place in ModelLoader.load :

First, we create a context: the context encapsulates a connection to the shared datastructure. We give each context a name (typically, the name of the component – here model loader): this is useful to debug/introspect the system.

with underworlds.Context("model loader") as ctx:
    # ...

The context object ctx gives access to the shared worlds. For instance:

ctx.worlds["test"]

either returns the world test if it already exists (some other component may have created it, for instance) or it creates a new one (which becomes immediately visible and accessible to every other software components connected to the underworlds server).

Next, we can access the scene and the timeline attached to this world:

world = ctx.worlds["test"]
scene = world.scene
timeline = world.timeline

Keep in mind that world, scene, timeline are datastructures shared amongst all the software components (clients) connected to the server! A scene or a timeline can be updated at any time by any component! While you iterate over a scene (for 3D rendering for instance), underworlds makes no guarantee that the objects (nodes) will remain constant during the iteration, and you need to be especially careful for inconsistencies.

To avoid these inconsistencies as much as possible, software components are therefore generally advised to only write to worlds that they have themselves created. This is however not enforced, and sometimes it makes perfectly sense to have several components updating together the same world. One example could be several perception modules that estimate in parallel the pose of different objects: they would typically update a same world called for instance raw perception.

Scenes and nodes

A scene represents a 3D environment, made of a set of nodes: a node can represent either a abstract entity (or frame), a physical object (or part thereof), or a camera (more types of nodes may be added in the future, like fields). Node itself has several properties like a unique identifier, a name, possibly a list of children nodes, a 3D transformation matrix relative to its parent, etc.

_images/worlds-chains-3.svg

Meshes are centrally stored

Besides, nodes that represent physical objects (node.type == MESH) have meshes attached. Because meshes can represent a large amount of data, they are stored by the server on a separate static store, indexed by their hash value. This way, only the hashes of the meshes are stored with the node. If a specific component need the actual mesh data (for instance, for rendering), it must separately request the mesh data from the underworlds server (by calling ctx.get_mesh(<mesh hash>)).

Scenes always have one special node, the root node, and every other node in the scene is utimately parented to this node. It can be access with scene.rootnode.

to be continued…

Performances

The performance of your system can be tested by running testing/performances.py <nb worlds>. This script measure the propagation time of one change across n worlds by simulating (n-1) clients which simply replicate changes for one world to another one (passthrough filters).

For reference, propagating one change across ten worlds (on the same network host) take about 50 ms.

Due the changes in how the Python interpreter manages condition variables between Python2 and Python3, underworlds is significantly faster with Python 3 (an order of magnitude faster on certain tests!).

Investigating performance issues

underworlds can profile the network while running, which usually help with identifying performance issues.

To enable the profiler, change the value of PROFILING_ENABLED to True in helpers/profile.py, reinstall underworlds, and re-run your code.

API Reference

underworlds package

Subpackages

underworlds.helpers package

Submodules
underworlds.helpers.daemon module

Generic linux daemon base class for python 3.x.

Taken from http://www.jejik.com/articles/2007/02/a_simple_unix_linux_daemon_in_python/

class underworlds.helpers.daemon.Daemon(pidfile)

A generic daemon class.

Usage: subclass the daemon class and override the run() method.

daemonize()

Deamonize class. UNIX double fork mechanism.

delpid()
restart()

Restart the daemon.

run()

You should override this method when you subclass Daemon.

It will be called after the process has been daemonized by start() or restart().

start()

Start the daemon.

stop(restarting=False)

Stop the daemon.

underworlds.helpers.geometry module
underworlds.helpers.geometry.get_bounding_box_for_node(scene, node)
underworlds.helpers.geometry.get_scene_bounding_box(scene)

Returns the axis-aligned bounding box (AABB) of a whole scene, or None if the scene is empty.

underworlds.helpers.geometry.get_world_transform(scene, node)
underworlds.helpers.geometry.transform(vector3, matrix4x4)

Apply a transformation matrix on a 3D vector.

Parameters:
  • vector3 – a numpy array with 3 elements
  • matrix4x4 – a numpy 4x4 matrix
underworlds.helpers.geometry.transformed_aabb(scene, node)

TODO: this computation is incorrect! To compute a transformed AABB, we need to re-compute the AABB from the transformed vertices (or maybe from the transformed bounding box?)

underworlds.helpers.transformations module

Homogeneous Transformation Matrices and Quaternions.

A library for calculating 4x4 matrices for translating, rotating, reflecting, scaling, shearing, projecting, orthogonalizing, and superimposing arrays of 3D homogeneous coordinates as well as for converting between rotation matrices, Euler angles, and quaternions. Also includes an Arcball control object and functions to decompose transformation matrices.

Authors:Christoph Gohlke, Laboratory for Fluorescence Dynamics, University of California, Irvine
Version:20090418
Requirements
Notes

Matrices (M) can be inverted using numpy.linalg.inv(M), concatenated using numpy.dot(M0, M1), or used to transform homogeneous coordinates (v) using numpy.dot(M, v) for shape (4, *) “point of arrays”, respectively numpy.dot(v, M.T) for shape (*, 4) “array of points”.

Calculations are carried out with numpy.float64 precision.

This Python implementation is not optimized for speed.

Vector, point, quaternion, and matrix function arguments are expected to be “array like”, i.e. tuple, list, or numpy arrays.

Return types are numpy arrays unless specified otherwise.

Angles are in radians unless specified otherwise.

Quaternions ix+jy+kz+w are represented as [x, y, z, w].

Use the transpose of transformation matrices for OpenGL glMultMatrixd().

A triple of Euler angles can be applied/interpreted in 24 ways, which can be specified using a 4 character string or encoded 4-tuple:

Axes 4-string: e.g. ‘sxyz’ or ‘ryxy’

  • first character : rotations are applied to ‘s’tatic or ‘r’otating frame
  • remaining characters : successive rotation axis ‘x’, ‘y’, or ‘z’

Axes 4-tuple: e.g. (0, 0, 0, 0) or (1, 1, 1, 1)

  • inner axis: code of axis (‘x’:0, ‘y’:1, ‘z’:2) of rightmost matrix.
  • parity : even (0) if inner axis ‘x’ is followed by ‘y’, ‘y’ is followed by ‘z’, or ‘z’ is followed by ‘x’. Otherwise odd (1).
  • repetition : first and last axis are same (1) or different (0).
  • frame : rotations are applied to static (0) or rotating (1) frame.
References
  1. Matrices and transformations. Ronald Goldman. In “Graphics Gems I”, pp 472-475. Morgan Kaufmann, 1990.
  2. More matrices and transformations: shear and pseudo-perspective. Ronald Goldman. In “Graphics Gems II”, pp 320-323. Morgan Kaufmann, 1991.
  3. Decomposing a matrix into simple transformations. Spencer Thomas. In “Graphics Gems II”, pp 320-323. Morgan Kaufmann, 1991.
  4. Recovering the data from the transformation matrix. Ronald Goldman. In “Graphics Gems II”, pp 324-331. Morgan Kaufmann, 1991.
  5. Euler angle conversion. Ken Shoemake. In “Graphics Gems IV”, pp 222-229. Morgan Kaufmann, 1994.
  6. Arcball rotation control. Ken Shoemake. In “Graphics Gems IV”, pp 175-192. Morgan Kaufmann, 1994.
  7. Representing attitude: Euler angles, unit quaternions, and rotation vectors. James Diebel. 2006.
  8. A discussion of the solution for the best rotation to relate two sets of vectors. W Kabsch. Acta Cryst. 1978. A34, 827-828.
  9. Closed-form solution of absolute orientation using unit quaternions. BKP Horn. J Opt Soc Am A. 1987. 4(4), 629-642.
  10. Quaternions. Ken Shoemake. http://www.sfu.ca/~jwa3/cmpt461/files/quatut.pdf
  11. From quaternion to matrix and back. JMP van Waveren. 2005. http://www.intel.com/cd/ids/developer/asmo-na/eng/293748.htm
  12. Uniform random rotations. Ken Shoemake. In “Graphics Gems III”, pp 124-132. Morgan Kaufmann, 1992.
Examples
>>> alpha, beta, gamma = 0.123, -1.234, 2.345
>>> origin, xaxis, yaxis, zaxis = (0, 0, 0), (1, 0, 0), (0, 1, 0), (0, 0, 1)
>>> I = identity_matrix()
>>> Rx = rotation_matrix(alpha, xaxis)
>>> Ry = rotation_matrix(beta, yaxis)
>>> Rz = rotation_matrix(gamma, zaxis)
>>> R = concatenate_matrices(Rx, Ry, Rz)
>>> euler = euler_from_matrix(R, 'rxyz')
>>> numpy.allclose([alpha, beta, gamma], euler)
True
>>> Re = euler_matrix(alpha, beta, gamma, 'rxyz')
>>> is_same_transform(R, Re)
True
>>> al, be, ga = euler_from_matrix(Re, 'rxyz')
>>> is_same_transform(Re, euler_matrix(al, be, ga, 'rxyz'))
True
>>> qx = quaternion_about_axis(alpha, xaxis)
>>> qy = quaternion_about_axis(beta, yaxis)
>>> qz = quaternion_about_axis(gamma, zaxis)
>>> q = quaternion_multiply(qx, qy)
>>> q = quaternion_multiply(q, qz)
>>> Rq = quaternion_matrix(q)
>>> is_same_transform(R, Rq)
True
>>> S = scale_matrix(1.23, origin)
>>> T = translation_matrix((1, 2, 3))
>>> Z = shear_matrix(beta, xaxis, origin, zaxis)
>>> R = random_rotation_matrix(numpy.random.rand(3))
>>> M = concatenate_matrices(T, R, Z, S)
>>> scale, shear, angles, trans, persp = decompose_matrix(M)
>>> numpy.allclose(scale, 1.23)
True
>>> numpy.allclose(trans, (1, 2, 3))
True
>>> numpy.allclose(shear, (0, math.tan(beta), 0))
True
>>> is_same_transform(R, euler_matrix(axes='sxyz', *angles))
True
>>> M1 = compose_matrix(scale, shear, angles, trans, persp)
>>> is_same_transform(M, M1)
True
class underworlds.helpers.transformations.Arcball(initial=None)

Bases: object

Virtual Trackball Control.

>>> ball = Arcball()
>>> ball = Arcball(initial=numpy.identity(4))
>>> ball.place([320, 320], 320)
>>> ball.down([500, 250])
>>> ball.drag([475, 275])
>>> R = ball.matrix()
>>> numpy.allclose(numpy.sum(R), 3.90583455)
True
>>> ball = Arcball(initial=[0, 0, 0, 1])
>>> ball.place([320, 320], 320)
>>> ball.setaxes([1,1,0], [-1, 1, 0])
>>> ball.setconstrain(True)
>>> ball.down([400, 200])
>>> ball.drag([200, 400])
>>> R = ball.matrix()
>>> numpy.allclose(numpy.sum(R), 0.2055924)
True
>>> ball.next()
down(point)

Set initial cursor window coordinates and pick constrain-axis.

drag(point)

Update current cursor window coordinates.

getconstrain()

Return state of constrain to axis mode.

matrix()

Return homogeneous rotation matrix.

next(acceleration=0.0)

Continue rotation in direction of last drag.

place(center, radius)

Place Arcball, e.g. when window size changes.

center : sequence[2]
Window coordinates of trackball center.
radius : float
Radius of trackball in window coordinates.
setaxes(*axes)

Set axes to constrain rotations.

setconstrain(constrain)

Set state of constrain to axis mode.

underworlds.helpers.transformations.arcball_constrain_to_axis(point, axis)

Return sphere point perpendicular to axis.

underworlds.helpers.transformations.arcball_map_to_sphere(point, center, radius)

Return unit sphere coordinates from window coordinates.

underworlds.helpers.transformations.arcball_nearest_axis(point, axes)

Return axis, which arc is nearest to point.

underworlds.helpers.transformations.clip_matrix(left, right, bottom, top, near, far, perspective=False)

Return matrix to obtain normalized device coordinates from frustrum.

The frustrum bounds are axis-aligned along x (left, right), y (bottom, top) and z (near, far).

Normalized device coordinates are in range [-1, 1] if coordinates are inside the frustrum.

If perspective is True the frustrum is a truncated pyramid with the perspective point at origin and direction along z axis, otherwise an orthographic canonical view volume (a box).

Homogeneous coordinates transformed by the perspective clip matrix need to be dehomogenized (devided by w coordinate).

>>> frustrum = numpy.random.rand(6)
>>> frustrum[1] += frustrum[0]
>>> frustrum[3] += frustrum[2]
>>> frustrum[5] += frustrum[4]
>>> M = clip_matrix(*frustrum, perspective=False)
>>> numpy.dot(M, [frustrum[0], frustrum[2], frustrum[4], 1.0])
array([-1., -1., -1.,  1.])
>>> numpy.dot(M, [frustrum[1], frustrum[3], frustrum[5], 1.0])
array([ 1.,  1.,  1.,  1.])
>>> M = clip_matrix(*frustrum, perspective=True)
>>> v = numpy.dot(M, [frustrum[0], frustrum[2], frustrum[4], 1.0])
>>> v / v[3]
array([-1., -1., -1.,  1.])
>>> v = numpy.dot(M, [frustrum[1], frustrum[3], frustrum[4], 1.0])
>>> v / v[3]
array([ 1.,  1., -1.,  1.])
underworlds.helpers.transformations.compose_matrix(scale=None, shear=None, angles=None, translate=None, perspective=None)

Return transformation matrix from sequence of transformations.

This is the inverse of the decompose_matrix function.

Sequence of transformations:
scale : vector of 3 scaling factors shear : list of shear factors for x-y, x-z, y-z axes angles : list of Euler angles about static x, y, z axes translate : translation vector along x, y, z axes perspective : perspective partition of matrix
>>> scale = numpy.random.random(3) - 0.5
>>> shear = numpy.random.random(3) - 0.5
>>> angles = (numpy.random.random(3) - 0.5) * (2*math.pi)
>>> trans = numpy.random.random(3) - 0.5
>>> persp = numpy.random.random(4) - 0.5
>>> M0 = compose_matrix(scale, shear, angles, trans, persp)
>>> result = decompose_matrix(M0)
>>> M1 = compose_matrix(*result)
>>> is_same_transform(M0, M1)
True
underworlds.helpers.transformations.concatenate_matrices(*matrices)

Return concatenation of series of transformation matrices.

>>> M = numpy.random.rand(16).reshape((4, 4)) - 0.5
>>> numpy.allclose(M, concatenate_matrices(M))
True
>>> numpy.allclose(numpy.dot(M, M.T), concatenate_matrices(M, M.T))
True
underworlds.helpers.transformations.decompose_matrix(matrix)

Return sequence of transformations from transformation matrix.

matrix : array_like
Non-degenerative homogeneous transformation matrix
Return tuple of:
scale : vector of 3 scaling factors shear : list of shear factors for x-y, x-z, y-z axes angles : list of Euler angles about static x, y, z axes translate : translation vector along x, y, z axes perspective : perspective partition of matrix

Raise ValueError if matrix is of wrong type or degenerative.

>>> T0 = translation_matrix((1, 2, 3))
>>> scale, shear, angles, trans, persp = decompose_matrix(T0)
>>> T1 = translation_matrix(trans)
>>> numpy.allclose(T0, T1)
True
>>> S = scale_matrix(0.123)
>>> scale, shear, angles, trans, persp = decompose_matrix(S)
>>> scale[0]
0.123
>>> R0 = euler_matrix(1, 2, 3)
>>> scale, shear, angles, trans, persp = decompose_matrix(R0)
>>> R1 = euler_matrix(*angles)
>>> numpy.allclose(R0, R1)
True
underworlds.helpers.transformations.euler_from_matrix(matrix, axes='sxyz')

Return Euler angles from rotation matrix for specified axis sequence.

axes : One of 24 axis sequences as string or encoded tuple

Note that many Euler angle triplets can describe one matrix.

>>> R0 = euler_matrix(1, 2, 3, 'syxz')
>>> al, be, ga = euler_from_matrix(R0, 'syxz')
>>> R1 = euler_matrix(al, be, ga, 'syxz')
>>> numpy.allclose(R0, R1)
True
>>> angles = (4.0*math.pi) * (numpy.random.random(3) - 0.5)
>>> for axes in _AXES2TUPLE.keys():
...    R0 = euler_matrix(axes=axes, *angles)
...    R1 = euler_matrix(axes=axes, *euler_from_matrix(R0, axes))
...    if not numpy.allclose(R0, R1): print axes, "failed"
underworlds.helpers.transformations.euler_from_quaternion(quaternion, axes='sxyz')

Return Euler angles from quaternion for specified axis sequence.

>>> angles = euler_from_quaternion([0.06146124, 0, 0, 0.99810947])
>>> numpy.allclose(angles, [0.123, 0, 0])
True
underworlds.helpers.transformations.euler_matrix(ai, aj, ak, axes='sxyz')

Return homogeneous rotation matrix from Euler angles and axis sequence.

ai, aj, ak : Euler’s roll, pitch and yaw angles axes : One of 24 axis sequences as string or encoded tuple

>>> R = euler_matrix(1, 2, 3, 'syxz')
>>> numpy.allclose(numpy.sum(R[0]), -1.34786452)
True
>>> R = euler_matrix(1, 2, 3, (0, 1, 0, 1))
>>> numpy.allclose(numpy.sum(R[0]), -0.383436184)
True
>>> ai, aj, ak = (4.0*math.pi) * (numpy.random.random(3) - 0.5)
>>> for axes in _AXES2TUPLE.keys():
...    R = euler_matrix(ai, aj, ak, axes)
>>> for axes in _TUPLE2AXES.keys():
...    R = euler_matrix(ai, aj, ak, axes)
underworlds.helpers.transformations.identity_matrix()

Return 4x4 identity/unit matrix.

>>> I = identity_matrix()
>>> numpy.allclose(I, numpy.dot(I, I))
True
>>> numpy.sum(I), numpy.trace(I)
(4.0, 4.0)
>>> numpy.allclose(I, numpy.identity(4, dtype=numpy.float64))
True
underworlds.helpers.transformations.inverse_matrix(matrix)

Return inverse of square transformation matrix.

>>> M0 = random_rotation_matrix()
>>> M1 = inverse_matrix(M0.T)
>>> numpy.allclose(M1, numpy.linalg.inv(M0.T))
True
>>> for size in range(1, 7):
...     M0 = numpy.random.rand(size, size)
...     M1 = inverse_matrix(M0)
...     if not numpy.allclose(M1, numpy.linalg.inv(M0)): print size
underworlds.helpers.transformations.is_same_transform(matrix0, matrix1)

Return True if two matrices perform same transformation.

>>> is_same_transform(numpy.identity(4), numpy.identity(4))
True
>>> is_same_transform(numpy.identity(4), random_rotation_matrix())
False
underworlds.helpers.transformations.orthogonalization_matrix(lengths, angles)

Return orthogonalization matrix for crystallographic cell coordinates.

Angles are expected in degrees.

The de-orthogonalization matrix is the inverse.

>>> O = orthogonalization_matrix((10., 10., 10.), (90., 90., 90.))
>>> numpy.allclose(O[:3, :3], numpy.identity(3, float) * 10)
True
>>> O = orthogonalization_matrix([9.8, 12.0, 15.5], [87.2, 80.7, 69.7])
>>> numpy.allclose(numpy.sum(O), 43.063229)
True
underworlds.helpers.transformations.projection_from_matrix(matrix, pseudo=False)

Return projection plane and perspective point from projection matrix.

Return values are same as arguments for projection_matrix function: point, normal, direction, perspective, and pseudo.

>>> point = numpy.random.random(3) - 0.5
>>> normal = numpy.random.random(3) - 0.5
>>> direct = numpy.random.random(3) - 0.5
>>> persp = numpy.random.random(3) - 0.5
>>> P0 = projection_matrix(point, normal)
>>> result = projection_from_matrix(P0)
>>> P1 = projection_matrix(*result)
>>> is_same_transform(P0, P1)
True
>>> P0 = projection_matrix(point, normal, direct)
>>> result = projection_from_matrix(P0)
>>> P1 = projection_matrix(*result)
>>> is_same_transform(P0, P1)
True
>>> P0 = projection_matrix(point, normal, perspective=persp, pseudo=False)
>>> result = projection_from_matrix(P0, pseudo=False)
>>> P1 = projection_matrix(*result)
>>> is_same_transform(P0, P1)
True
>>> P0 = projection_matrix(point, normal, perspective=persp, pseudo=True)
>>> result = projection_from_matrix(P0, pseudo=True)
>>> P1 = projection_matrix(*result)
>>> is_same_transform(P0, P1)
True
underworlds.helpers.transformations.projection_matrix(point, normal, direction=None, perspective=None, pseudo=False)

Return matrix to project onto plane defined by point and normal.

Using either perspective point, projection direction, or none of both.

If pseudo is True, perspective projections will preserve relative depth such that Perspective = dot(Orthogonal, PseudoPerspective).

>>> P = projection_matrix((0, 0, 0), (1, 0, 0))
>>> numpy.allclose(P[1:, 1:], numpy.identity(4)[1:, 1:])
True
>>> point = numpy.random.random(3) - 0.5
>>> normal = numpy.random.random(3) - 0.5
>>> direct = numpy.random.random(3) - 0.5
>>> persp = numpy.random.random(3) - 0.5
>>> P0 = projection_matrix(point, normal)
>>> P1 = projection_matrix(point, normal, direction=direct)
>>> P2 = projection_matrix(point, normal, perspective=persp)
>>> P3 = projection_matrix(point, normal, perspective=persp, pseudo=True)
>>> is_same_transform(P2, numpy.dot(P0, P3))
True
>>> P = projection_matrix((3, 0, 0), (1, 1, 0), (1, 0, 0))
>>> v0 = (numpy.random.rand(4, 5) - 0.5) * 20.0
>>> v0[3] = 1.0
>>> v1 = numpy.dot(P, v0)
>>> numpy.allclose(v1[1], v0[1])
True
>>> numpy.allclose(v1[0], 3.0-v1[1])
True
underworlds.helpers.transformations.quaternion_about_axis(angle, axis)

Return quaternion for rotation about axis.

>>> q = quaternion_about_axis(0.123, (1, 0, 0))
>>> numpy.allclose(q, [0.06146124, 0, 0, 0.99810947])
True
underworlds.helpers.transformations.quaternion_conjugate(quaternion)

Return conjugate of quaternion.

>>> q0 = random_quaternion()
>>> q1 = quaternion_conjugate(q0)
>>> q1[3] == q0[3] and all(q1[:3] == -q0[:3])
True
underworlds.helpers.transformations.quaternion_from_euler(ai, aj, ak, axes='sxyz')

Return quaternion from Euler angles and axis sequence.

ai, aj, ak : Euler’s roll, pitch and yaw angles axes : One of 24 axis sequences as string or encoded tuple

>>> q = quaternion_from_euler(1, 2, 3, 'ryxz')
>>> numpy.allclose(q, [0.310622, -0.718287, 0.444435, 0.435953])
True
underworlds.helpers.transformations.quaternion_from_matrix(matrix)

Return quaternion from rotation matrix.

>>> R = rotation_matrix(0.123, (1, 2, 3))
>>> q = quaternion_from_matrix(R)
>>> numpy.allclose(q, [0.0164262, 0.0328524, 0.0492786, 0.9981095])
True
underworlds.helpers.transformations.quaternion_inverse(quaternion)

Return inverse of quaternion.

>>> q0 = random_quaternion()
>>> q1 = quaternion_inverse(q0)
>>> numpy.allclose(quaternion_multiply(q0, q1), [0, 0, 0, 1])
True
underworlds.helpers.transformations.quaternion_matrix(quaternion)

Return homogeneous rotation matrix from quaternion.

>>> R = quaternion_matrix([0.06146124, 0, 0, 0.99810947])
>>> numpy.allclose(R, rotation_matrix(0.123, (1, 0, 0)))
True
underworlds.helpers.transformations.quaternion_multiply(quaternion1, quaternion0)

Return multiplication of two quaternions.

>>> q = quaternion_multiply([1, -2, 3, 4], [-5, 6, 7, 8])
>>> numpy.allclose(q, [-44, -14, 48, 28])
True
underworlds.helpers.transformations.quaternion_slerp(quat0, quat1, fraction, spin=0, shortestpath=True)

Return spherical linear interpolation between two quaternions.

>>> q0 = random_quaternion()
>>> q1 = random_quaternion()
>>> q = quaternion_slerp(q0, q1, 0.0)
>>> numpy.allclose(q, q0)
True
>>> q = quaternion_slerp(q0, q1, 1.0, 1)
>>> numpy.allclose(q, q1)
True
>>> q = quaternion_slerp(q0, q1, 0.5)
>>> angle = math.acos(numpy.dot(q0, q))
>>> numpy.allclose(2.0, math.acos(numpy.dot(q0, q1)) / angle) or         numpy.allclose(2.0, math.acos(-numpy.dot(q0, q1)) / angle)
True
underworlds.helpers.transformations.random_quaternion(rand=None)

Return uniform random unit quaternion.

rand: array like or None
Three independent random variables that are uniformly distributed between 0 and 1.
>>> q = random_quaternion()
>>> numpy.allclose(1.0, vector_norm(q))
True
>>> q = random_quaternion(numpy.random.random(3))
>>> q.shape
(4,)
underworlds.helpers.transformations.random_rotation_matrix(rand=None)

Return uniform random rotation matrix.

rnd: array like
Three independent random variables that are uniformly distributed between 0 and 1 for each returned quaternion.
>>> R = random_rotation_matrix()
>>> numpy.allclose(numpy.dot(R.T, R), numpy.identity(4))
True
underworlds.helpers.transformations.random_vector(size)

Return array of random doubles in the half-open interval [0.0, 1.0).

>>> v = random_vector(10000)
>>> numpy.all(v >= 0.0) and numpy.all(v < 1.0)
True
>>> v0 = random_vector(10)
>>> v1 = random_vector(10)
>>> numpy.any(v0 == v1)
False
underworlds.helpers.transformations.reflection_from_matrix(matrix)

Return mirror plane point and normal vector from reflection matrix.

>>> v0 = numpy.random.random(3) - 0.5
>>> v1 = numpy.random.random(3) - 0.5
>>> M0 = reflection_matrix(v0, v1)
>>> point, normal = reflection_from_matrix(M0)
>>> M1 = reflection_matrix(point, normal)
>>> is_same_transform(M0, M1)
True
underworlds.helpers.transformations.reflection_matrix(point, normal)

Return matrix to mirror at plane defined by point and normal vector.

>>> v0 = numpy.random.random(4) - 0.5
>>> v0[3] = 1.0
>>> v1 = numpy.random.random(3) - 0.5
>>> R = reflection_matrix(v0, v1)
>>> numpy.allclose(2., numpy.trace(R))
True
>>> numpy.allclose(v0, numpy.dot(R, v0))
True
>>> v2 = v0.copy()
>>> v2[:3] += v1
>>> v3 = v0.copy()
>>> v2[:3] -= v1
>>> numpy.allclose(v2, numpy.dot(R, v3))
True
underworlds.helpers.transformations.rotation_from_matrix(matrix)

Return rotation angle and axis from rotation matrix.

>>> angle = (random.random() - 0.5) * (2*math.pi)
>>> direc = numpy.random.random(3) - 0.5
>>> point = numpy.random.random(3) - 0.5
>>> R0 = rotation_matrix(angle, direc, point)
>>> angle, direc, point = rotation_from_matrix(R0)
>>> R1 = rotation_matrix(angle, direc, point)
>>> is_same_transform(R0, R1)
True
underworlds.helpers.transformations.rotation_matrix(angle, direction, point=None)

Return matrix to rotate about axis defined by point and direction.

>>> angle = (random.random() - 0.5) * (2*math.pi)
>>> direc = numpy.random.random(3) - 0.5
>>> point = numpy.random.random(3) - 0.5
>>> R0 = rotation_matrix(angle, direc, point)
>>> R1 = rotation_matrix(angle-2*math.pi, direc, point)
>>> is_same_transform(R0, R1)
True
>>> R0 = rotation_matrix(angle, direc, point)
>>> R1 = rotation_matrix(-angle, -direc, point)
>>> is_same_transform(R0, R1)
True
>>> I = numpy.identity(4, numpy.float64)
>>> numpy.allclose(I, rotation_matrix(math.pi*2, direc))
True
>>> numpy.allclose(2., numpy.trace(rotation_matrix(math.pi/2,
...                                                direc, point)))
True
underworlds.helpers.transformations.scale_from_matrix(matrix)

Return scaling factor, origin and direction from scaling matrix.

>>> factor = random.random() * 10 - 5
>>> origin = numpy.random.random(3) - 0.5
>>> direct = numpy.random.random(3) - 0.5
>>> S0 = scale_matrix(factor, origin)
>>> factor, origin, direction = scale_from_matrix(S0)
>>> S1 = scale_matrix(factor, origin, direction)
>>> is_same_transform(S0, S1)
True
>>> S0 = scale_matrix(factor, origin, direct)
>>> factor, origin, direction = scale_from_matrix(S0)
>>> S1 = scale_matrix(factor, origin, direction)
>>> is_same_transform(S0, S1)
True
underworlds.helpers.transformations.scale_matrix(factor, origin=None, direction=None)

Return matrix to scale by factor around origin in direction.

Use factor -1 for point symmetry.

>>> v = (numpy.random.rand(4, 5) - 0.5) * 20.0
>>> v[3] = 1.0
>>> S = scale_matrix(-1.234)
>>> numpy.allclose(numpy.dot(S, v)[:3], -1.234*v[:3])
True
>>> factor = random.random() * 10 - 5
>>> origin = numpy.random.random(3) - 0.5
>>> direct = numpy.random.random(3) - 0.5
>>> S = scale_matrix(factor, origin)
>>> S = scale_matrix(factor, origin, direct)
underworlds.helpers.transformations.shear_from_matrix(matrix)

Return shear angle, direction and plane from shear matrix.

>>> angle = (random.random() - 0.5) * 4*math.pi
>>> direct = numpy.random.random(3) - 0.5
>>> point = numpy.random.random(3) - 0.5
>>> normal = numpy.cross(direct, numpy.random.random(3))
>>> S0 = shear_matrix(angle, direct, point, normal)
>>> angle, direct, point, normal = shear_from_matrix(S0)
>>> S1 = shear_matrix(angle, direct, point, normal)
>>> is_same_transform(S0, S1)
True
underworlds.helpers.transformations.shear_matrix(angle, direction, point, normal)

Return matrix to shear by angle along direction vector on shear plane.

The shear plane is defined by a point and normal vector. The direction vector must be orthogonal to the plane’s normal vector.

A point P is transformed by the shear matrix into P” such that the vector P-P” is parallel to the direction vector and its extent is given by the angle of P-P’-P”, where P’ is the orthogonal projection of P onto the shear plane.

>>> angle = (random.random() - 0.5) * 4*math.pi
>>> direct = numpy.random.random(3) - 0.5
>>> point = numpy.random.random(3) - 0.5
>>> normal = numpy.cross(direct, numpy.random.random(3))
>>> S = shear_matrix(angle, direct, point, normal)
>>> numpy.allclose(1.0, numpy.linalg.det(S))
True
underworlds.helpers.transformations.superimposition_matrix(v0, v1, scaling=False, usesvd=True)

Return matrix to transform given vector set into second vector set.

v0 and v1 are shape (3, *) or (4, *) arrays of at least 3 vectors.

If usesvd is True, the weighted sum of squared deviations (RMSD) is minimized according to the algorithm by W. Kabsch [8]. Otherwise the quaternion based algorithm by B. Horn [9] is used (slower when using this Python implementation).

The returned matrix performs rotation, translation and uniform scaling (if specified).

>>> v0 = numpy.random.rand(3, 10)
>>> M = superimposition_matrix(v0, v0)
>>> numpy.allclose(M, numpy.identity(4))
True
>>> R = random_rotation_matrix(numpy.random.random(3))
>>> v0 = ((1,0,0), (0,1,0), (0,0,1), (1,1,1))
>>> v1 = numpy.dot(R, v0)
>>> M = superimposition_matrix(v0, v1)
>>> numpy.allclose(v1, numpy.dot(M, v0))
True
>>> v0 = (numpy.random.rand(4, 100) - 0.5) * 20.0
>>> v0[3] = 1.0
>>> v1 = numpy.dot(R, v0)
>>> M = superimposition_matrix(v0, v1)
>>> numpy.allclose(v1, numpy.dot(M, v0))
True
>>> S = scale_matrix(random.random())
>>> T = translation_matrix(numpy.random.random(3)-0.5)
>>> M = concatenate_matrices(T, R, S)
>>> v1 = numpy.dot(M, v0)
>>> v0[:3] += numpy.random.normal(0.0, 1e-9, 300).reshape(3, -1)
>>> M = superimposition_matrix(v0, v1, scaling=True)
>>> numpy.allclose(v1, numpy.dot(M, v0))
True
>>> M = superimposition_matrix(v0, v1, scaling=True, usesvd=False)
>>> numpy.allclose(v1, numpy.dot(M, v0))
True
>>> v = numpy.empty((4, 100, 3), dtype=numpy.float64)
>>> v[:, :, 0] = v0
>>> M = superimposition_matrix(v0, v1, scaling=True, usesvd=False)
>>> numpy.allclose(v1, numpy.dot(M, v[:, :, 0]))
True
underworlds.helpers.transformations.translation_from_matrix(matrix)

Return translation vector from translation matrix.

>>> v0 = numpy.random.random(3) - 0.5
>>> v1 = translation_from_matrix(translation_matrix(v0))
>>> numpy.allclose(v0, v1)
True
underworlds.helpers.transformations.translation_matrix(direction)

Return matrix to translate by direction vector.

>>> v = numpy.random.random(3) - 0.5
>>> numpy.allclose(v, translation_matrix(v)[:3, 3])
True
underworlds.helpers.transformations.unit_vector(data, axis=None, out=None)

Return ndarray normalized by length, i.e. eucledian norm, along axis.

>>> v0 = numpy.random.random(3)
>>> v1 = unit_vector(v0)
>>> numpy.allclose(v1, v0 / numpy.linalg.norm(v0))
True
>>> v0 = numpy.random.rand(5, 4, 3)
>>> v1 = unit_vector(v0, axis=-1)
>>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=2)), 2)
>>> numpy.allclose(v1, v2)
True
>>> v1 = unit_vector(v0, axis=1)
>>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=1)), 1)
>>> numpy.allclose(v1, v2)
True
>>> v1 = numpy.empty((5, 4, 3), dtype=numpy.float64)
>>> unit_vector(v0, axis=1, out=v1)
>>> numpy.allclose(v1, v2)
True
>>> list(unit_vector([]))
[]
>>> list(unit_vector([1.0]))
[1.0]
underworlds.helpers.transformations.vector_norm(data, axis=None, out=None)

Return length, i.e. eucledian norm, of ndarray along axis.

>>> v = numpy.random.random(3)
>>> n = vector_norm(v)
>>> numpy.allclose(n, numpy.linalg.norm(v))
True
>>> v = numpy.random.rand(6, 5, 3)
>>> n = vector_norm(v, axis=-1)
>>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=2)))
True
>>> n = vector_norm(v, axis=1)
>>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=1)))
True
>>> v = numpy.random.rand(5, 4, 3)
>>> n = numpy.empty((5, 3), dtype=numpy.float64)
>>> vector_norm(v, axis=1, out=n)
>>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=1)))
True
>>> vector_norm([])
0.0
>>> vector_norm([1.0])
1.0
Module contents

underworlds.tools package

Submodules
underworlds.tools.loader module
class underworlds.tools.loader.ModelLoader
fill_node_details(assimp_node, underworlds_node, assimp_model, custom_root=None, scale=1.0)
load(filename, ctx=None, world='base', root=None, only_meshes=False, scale=1.0)

Loads a Collada (or any Assimp compatible model) file in the world.

The kinematic chains are added to the world’s geometric state. The meshes are added to the meshes repository.

A new ‘load’ event is also added in the world timeline.

Parameters:
  • path (string) – the path (relative or absolute) to the Collada resource
  • ctx (Context) – an existing underworlds context. If not provided, a new one is created (named ‘model loader’)
  • world (string) – the target world for the creation of nodes
  • root (Node) – if given, the loaded nodes will be parented to this node instead of the scene’s root.
  • only_meshes (bool) – if true, no node is created. Only the

meshes are pushed to the server. :param float scale : scale of the model :returns: the list of loaded underworlds nodes.

load_meshes(filename, ctx=None, scale=1.0)

Pushes meshes from any Assimp-compatible 3D model to the server’s mesh repository.

A new ‘load’ event is also added in the world timeline.

Parameters:
  • path (string) – the path (relative or absolute) to the 3D model
  • ctx (Context) – an existing underworlds context. If not provided, a new one is created (named ‘model loader’)

:param float scale : scale of the model :returns: a dictionary {mesh name: mesh ID}

See:load loads the meshes and creates corresponding nodes.
node_boundingbox(node)

Returns the AABB bounding box of an ASSIMP node. Be careful: this is the untransformed bounding box, ie, the bounding box of the mesh in the node frame.

recur_node(assimp_node, model, level=0)
Module contents

Submodules

underworlds.errors module

exception underworlds.errors.TimeoutError(value)

Bases: underworlds.errors.UnderworldsError

exception underworlds.errors.UnderworldsError(value)

Bases: exceptions.Exception

underworlds.server module

class underworlds.server.Client(name, host, port)
close()
emit_invalidation(invalidation)
class underworlds.server.Server

Bases: underworlds.underworlds_pb2.BetaUnderworldsServicer

byebye(client, context)

Inform the server that the client is disconnecting. Before completing this call, the client must keep its invalidation server open and listening. After completing this call, the server should not attempt to connect to the client’s invalidation server.

deleteNodes(nodesInCtxt, context)

Deletes (and broadcasts to all client) nodes in a given world

deleteSituations(sitInCtxt, context)

Deletes (and broadcasts to all client) a node in a given world

getMesh(meshInCtxt, context)

Returns a 3D mesh. Note that only the ID of the input mesh is used.

getNode(nodeInCtxt, context)

Returns a node from its ID in the given world. Note that only the node ID is used (and thus, required).

getNodesIds(ctxt, context)

Returns the list of node IDs present in the given world

getNodesLen(ctxt, context)

NODES

Returns the number of nodes in a given world. Accepts a context (client ID and world) and returns the number of existing nodes.

getRootNode(ctxt, context)

Returns the root node ID of the given world

getSituation(sitInCtxt, context)

Returns a situation from its ID. Note that only the situation ID is used (and thus, required).

getSituationsIds(ctxt, context)

Returns the list of situation IDs present in the given world

getSituationsLen(ctxt, context)

TIMELINE

Returns the number of situations in a given world. Accepts a context (client ID and world) and returns the number of existing situations.

hasMesh(meshInCtxt, context)

MESHES

Returns whether the given mesh is already available on the server. Note that only the mesh ID is used.

helo(client, context)

GENERAL

Establish the connection to the server, setting a human-friendly name for the client. The server returns a unique client ID that must be used in every subsequent request to the server.

pushMesh(meshInCtxt, context)

Sends a 3D mesh to the server.

reset(client, context)

Hard reset of Underworlds: all the worlds are deleted. The existing mesh database is kept, however. This does not impact the list of known clients (ie, clients do not have to call ‘helo’ again).

timelineOrigin(ctxt, context)

Returns the timeline origin: time of the timeline creation

topology(client, context)

Returns the current topology of underworlds: the list of worlds and the list of clients + their interactions with the worlds

updateNodes(nodesInCtxt, context)

Updates (and broadcasts to all client) nodes in a given world

updateSituations(sitInCtxt, context)

Updates (and broadcasts to all client) a situation in a given world

uptime(client, context)

Returns the uptime of the server, in seconds

underworlds.server.start(port=50051, signaling_queue=None)

Starts the underworlds server in a thread on the given port and returns the resulting gRPC server.

If signaling_queue is provided, the behaviour is blocking: it creates and start an underworlds server, then blocks until something is pushed onto the queue. It then properly closes the server and returns None.

underworlds.server.start_process(port=50051)

underworlds.services module

underworlds.situations module

underworlds.types module

class underworlds.types.Camera(name='')

Bases: underworlds.types.Node

class underworlds.types.Entity(name='')

Bases: underworlds.types.Node

class underworlds.types.EventMonitor(evt)

Bases: object

call(cb)
make_call()
wait(timeout=0)

Blocks until an event occurs, or the timeout expires.

class underworlds.types.Mesh(name='')

Bases: underworlds.types.Node

class underworlds.types.MeshData(vertices, faces, normals, diffuse=(1, 1, 1, 1))

Bases: object

static deserialize(data)

Creates a Python mesh object from a protobuf encoding.

serialize(MeshType)

Outputs a protobuf encoding of the mesh

The MeshType (underworlds_pb2.Mesh) needs to be passed as parameter to prevent the creation of a 2nd instance of the underworlds_pb2 that crashes the gRPC. Not sure why… Similar to http://stackoverflow.com/questions/32010905/unbound-method-must-be-called-with-x-instance-as-first-argument-got-x-instance

class underworlds.types.Node(name='', type=0)

Bases: object

children
copy()

Performs a deep-copy of myself, and return the copy. The copy has a new, different, unique ID (ie, the ID & children are not copied).

static deserialize(data)

Creates a node from a protobuf encoding.

serialize(NodeType)

Outputs a protobuf encoding of the node

The NodeType (underworlds_pb2.Node) needs to be passed as parameter to prevent the creation of a 2nd instance of the underworlds_pb2 that crashes the gRPC. Not sure why… Similar to http://stackoverflow.com/questions/32010905/unbound-method-must-be-called-with-x-instance-as-first-argument-got-x-instance

translate(vector)

Translates the node by a vector. The change is not propagated automatically (you must call nodes.update(…)).

translation()
Returns:a numpy vector (x, y, z) representing the current translation of the node wrt to its parent.
type
class underworlds.types.Scene

Bases: object

An Underworlds scene

list_entities()

Returns the list of entities contained in the scene.

node(id)

Returns a node from its ID (or None if the node does not exist)

nodebyname(name)

Returns a list of node that have the given name (or [] if no node has this name)

class underworlds.types.Situation(desc='', type=0)

Bases: object

A situation represents a generic temporal object.

It has two subclasses:
  • events, which are instantaneous situations (null duration)
  • static situations, that have a duration.
copy()

Performs a deep-copy of myself, and return the copy. The copy has a new, different, unique ID (ie, the ID & children are not copied).

static deserialize(data)

Creates a situation from a protobuf encoding.

isevent()
serialize(SituationType)

Outputs a protobuf encoding of the situation

The SituationType (underworlds_pb2.Situation) needs to be passed as parameter to prevent the creation of a 2nd instance of the underworlds_pb2 that crashes the gRPC. Not sure why… Similar to http://stackoverflow.com/questions/32010905/unbound-method-must-be-called-with-x-instance-as-first-argument-got-x-instance

class underworlds.types.Timeline

Bases: object

Stores ‘situations’ (ie, either events – temporal objects without duration – or static situations – temporal objects with a non-null duration).

A timeline also exposes an API to find for temporal patterns.

TODO: situations are currently stored as a flat array, which is certainly not the most efficient way!

append(situation)

Adds the given situation to the timeline.

If a situation with the same ID already exists, it replaces it.

Returns:True if the situation has been added, False if it has simply updated an existing situation
end(situation)

Asserts the end of a situation.

Note that in the special case of events, this method a no effect.

event()

Asserts a new event occured in this timeline.

Returns:the newly created event.
on(event)

Creates a new EventMonitor to watch a given event model.

Typical use is:

>>> t = Timeline()
>>> e = Event(...)
>>>
>>> def onevt(evt):
>>>    print(evt)
>>>
>>> t.on(e).call(onevt)
Returns:a new instance of EventMonitor for this event.
remove(situation)

Deletes an existing situation.

situation(id)
start()

Asserts a situation has started.

Note that in the special case of events, the situation ends immediately.

Returns:The newly created situation
update(situation)

Update (ie, replace) an existing situation with the given one.

If the situations does not exist, simply add it to the timeline.

Returns:True if the situation has been updated, False if it has been simply added (new situation)
class underworlds.types.World(name)

Bases: object

deepcopy(world)

Module contents

class underworlds.Context(name, host='localhost', port=50051)

Bases: object

close()
has_mesh(id)
mesh(id)
push_mesh(mesh)
reset()

Hard reset of Underworlds: all the worlds are deleted. The existing mesh database is kept, however. This does not impact the list of known clients (ie, clients do not have to call ‘helo’ again).

topology()

Returns the current topology to the underworlds environment.

It returns an object with two members: - ‘worlds’: the list of all worlds’ names known to the system - ‘clients’: the list of known clients. Each client is an object with

the following members: - client.id - client.name - client.links: a list of the ‘links’ between this client and the

worlds. Each link has the following members: - link.world - link.type: READER, PROVIDER, FILTER, MONITOR, see types.py - link.last_activity: the timestamp of the last time this link has been used
uptime()

Returns the server uptime in seconds.

class underworlds.InvalidationServer(ctx)

Bases: underworlds.underworlds_pb2.BetaUnderworldsInvalidationServicer

emitInvalidation(invalidation, context)

Sends (to the client’s invalidation server) ‘invalidated’ nodes/situations that need to be updated. Invalidated nodes/situations can be new nodes/situations, nodes/situations that have changed, or nodes/situations that have been removed (see Invalidation.type).

class underworlds.NodesProxy(context, world)
append(nodes)

Adds one or several new nodes to the node set.

It is actually an alias for NodesProxy.update: all the restrictions regarding ordering or propagation time apply as well.

Parameters:nodes – a single node instance, or a sequence of node instances.
remove(nodes)

Deletes one or several nodes from the node set.

THIS METHOD DOES NOT DIRECTLY delete the local copy of the nodes: it tells instead the server to delete these nodes for all clients. The roundtrip is slower, but data consistency is easier to ensure.

This means that if you delete a node, the node won’t be actually deleted immediately. It will take some time (a couple of milliseconds) to propagate the change.

If the deleted node(s) have children, the children are reparented to the root node.

Parameters:nodes – a single node instance, or a sequence of node instances.
update(nodes)

Update the value of one or several nodes in the node set. If the node(s) do(es) not exist yet, add them.

This method sends the new/updated nodes to the remote. IT DOES NOT DIRECTLY modify the local copy of nodes: the roundtrip is slower, but data consistency is easier to ensure.

This means that if you create or update a node, the node won’t be created/updated immediately. It will take some time (a couple of milliseconds) to propagate the change.

Also, you have no guarantee regarding the ordering:

for instance,

>>> nodes.update(n1)
>>> nodes.update(n2)

does not mean that nodes[0] = n1 and nodes[1] = n2. This is due to the lazy access process.

However, once accessed once, nodes keep their index (until a node with a smaller index is removed).

Parameters:nodes – a single node instance, or a sequence of node instances.
class underworlds.SceneProxy(ctx, world)

Bases: object

append_and_propagate(nodes)

An alias for NodesProxy.append

nodebyname(name)

Returns a list of node that have the given name (or [] if no node has this name)

remove_and_propagate(nodes)

An alias for NodesProxy.remove

rootnode
update_and_propagate(nodes)

An alias for NodesProxy.update

waitforchanges(timeout=None)

This method blocks until either the scene has been updated (a node has been either updated, added or removed) or the timeout is over.

Parameters:timeout – timeout in seconds (float value)
Returns:the change that occured as a pair [[node ids], operation]

(operation is one of UPDATE, NEW, DELETE) or None if the timeout has been reached.

class underworlds.TimelineProxy(ctx, world)
append(situations)

Adds one or several new situations to the timeline.

It is actually an alias for TimelineProxy.update: all the restrictions regarding ordering or propagation time apply as well.

Parameters:situations – a single situation instance, or a sequence of situation instances.
end(situation)

Ends an existing situation

This method sends the situation update to the remote. IT DOES NOT DIRECTLY modify the local copy of situations: the roundtrip is slower, but data consistency is easier to ensure.

Note that the situation ending time is set by the client, at the time at which this method is called.

event()

Creates (and return) a new event (situation with 0 duration)

This method sends the new event to the remote. IT DOES NOT DIRECTLY modify the local copy of situations: the roundtrip is slower, but data consistency is easier to ensure.

Note that the event time is set by the client, at the time at which this method is called.

remove(situations)

Deletes one or several situations.

THIS METHOD DOES NOT DIRECTLY delete the local copy of the situations: it tells instead the server to delete this situation for all clients. the roundtrip is slower, but data consistency is easier to ensure.

This means that if you delete a situation, the situation won’t be actually deleted immediately. It will take some time (a couple of milliseconds) to propagate the change.

Parameters:situations – a single situation instance, or a sequence of situation instances.
start()

Starts (and return) a new situation

This method sends the new situation to the remote. IT DOES NOT DIRECTLY modify the local copy of situations: the roundtrip is slower, but data consistency is easier to ensure.

Note that the situation starting time is set by the client, at the time at which this method is called.

update(situations)

Update the value of a situation. If the situation does not exist yet, add it.

This method sends the new/updated situations to the remote. IT DOES NOT DIRECTLY modify the local copy of situations: the roundtrip is slower, but data consistency is easier to ensure.

This means that if you create or update a situation, the situation won’t be created/updated immediately. It will take some time (a couple of milliseconds) to propagate the change.

Also, you have no guarantee regarding the ordering:

for instance,

>>> timeline.update(sit1)
>>> timeline.update(sit2)

does not mean that timeline[0] = sit1 and timeline[1] = sit2. This is due to the lazy access process.

However, once accessed once, situations keep their index (until a situation with a smaller index is removed).

Parameters:situations – a single situation instance, or a sequence of situation instances.
waitforchanges(timeout=None)

This method blocks until either the timeline has been updated (a situation has been either started or ended) or the timeout is over.

Parameters:timeout – timeout in seconds (float value)
Returns:the change that occured as a pair [[node ids], operation]

(operation is one of UPDATE, NEW, DELETE) or None if the timeout has been reached.

class underworlds.WorldProxy(ctx, name)
copy_from(world)

Creates and/or replaces the content of the world with an exact copy of the given world.

class underworlds.WorldsProxy(ctx)

Indices and tables