An Introduction to MORSE
The Modular OpenRobots Simulation Engine

The Cat & Mouse game
First demo: Chasing the mouse!
We start the presentation with a concrete example: the 'Cat and Mouse' game
Do the full demo, but without too many explantions (for now):

Example breakdown

from morse.builder import *

# Our mouse
mouse = ATRV()
mouse.translate(x=1.0, z=0.2)
mouse.properties(Object = True, Graspable = False, Label = "MOUSE")

keyboard = Keyboard()
keyboard.properties(Speed=3.0)
mouse.append(keyboard)

Example breakdown (continued)

# Our cat
cat = ATRV()
cat.translate(x=-6.0, z=0.2)

cameraL = SemanticCamera()
cameraL.translate(x=0.2, y=0.3, z=0.9)
cat.append(cameraL)

cameraR = SemanticCamera()
cameraR.translate(x=0.2, y=-0.3, z=0.9)
cat.append(cameraR)

motion = MotionVW()
cat.append(motion)

motion.add_stream('socket')
cameraL.add_stream('socket')
cameraR.add_stream('socket')

# The environment
env = Environment('land-1/trees')

Presentation outline

MORSE foundations

The MORSE project

Blender interface
Blender and Blender Game Engine
Bullet physics engine
Video by microcontroled1204 (YouTube)

Modularity
and the MORSE main loop

Levels of abstraction: level 0
Levels of abstraction: vision level
This set of 4 slides show how MORSE can be used at different level of abstraction: from 'few things simulated, lot of robot software running' to 'almost everything simulated, only high-level robot softwares'.
Levels of abstraction: level 1
Levels of abstraction: depth map level
Levels of abstraction: level 2
Levels of abstraction: terrain level
Levels of abstraction: level 3
Levels of abstraction: semantic level
SAIL architecture
SAIL: Software Architecture In the Loop
A seamless transition of the robotics functions from a simulated case to an actual robot is essential. ⇒ Middleware independence + middleware connectivity
MORSE main loop

The MORSE main loop: summary

Inside MORSE's components

Available robotic bases
A click on the image redirect to MORSE Component Library in the on-line doc.
Scroll there to quickly show the available components.

What is a component?

from morse.core.sensor import Sensor

class GPS(Sensor):

    add_data('x', 0.0, 'float', 'X position in the world')
    add_data('y', 0.0, 'float', 'Y position in the world')
    add_data('z', 0.0, 'float', 'Z position in the world')

    def default_action(self):

        x = self.position_3d.x
        y = self.position_3d.y
        z = self.position_3d.z

        # Store the data acquired by this sensor that could be sent
        #  via a middleware.
        self.local_data['x'] = float(x)
        self.local_data['y'] = float(y)
        self.local_data['z'] = float(z)
The GPS sensor implementation.
Important stuff:
from morse.core.services import service
from morse.core.actuator import Acutator

class VWActuator(Actuator):

    add_data('x', 0.0, 'float', 'linear velocity towards x (m/s)')
    add_data('w', 0.0, 'float', 'angular velocity (rad/s)')

    @service
    def set_speed(self, v, w):
        self.local_data['v'] = v
        self.local_data['w'] = w

    @service
    def stop(self):
        self.local_data['v'] = 0.0
        self.local_data['w'] = 0.0

    def default_action(self):
        vx, vy, vz = 0.0, 0.0, 0.0
        rx, ry, rz = 0.0, 0.0, 0.0

        # Scale the speeds to the time used by Blender
        vx = self.local_data['v'] / self.frequency
        rz = self.local_data['w'] / self.frequency

        # Give the movement instructions directly to the parent
        parent = self.robot_parent.blender_obj
        parent.applyMovement([vx, vy, vz], True)
        parent.applyRotation([rx, ry, rz], True)
The (V,W) actuator implementation.
Important stuff:

MORSE Components

Interfacing with the real world

The Cat Controller

import pymorse
def visible(data):
    objects = [obj["name"] for obj in data["visible_objects"]]
    return "MOUSE" in objects

with pymorse.Morse() as simu:
    v_w_prev = None
    while True:
        seen_left = visible(simu.cat.cameraL.last())
        seen_right = visible(simu.cat.cameraR.last())

        if seen_left and seen_right:
            v_w = {"v": 2, "w": 0}
        elif seen_left:
            v_w = {"v": 1.5, "w": 1}
        elif seen_right:
            v_w = {"v": 1.5, "w": -1}
        else:
            v_w = {"v": 0, "w": -1}

        if v_w != v_w_prev:
            simu.cat.motion.publish(v_w)
            v_w_prev = v_w
The CAT Controller: socket based interface, wrapped in the pymorse bindings.
Important stuff:

Interfaces

Serialization/Deserialization

Glimpse on the middleware support matrix

Real-world use-case:
ROS navigation tutorial

ROS navigation demonstration
We start the presentation with a concrete example: the 'Cat and Mouse' game
Do the full demo, but without too many explantions (for now):

Steps

Other features

Modifiers


import random
from morse.core.modifier import Modifier

class IMUNoise(Modifier):

    def register_component(self, name, instance, modifier_data):
        instance.output_modifiers.append(noisify)
        self._gyro_std_dev = 0.5
        self._accel_std_dev = 0.5

    def noisify(self, instance):
        for i in range(0, 3):
            instance.local_data['angular_velocity'][i] = \
                random.gauss(instance.local_data['angular_velocity'][i], 
                             self._gyro_std_dev)

            instance.local_data['linear_acceleration'][i] = \
                random.gauss(instance.local_data['linear_acceleration'][i], 
                             self._accel_std_dev)

Human-Robot interaction

Multi-node

Multi-node MORSE
Multi-node MORSE
Multi-node MORSE

Questions?