Package rst.geometry

Not documented

Messages

Message PointCloud2DInt

class rst.geometry.PointCloud2DInt

A collection of points in 2D space.

Code author: Jan Moringen <jmoringe@techfak.uni-bielefeld.de>

points
Type :array of rst.math.Vec2DInt

The points.

Duplicate entries should be avoided. Order of entries is not significant.

Download this file

message PointCloud2DInt {

    /**
     * The points.
     *
     * Duplicate entries should be avoided.
     * Order of entries is not significant.
     */
    repeated math.Vec2DInt points = 1;

}

Message Shape3DFloat

class rst.geometry.Shape3DFloat

Description of a 3D shape as a union of geometric primitives.

New primitive types can be added to this type.

Code author: Johannes Wienke <jwienke@techfak.uni-bielefeld.de>

Code author: Jan Moringen <jmoringe@techfak.uni-bielefeld.de>

box
Type :array of rst.geometry.BoundingBox3DFloat

Set of oriented bounding boxes contributing to the described 3D shape.

The order of bounding boxes is not significant.

Download this file

message Shape3DFloat {

    /**
     * Set of oriented bounding boxes contributing to the described 3D
     * shape.
     *
     * The order of bounding boxes is not significant.
     */
    repeated geometry.BoundingBox3DFloat box = 1;

}

Message CameraPose

class rst.geometry.CameraPose

Pose of a camera with semantic annotation of the axes.

The pure transformation of the camera’s pose (in terms of coordinate systems) does not provide information about the viewing direction. There must be a convention about the semantic meaning of the transformation in order to convey the information about where the camera actually looks. coordinate_frame realizes this convention by describing the three axes of the camera’s coordinate system semantically including viewing direction and up direction.

Code author: Leon Ziegler <lziegler@techfak.uni-bielefeld.de>

coordinate_frame
Type :rst.geometry.CameraPose.CoordinateFrame

Annotation of the axes.

pose
Type :rst.geometry.Pose

The pose of the camera’s coordinate system in 3d space relative to a given parent coordinate system.

Download this file

message CameraPose {

    /**
     * Semantic annotation of the axes. (all right-handed)
     */
    enum CoordinateFrame {

        /**
         * X: right - Y: down - Z: forward (depth axis)
         */
        CAMERA_IMAGE_FRAME = 0;

        /**
         * X: up - Y: right - Z: forward (depth axis)
         */
        CAMERA_X_UP_FRAME = 1;

        /**
         * X: left - Y: up - Z: forward (depth axis)
         */
        CAMERA_Y_UP_FRAME = 2;

        /**
         * X: forward (depth axis) - Y: left - Z: up
         */
        LASER_FRAME = 3;

        /**
         * X: right - Y: up - Z: towards viewer (negative depth axis)
         */
        SCREEN_FRAME = 4;

    }

    /**
     * Annotation of the axes.
     */
    optional CoordinateFrame coordinate_frame = 1 [default = CAMERA_IMAGE_FRAME];

    /**
     * The pose of the camera's coordinate system in 3d space relative
     * to a given parent coordinate system.
     */
    required geometry.Pose pose = 2;

}

Message CoordinateFrame

class rst.geometry.CameraPose.CoordinateFrame

Semantic annotation of the axes. (all right-handed)

CAMERA_IMAGE_FRAME
= 0

X: right - Y: down - Z: forward (depth axis)

CAMERA_X_UP_FRAME
= 1

X: up - Y: right - Z: forward (depth axis)

CAMERA_Y_UP_FRAME
= 2

X: left - Y: up - Z: forward (depth axis)

LASER_FRAME
= 3

X: forward (depth axis) - Y: left - Z: up

SCREEN_FRAME
= 4

X: right - Y: up - Z: towards viewer (negative depth axis)

Download this file

    enum CoordinateFrame {

        /**
         * X: right - Y: down - Z: forward (depth axis)
         */
        CAMERA_IMAGE_FRAME = 0;

        /**
         * X: up - Y: right - Z: forward (depth axis)
         */
        CAMERA_X_UP_FRAME = 1;

        /**
         * X: left - Y: up - Z: forward (depth axis)
         */
        CAMERA_Y_UP_FRAME = 2;

        /**
         * X: forward (depth axis) - Y: left - Z: up
         */
        LASER_FRAME = 3;

        /**
         * X: right - Y: up - Z: towards viewer (negative depth axis)
         */
        SCREEN_FRAME = 4;

    }

Message ViewFrustum

class rst.geometry.ViewFrustum

Constraint: .maximal_distance > .minimal_distance

A camera’s view frustum.

