Odometry

An odometry sensor that returns raw, partially integrated or fully integrated displacement information.

This sensor produces relative displacement with respect to the position and rotation in the previous Blender tick. It can compute too the position of the robot with respect to its original position, and the associated speed.

The angles for yaw, pitch and roll are given in radians.

Note

This sensor always provides perfect data. To obtain more realistic readings, it is recommended to add modifiers.

  • Noise modifier: Adds random Gaussian noise to the data
  • Odometry Noise modifier: Simulate scale factor error and gyroscope drift

Configuration parameters for Odometry

No configurable parameter.

Available functional levels

Functional levels are predefined abstraction or realism levels for the sensor.

  • raw raw odometry: only dS is exported

    At this level, the sensor exports these datafields at each simulation step:

    • dS (float, initial value: 0.0): curvilinear distance since last tick

    Interface support:

  • differential differential odometry, corresponding to standard ‘robot level’ odometry

    At this level, the sensor exports these datafields at each simulation step:

    • dx (float, initial value: 0.0): delta of X coordinate of the sensor
    • dy (float, initial value: 0.0): delta of Y coordinate of the sensor
    • dz (float, initial value: 0.0): delta of Z coordinate of the sensor
    • dyaw (float, initial value: 0.0): delta of rotation angle with respect to the Z axis
    • dpitch (float, initial value: 0.0): delta of rotation angle with respect to the Y axis
    • droll (float, initial value: 0.0): delta of rotation angle with respect to the X axis

    Interface support:

  • integrated (default level) integrated odometry: absolution position is exported

    At this level, the sensor exports these datafields at each simulation step:

    • x (float, initial value: 0.0): X coordinate of the sensor
    • y (float, initial value: 0.0): Y coordinate of the sensor
    • z (float, initial value: 0.0): Z coordinate of the sensor
    • yaw (float, initial value: 0.0): rotation angle with respect to the Z axis
    • pitch (float, initial value: 0.0): rotation angle with respect to the Y axis
    • roll (float, initial value: 0.0): rotation angle with respect to the X axis
    • vx (float, initial value: 0.0): linear velocity related to the X coordinate of the sensor
    • vy (float, initial value: 0.0): linear velocity related to the Y coordinate of the sensor
    • vz (float, initial value: 0.0): linear velocity related to the Z coordinate of the sensor
    • wz (float, initial value: 0.0): angular velocity related to the Z coordinate of the sensor
    • wy (float, initial value: 0.0): angular velocity related to the Y coordinate of the sensor
    • wx (float, initial value: 0.0): angular velocity related to the X coordinate of the sensor

    Interface support:

Services for Odometry

  • get_configurations() (blocking)

    Returns the configurations of a component (parsed from the properties).

    • Return value

      a dictionary of the current component’s configurations

  • get_local_data() (blocking)

    Returns the current data stored in the sensor.

    • Return value

      a dictionary of the current sensor’s data

  • get_properties() (blocking)

    Returns the properties of a component.

    • Return value

      a dictionary of the current component’s properties

  • set_property(prop_name, prop_val) (blocking)

    Modify one property on a component

    • Parameters

      • prop_name: the name of the property to modify (as shown the documentation)
      • prop_val: the new value of the property. Note that there is no checking about the type of the value so be careful
    • Return value

      nothing

Examples

The following examples show how to use this component in a Builder script:

from morse.builder import *

# adds a default robot (the MORSE mascott!)
robot = Morsy()

# creates a new instance of the sensor
odometry = Odometry()

# place your component at the correct location
odometry.translate(<x>, <y>, <z>)
odometry.rotate(<rx>, <ry>, <rz>)

# select a specific abstraction level (cf below), or skip it to use default level
odometry.level(<level>)

robot.append(odometry)

# define one or several communication interface, like 'socket'
odometry.add_interface(<interface>)

env = Environment('empty')

Other sources of examples

(This page has been auto-generated from MORSE module morse.sensors.odometry.)