underworlds package

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)