Adds information about the maximal and minimal perceivable distance (minimal_distance, maximal_distance) of a sensor to the definition of its field of view (fov).

Code author: Leon Ziegler <lziegler@techfak.uni-bielefeld.de>

fov
Type :rst.geometry.FieldOfView

The field of view of the frustum.

minimal_distance
Type :FLOAT32

Constraint: value > 0

Unit: meter

The minimal perceivable distance.

maximal_distance
Type :FLOAT32

Constraint: value > 0

Unit: meter

The maximal perceivable distance.

Download this file

message ViewFrustum {

    /**
     * The field of view of the frustum.
     */
    required FieldOfView fov = 1;

    /**
     * The minimal perceivable distance.
     */
    // @constraint(value > 0)
    // @unit(meter)
    optional float minimal_distance = 2 [default = 0];

    /**
     * The maximal perceivable distance.
     */
    // @constraint(value > 0)
    // @unit(meter)
    optional float maximal_distance = 3 [default = 99999];

}

Message FieldOfView

class rst.geometry.FieldOfView

The field of view of a sensor.

The sensor’s FOV is defined as the angular extent of a scene that is imaged by a visual sensor. The outermost observable ray that falls in a sensor’s FOV has the angular distance +/- AOV/2.0 from the optical axis in the respective extent (vertical/horizontal). The angles are given in radian.

Code author: Leon Ziegler <lziegler@techfak.uni-bielefeld.de>

horizontal_aov
Type :FLOAT32

Constraint: value > 0

Unit: radian

An angle defining the horizontal bounds of the FOV.

vertical_aov
Type :FLOAT32

Constraint: value > 0

Unit: radian

An angle defining the vertical bounds of the FOV.

Download this file

message FieldOfView {

    /**
     * An angle defining the horizontal bounds of the FOV.
     */
    // @constraint(value > 0)
    // @unit(radian)
    required float horizontal_aov = 1;

    /**
     * An angle defining the vertical bounds of the FOV.
     */
    // @constraint(value > 0)
    // @unit(radian)
    required float vertical_aov = 2;

}

Message BoundingBox

class rst.geometry.BoundingBox

Constraint: .top_left.x < .image_width

Constraint: .top_left.x + .width <= .image_width

Constraint: .top_left.y < .image_height

Constraint: .top_left.y + .height <= .image_height

A bounding box, which is associated to a raster image.

(0,0)           Image
+----------------------------------+ ^
|                                  |
|    top_left                    |
|    +---------------+ ^           |
|    |               |             |
|    |               | height    | image_height
|    |               |             |
|    +---------------+ v           |
|    <    width     >            |
|                                  |
+----------------------------------+ v
<         image_width            >

All values are in pixels and refer to the associated image.

Code author: Johannes Wienke <jwienke@techfak.uni-bielefeld.de>

top_left
Type :rst.math.Vec2DInt

Unit: pixel

Coordinates of the top left corner.

width
Type :UINT32

Unit: pixel

Width of the bounding box.

height
Type :UINT32

Unit: pixel

Height of the bounding box.

image_width
Type :UINT32

Unit: pixel

Width of the image the bounding box is based on.

image_height
Type :UINT32

Unit: pixel

Height of the image the bounding box is based on.

Download this file

message BoundingBox {

    /**
     * Coordinates of the top left corner.
     */
    // @unit(pixel)
    required math.Vec2DInt top_left = 1;

    /**
     * Width of the bounding box.
     */
    // @unit(pixel)
    required uint32 width = 2;

    /**
     * Height of the bounding box.
     */
    // @unit(pixel)
    required uint32 height = 3;

    /**
     * Width of the image the bounding box is based on.
     */
    // @unit(pixel)
    optional uint32 image_width = 4;

    /**
     * Height of the image the bounding box is based on.
     */
    // @unit(pixel)
    optional uint32 image_height = 5;

}

Message BoundingBox3DFloat

class rst.geometry.BoundingBox3DFloat

Bounding-box in 3D in general position and orientation.

The general bounding-box with dimensions width x depth x height is constructed by translating and rotating (via transformation) an axis-aligned bounding-box around its center of mass.

For an axis-aligned version, see AxisAlignedBoundingBox3DFloat.

Code author: Christian Emmerich <cemmeric@cor-lab.de>

Code author: Jan Moringen <jmoringe@techfak.uni-bielefeld.de>

transformation
Type :rst.geometry.Pose

Transformation, consisting of translation and orientation, of the center of mass of the bounding-box.

width
Type :FLOAT32

Unit: meter

The width (along the X axis) of the box.

depth
Type :FLOAT32

Unit: meter

The depth (along the Y axis) of the box.

height
Type :FLOAT32

Unit: meter

The height (along the Z axis) of the box.

Download this file

message BoundingBox3DFloat {

    /**
     * Transformation, consisting of translation and orientation, of
     * the center of mass of the bounding-box.
     */
    required geometry.Pose transformation = 1;

    /**
     * The width (along the X axis) of the box.
     */
    // @unit(meter)
    required float width = 2;

    /**
     * The depth (along the Y axis) of the box.
     */
    // @unit(meter)
    required float depth = 3;

    /**
     * The height (along the Z axis) of the box.
     */
    // @unit(meter)
    required float height = 4;

}

Message AxisAlignedBoundingBox3DFloat

class rst.geometry.AxisAlignedBoundingBox3DFloat

An axis-aligned bounding-box in 3D.

The bounding-box is constructed by spanning at left_front_bottom a rectangular volume of lengths width x depth x height along the positive directions of the X, Y and Z axis respectively.

^ Z
|
|            +----------------------+ ^
|           /                      /|
|          /                      / |
|         /                      /  | height
|        +----------------------+   |
|        |                      |   |
|        |                      |   + v
|     Y  |                      |  / ^
|     ^  |                      | / depth
|    /   |                      |/
|   /    +----------------------+ v
|  /     left_front_bottom
| /      <     width      >
|/
+-----------------------------> X

For a bouding-box in general orientation (i.e. not axis-aligned) see BoundingBox3DFloat.

Code author: Christian Emmerich <cemmeric@cor-lab.de>

Code author: Jan Moringen <jmoringe@techfak.uni-bielefeld.de>

left_front_bottom
Type :rst.geometry.Translation

Coordinates of the bottom left front corner.

width
Type :FLOAT32

Unit: meter

The width (along the X axis) of the box.

depth
Type :FLOAT32

Unit: meter

The depth (along the Y axis) of the box.

height
Type :FLOAT32

Unit: meter

The height (along the Z axis) of the box.

Download this file

message AxisAlignedBoundingBox3DFloat {

    /**
     * Coordinates of the bottom left front corner.
     */
    required geometry.Translation left_front_bottom = 1;

    /**
     * The width (along the X axis) of the box.
     */
    // @unit(meter)
    required float width = 2;

    /**
     * The depth (along the Y axis) of the box.
     */
    // @unit(meter)
    required float depth = 3;

    /**
     * The height (along the Z axis) of the box.
     */
    // @unit(meter)
    required float height = 4;

}

Message Pose

class rst.geometry.Pose

Pose data (camera, robot, ...).

Todo

extend explanation

Code author: Arne Nordmann <anordman@techfak.uni-bielefeld.de>

translation
Type :rst.geometry.Translation

TODO

rotation
Type :rst.geometry.Rotation

TODO

Download this file

message Pose {

    /**
     * TODO
     */
    required Translation translation = 1;

    /**
     * TODO
     */
    required Rotation rotation = 2;

}

Message Rotation

class rst.geometry.Rotation

Cartesian 3-dimensional rotatory displacement or orientation.

The displacement or orientation (orientation being a rotation from an origin) is in world coordinates and expressed as unit quaternion (all-zero quaternion denotes an invalid orientation/rotation).

Code author: Arne Nordmann <anordman@cor-lab.uni-bielefeld.de>

qw
Type :FLOAT64

TODO

qx
Type :FLOAT64

TODO

qy
Type :FLOAT64

TODO

qz
Type :FLOAT64

TODO

Download this file

message Rotation {

    /**
     * TODO
     */
    required double qw = 4;

    /**
     * TODO
     */
    required double qx = 5;

    /**
     * TODO
     */
    required double qy = 6;

    /**
     * TODO
     */
    required double qz = 7;

}

Message Translation

class rst.geometry.Translation

Cartesian 3-dimensional translatory displacement or position.

The displacement or position (position being translation from an origin) is expressed in world coordinates.

Code author: Arne Nordmann <anordman@cor-lab.uni-bielefeld.de>

x
Type :FLOAT64

Unit: meter

Cartesian displacement along the x axis

y
Type :FLOAT64

Unit: meter

Cartesian displacement along the y axis

z
Type :FLOAT64

Unit: meter

Cartesian displacement along the z axis

Download this file

message Translation {

    /**
     * Cartesian displacement along the x axis
     */
    // @unit(meter)
    required double x = 1;

    /**
     * Cartesian displacement along the y axis
     */
    // @unit(meter)
    required double y = 2;

    /**
     * Cartesian displacement along the z axis
     */
    // @unit(meter)
    required double z = 3;

}

Table Of Contents

Related Documentation

This Page