.. _package-rst-geometry: ====================== Package rst.geometry ====================== Geometry is a branch of mathematics concerned with questions of shape, size, relative position of figures, and the properties of space. This package contains data types which represent geometrical objects. .. seealso:: Wikipedia article containing the definition above http://en.wikipedia.org/wiki/Geometry .. seealso:: Corresponding data types in ROS http://www.ros.org/wiki/geometry_msgs Messages ======== .. container:: mess4ge-multi .. container:: mess4ge-graph .. digraph:: message_graph fontname="Arial"; fontsize=11; stylesheet="../_static/graphs.css"; node [fontsize=11,fontname="Arial"] edge [fontsize=11,fontname="Arial"] "25" [label=<
AxisAlignedBoundingBox3DFloat
Translationleft_front_bottom
FLOAT32width
FLOAT32depth
FLOAT32height
>,shape=box,style=filled,fillcolor="white"]; "24" [label=<
BoundingBox
Vec2DInttop_left
UINT32width
UINT32height
UINT32image_width
UINT32image_height
>,shape=box,style=filled,fillcolor="white"]; "22" [label=<
ViewFrustum
FieldOfViewfov
FLOAT32minimal_distance
FLOAT32maximal_distance
>,shape=box,style=filled,fillcolor="white"]; "23" [label=<
FieldOfView
FLOAT32horizontal_aov
FLOAT32vertical_aov
>,shape=box,style=filled,fillcolor="white"]; "20" [label=<
CameraPose
CoordinateFramecoordinate_frame
Posepose
>,shape=box,style=filled,fillcolor="white"]; "21" [label=<
CoordinateFrame
CAMERA_IMAGE_FRAME0
CAMERA_X_UP_FRAME1
CAMERA_Y_UP_FRAME2
LASER_FRAME3
SCREEN_FRAME4
>,shape=box,style=filled,fillcolor="white"]; "19" [label=<
Shape3DFloat
BoundingBox3DFloatbox
>,shape=box,style=filled,fillcolor="white"]; "16" [label=<
TriangleMesh3DFloatSet
TriangleMesh3DFloatmeshes
>,shape=box,style=filled,fillcolor="white"]; "17" [label=<
TriangleMesh3DFloat
PointCloud3DFloatvertices
Triangletriangles
>,shape=box,style=filled,fillcolor="white"]; "18" [label=<
Triangle
UINT32point1
UINT32point2
UINT32point3
>,shape=box,style=filled,fillcolor="white"]; "13" [label=<
PointCloudSet3DFloat
PointCloud3DFloatclouds
>,shape=box,style=filled,fillcolor="white"]; "14" [label=<
PointCloud3DFloat
Vec3DFloatpoints
>,shape=box,style=filled,fillcolor="white"]; "15" [label=<
Vec3DFloat
FLOAT32x
FLOAT32y
FLOAT32z
>,shape=box,style=filled,fillcolor="white"]; "11" [label=<
Cylinder3DFloatSet
Cylinder3DFloatcylinders
>,shape=box,style=filled,fillcolor="white"]; "12" [label=<
Cylinder3DFloat
Posetransformation
FLOAT32radius
FLOAT32height
>,shape=box,style=filled,fillcolor="white"]; "9" [label=<
PointCloud2DInt
Vec2DIntpoints
>,shape=box,style=filled,fillcolor="white"]; "10" [label=<
Vec2DInt
INT32x
INT32y
>,shape=box,style=filled,fillcolor="white"]; "8" [label=<
Lengths
FLOAT64lengths
>,shape=box,style=filled,fillcolor="white"]; "6" [label=<
PointPair
Vec2DFloatfirst
Vec2DFloatsecond
>,shape=box,style=filled,fillcolor="white"]; "7" [label=<
Vec2DFloat
FLOAT32x
FLOAT32y
>,shape=box,style=filled,fillcolor="white"]; "1" [label=<
BoundingBox3DFloatSet
BoundingBox3DFloatboxes
>,shape=box,style=filled,fillcolor="white"]; "2" [label=<
BoundingBox3DFloat
Posetransformation
FLOAT32width
FLOAT32depth
FLOAT32height
>,shape=box,style=filled,fillcolor="white"]; "3" [label=<
Pose
Translationtranslation
Rotationrotation
>,shape=box,style=filled,fillcolor="white"]; "5" [label=<
Rotation
FLOAT64qw
FLOAT64qx
FLOAT64qy
FLOAT64qz
ASCII-STRINGframe_id
>,shape=box,style=filled,fillcolor="white"]; "4" [label=<
Translation
FLOAT64x
FLOAT64y
FLOAT64z
ASCII-STRINGframe_id
>,shape=box,style=filled,fillcolor="white"]; "25":left_front_bottom -> "4" []; "24":top_left -> "10" []; "22":fov -> "23" []; "20" -> "21" []; "20":pose -> "3" []; "20":coordinate_frame -> "21" []; "19":box -> "2" []; "16":meshes -> "17" []; "17" -> "18" []; "17":triangles -> "18" []; "17":vertices -> "14" []; "13":clouds -> "14" []; "14":points -> "15" []; "11":cylinders -> "12" []; "12":transformation -> "3" []; "9":points -> "10" []; "6":second -> "7" []; "6":first -> "7" []; "1":boxes -> "2" []; "2":transformation -> "3" []; "3":rotation -> "5" []; "3":translation -> "4" []; .. container:: mess4ge-list .. container:: messages * :ref:`BoundingBox3DFloatSet ` * :ref:`PointPair ` * :ref:`Lengths ` * :ref:`PointCloud2DInt ` * :ref:`Cylinder3DFloatSet ` * :ref:`Cylinder3DFloat ` * :ref:`PointCloudSet3DFloat ` * :ref:`TriangleMesh3DFloatSet ` * :ref:`TriangleMesh3DFloat ` * :ref:`Shape3DFloat ` * :ref:`PointCloud3DFloat ` * :ref:`CameraPose ` * :ref:`ViewFrustum ` * :ref:`FieldOfView ` * :ref:`BoundingBox ` * :ref:`BoundingBox3DFloat ` * :ref:`AxisAlignedBoundingBox3DFloat ` * :ref:`Pose ` * :ref:`Rotation ` * :ref:`Translation ` .. container:: clearer clearer: should be made invisible via css .. _message-rst-geometry-boundingbox3dfloatset: Message BoundingBox3DFloatSet ----------------------------- .. container:: message-rst-geometry-boundingbox3dfloatset-multi .. container:: message-rst-geometry-boundingbox3dfloatset-documentation .. py:class:: rst.geometry.BoundingBox3DFloatSet A set of :py:class:`BoundingBox3DFloat ` objects. .. codeauthor:: Christian Emmerich .. py:attribute:: boxes :type: array of :py:class:`rst.geometry.BoundingBox3DFloat` Empty collection of boxes is allowed. The order of box objects is not significant. .. container:: message-rst-geometry-boundingbox3dfloatset-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/BoundingBox3DFloatSet.proto :lines: 12-20 :language: protobuf :emphasize-lines: 7-7 .. _message-rst-geometry-pointpair: Message PointPair ----------------- .. container:: message-rst-geometry-pointpair-multi .. container:: message-rst-geometry-pointpair-documentation .. py:class:: rst.geometry.PointPair A message representing a pair of 2D Points .. codeauthor:: TODO .. py:attribute:: first :type: :py:class:`rst.math.Vec2DFloat` TODO .. py:attribute:: second :type: :py:class:`rst.math.Vec2DFloat` TODO .. container:: message-rst-geometry-pointpair-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/PointPair.proto :lines: 12-24 :language: protobuf :emphasize-lines: 6-6,11-11 .. _message-rst-geometry-lengths: Message Lengths --------------- .. container:: message-rst-geometry-lengths-multi .. container:: message-rst-geometry-lengths-documentation .. py:class:: rst.geometry.Lengths A sequence of length measurements (e.g. length of a link in a kinematics chain). .. codeauthor:: Arne Nordmann .. py:attribute:: lengths :type: array of :py:class:`FLOAT64` **Unit**: meter .. container:: message-rst-geometry-lengths-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/Lengths.proto :lines: 11-16 :language: protobuf :emphasize-lines: 4-4 .. _message-rst-geometry-pointcloud2dint: Message PointCloud2DInt ----------------------- .. container:: message-rst-geometry-pointcloud2dint-multi .. container:: message-rst-geometry-pointcloud2dint-documentation .. py:class:: rst.geometry.PointCloud2DInt A collection of points in 2D space. .. codeauthor:: Jan Moringen .. py:attribute:: points :type: array of :py:class:`rst.math.Vec2DInt` The points. Duplicate entries should be avoided. Order of entries is not significant. .. container:: message-rst-geometry-pointcloud2dint-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/PointCloud2DInt.proto :lines: 12-22 :language: protobuf :emphasize-lines: 9-9 .. _message-rst-geometry-cylinder3dfloatset: Message Cylinder3DFloatSet -------------------------- .. container:: message-rst-geometry-cylinder3dfloatset-multi .. container:: message-rst-geometry-cylinder3dfloatset-documentation .. py:class:: rst.geometry.Cylinder3DFloatSet A set of :py:class:`Cylinder3DFloat ` objects. .. codeauthor:: Christian Emmerich .. py:attribute:: cylinders :type: array of :py:class:`rst.geometry.Cylinder3DFloat` Empty collection of cylinders is allowed. The order of cylinders is not significant. .. container:: message-rst-geometry-cylinder3dfloatset-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/Cylinder3DFloatSet.proto :lines: 12-20 :language: protobuf :emphasize-lines: 7-7 .. _message-rst-geometry-cylinder3dfloat: Message Cylinder3DFloat ----------------------- .. container:: message-rst-geometry-cylinder3dfloat-multi .. container:: message-rst-geometry-cylinder3dfloat-documentation .. py:class:: rst.geometry.Cylinder3DFloat Cylinder in 3D in general position and orientation. The general cylinder with dimensions :py:attr:`radius ` and :py:attr:`height ` is constructed by translating and rotating (via :py:attr:`transformation `) a zero-centered, z-oriented axis-aligned cylinder such as below around its center of mass. .. parsed-literal:: < :py:attr:`radius ` > .---------------------. / \\ / \\ + + + ^ \|\\ /| | \\ / | | \`---------------------' | | | | Z ^ | \| \| ^ Y \| :py:attr:`height ` \| \| / \| \| \|/ \| \| +-----> X \| | | ˙ | | | | | | + + v \\ / \\ / \`---------------------' .. codeauthor:: Christian Emmerich .. py:attribute:: transformation :type: :py:class:`rst.geometry.Pose` Transformation, consisting of translation and orientation, of the center of mass of the cylinder. .. py:attribute:: radius :type: :py:class:`FLOAT32` **Unit**: meter The radius of the cylinder. .. py:attribute:: height :type: :py:class:`FLOAT32` **Unit**: meter The height of the cylinder. .. container:: message-rst-geometry-cylinder3dfloat-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/Cylinder3DFloat.proto :lines: 43-63 :language: protobuf :emphasize-lines: 7-7,13-13,19-19 .. _message-rst-geometry-pointcloudset3dfloat: Message PointCloudSet3DFloat ---------------------------- .. container:: message-rst-geometry-pointcloudset3dfloat-multi .. container:: message-rst-geometry-pointcloudset3dfloat-documentation .. py:class:: rst.geometry.PointCloudSet3DFloat A set of 3D Point clouds. .. codeauthor:: Christian Emmerich .. py:attribute:: clouds :type: array of :py:class:`rst.geometry.PointCloud3DFloat` Empty collection of clouds is allowed. The order of cloud objects is not significant. .. container:: message-rst-geometry-pointcloudset3dfloat-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/PointCloudSet3DFloat.proto :lines: 12-20 :language: protobuf :emphasize-lines: 7-7 .. _message-rst-geometry-trianglemesh3dfloatset: Message TriangleMesh3DFloatSet ------------------------------ .. container:: message-rst-geometry-trianglemesh3dfloatset-multi .. container:: message-rst-geometry-trianglemesh3dfloatset-documentation .. py:class:: rst.geometry.TriangleMesh3DFloatSet A set of :py:class:`TriangleMesh3DFloat ` objects. .. codeauthor:: Johannes Wienke .. py:attribute:: meshes :type: array of :py:class:`rst.geometry.TriangleMesh3DFloat` Empty collection is allowed. Order is not important. .. container:: message-rst-geometry-trianglemesh3dfloatset-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/TriangleMesh3DFloatSet.proto :lines: 12-19 :language: protobuf :emphasize-lines: 6-6 .. _message-rst-geometry-trianglemesh3dfloat: Message TriangleMesh3DFloat --------------------------- .. container:: message-rst-geometry-trianglemesh3dfloat-multi .. container:: message-rst-geometry-trianglemesh3dfloat-documentation .. py:class:: rst.geometry.TriangleMesh3DFloat Defines a triangle mesh for describing 3D objects through vertices and their assembly to triangles. Edges are therefore only implicitly defined through the definitions of the triangles. Other typical mesh properties like faces, and surfaces are not defined. .. codeauthor:: Johannes Wienke .. py:attribute:: vertices :type: :py:class:`rst.geometry.PointCloud3DFloat` The collection of vertices in the mesh. .. py:attribute:: triangles :type: array of :py:class:`rst.geometry.TriangleMesh3DFloat.Triangle` Defines the triangles that form the mesh in the form of 3-tuples to indexes in the vertices point cloud. No particular ordering is assumed here. .. container:: message-rst-geometry-trianglemesh3dfloat-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/TriangleMesh3DFloat.proto :lines: 15-54 :language: protobuf :emphasize-lines: 6-6,38-38 .. _message-rst-geometry-trianglemesh3dfloat-triangle: Message Triangle ---------------- .. container:: message-rst-geometry-trianglemesh3dfloat-triangle-multi .. container:: message-rst-geometry-trianglemesh3dfloat-triangle-documentation .. py:class:: rst.geometry.TriangleMesh3DFloat.Triangle Definition of a single triangle in a mesh by means of indices to the vertex point cloud for all corners of the triangle. Vertices are indexed in counter-clockwise order to define a normal of the triangle that points outwards. .. py:attribute:: point1 :type: :py:class:`UINT32` Index of the first vertex defining the triangle. .. py:attribute:: point2 :type: :py:class:`UINT32` Index of the second vertex defining the triangle. .. py:attribute:: point3 :type: :py:class:`UINT32` Index of the third vertex defining the triangle. .. container:: message-rst-geometry-trianglemesh3dfloat-triangle-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/TriangleMesh3DFloat.proto :lines: 28-45 :language: protobuf :emphasize-lines: 6-6,11-11,16-16 .. _message-rst-geometry-shape3dfloat: Message Shape3DFloat -------------------- .. container:: message-rst-geometry-shape3dfloat-multi .. container:: message-rst-geometry-shape3dfloat-documentation .. py:class:: rst.geometry.Shape3DFloat Description of a 3D shape as a union of geometric primitives. New primitive types can be added to this type. .. codeauthor:: Johannes Wienke .. codeauthor:: Jan Moringen .. py:attribute:: box :type: array of :py:class:`rst.geometry.BoundingBox3DFloat` Set of oriented bounding boxes contributing to the described 3D shape. The order of bounding boxes is not significant. .. container:: message-rst-geometry-shape3dfloat-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/Shape3DFloat.proto :lines: 15-25 :language: protobuf :emphasize-lines: 9-9 .. _message-rst-geometry-pointcloud3dfloat: Message PointCloud3DFloat ------------------------- .. container:: message-rst-geometry-pointcloud3dfloat-multi .. container:: message-rst-geometry-pointcloud3dfloat-documentation .. py:class:: rst.geometry.PointCloud3DFloat A collection of points in 3D space. .. codeauthor:: Jordi Sanchez Riera .. todo:: correct author? .. py:attribute:: points :type: array of :py:class:`rst.math.Vec3DFloat` TODO @unit(meter?) .. container:: message-rst-geometry-pointcloud3dfloat-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/PointCloud3DFloat.proto :lines: 13-21 :language: protobuf :emphasize-lines: 7-7 .. _message-rst-geometry-camerapose: Message CameraPose ------------------ .. container:: message-rst-geometry-camerapose-multi .. container:: message-rst-geometry-camerapose-documentation .. py: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. :py:attr:`coordinate_frame ` realizes this convention by describing the three axes of the camera's coordinate system semantically including viewing direction and up direction. .. codeauthor:: Leon Ziegler .. py:attribute:: coordinate_frame :type: :py:class:`rst.geometry.CameraPose.CoordinateFrame` Annotation of the axes. .. py:attribute:: pose :type: :py:class:`rst.geometry.Pose` The pose of the camera's coordinate system in 3d space relative to a given parent coordinate system. .. container:: message-rst-geometry-camerapose-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/CameraPose.proto :lines: 20-65 :language: protobuf :emphasize-lines: 38-38,44-44 .. _message-rst-geometry-camerapose-coordinateframe: Message CoordinateFrame ----------------------- .. container:: message-rst-geometry-camerapose-coordinateframe-multi .. container:: message-rst-geometry-camerapose-coordinateframe-documentation .. py:class:: rst.geometry.CameraPose.CoordinateFrame Semantic annotation of the axes. (all right-handed) .. py:attribute:: CAMERA_IMAGE_FRAME = 0 X: right - Y: down - Z: forward (depth axis) .. py:attribute:: CAMERA_X_UP_FRAME = 1 X: up - Y: right - Z: forward (depth axis) .. py:attribute:: CAMERA_Y_UP_FRAME = 2 X: left - Y: up - Z: forward (depth axis) .. py:attribute:: LASER_FRAME = 3 X: forward (depth axis) - Y: left - Z: up .. py:attribute:: SCREEN_FRAME = 4 X: right - Y: up - Z: towards viewer (negative depth axis) .. container:: message-rst-geometry-camerapose-coordinateframe-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/CameraPose.proto :lines: 25-52 :language: protobuf :emphasize-lines: 6-6,11-11,16-16,21-21,26-26 .. _message-rst-geometry-viewfrustum: Message ViewFrustum ------------------- .. container:: message-rst-geometry-viewfrustum-multi .. container:: message-rst-geometry-viewfrustum-documentation .. py:class:: rst.geometry.ViewFrustum **Constraint**: ``.maximal_distance > .minimal_distance`` A camera's view frustum. Adds information about the maximal and minimal perceivable distance (:py:attr:`minimal_distance `, :py:attr:`maximal_distance `) of a sensor to the definition of its field of view (:py:attr:`fov `). .. codeauthor:: Leon Ziegler .. py:attribute:: fov :type: :py:class:`rst.geometry.FieldOfView` The field of view of the frustum. .. py:attribute:: minimal_distance :type: :py:class:`FLOAT32` **Constraint**: ``value > 0`` **Unit**: meter The minimal perceivable distance. .. py:attribute:: maximal_distance :type: :py:class:`FLOAT32` **Constraint**: ``value > 0`` **Unit**: meter The maximal perceivable distance. .. container:: message-rst-geometry-viewfrustum-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/ViewFrustum.proto :lines: 17-38 :language: protobuf :emphasize-lines: 6-6,13-13,20-20 .. _message-rst-geometry-fieldofview: Message FieldOfView ------------------- .. container:: message-rst-geometry-fieldofview-multi .. container:: message-rst-geometry-fieldofview-documentation .. py: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. .. codeauthor:: Leon Ziegler .. py:attribute:: horizontal_aov :type: :py:class:`FLOAT32` **Constraint**: ``value > 0`` **Unit**: radian An angle defining the horizontal bounds of the FOV. .. py:attribute:: vertical_aov :type: :py:class:`FLOAT32` **Constraint**: ``value > 0`` **Unit**: radian An angle defining the vertical bounds of the FOV. .. container:: message-rst-geometry-fieldofview-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/FieldOfView.proto :lines: 16-32 :language: protobuf :emphasize-lines: 8-8,15-15 .. _message-rst-geometry-boundingbox: Message BoundingBox ------------------- .. container:: message-rst-geometry-boundingbox-multi .. container:: message-rst-geometry-boundingbox-documentation .. py: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. .. parsed-literal:: (0,0) Image +----------------------------------+ ^ | | | :py:attr:`top_left ` | | +---------------+ ^ | | | | | | | | :py:attr:`height ` | :py:attr:`image_height ` | | | | | +---------------+ v | | < :py:attr:`width ` > | | | +----------------------------------+ v < :py:attr:`image_width ` > All values are in pixels and refer to the associated image. .. codeauthor:: Johannes Wienke .. py:attribute:: top_left :type: :py:class:`rst.math.Vec2DInt` **Unit**: pixel Coordinates of the top left corner. .. py:attribute:: width :type: :py:class:`UINT32` **Unit**: pixel Width of the bounding box. .. py:attribute:: height :type: :py:class:`UINT32` **Unit**: pixel Height of the bounding box. .. py:attribute:: image_width :type: :py:class:`UINT32` **Unit**: pixel Width of the image the bounding box is based on. .. py:attribute:: image_height :type: :py:class:`UINT32` **Unit**: pixel Height of the image the bounding box is based on. .. container:: message-rst-geometry-boundingbox-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/BoundingBox.proto :lines: 34-66 :language: protobuf :emphasize-lines: 7-7,13-13,19-19,25-25,31-31 .. _message-rst-geometry-boundingbox3dfloat: Message BoundingBox3DFloat -------------------------- .. container:: message-rst-geometry-boundingbox3dfloat-multi .. container:: message-rst-geometry-boundingbox3dfloat-documentation .. py:class:: rst.geometry.BoundingBox3DFloat Bounding-box in 3D in general position and orientation. The general bounding-box with dimensions :py:attr:`width ` x :py:attr:`depth ` x :py:attr:`height ` is constructed by translating and rotating (via :py:attr:`transformation `) an axis-aligned bounding-box around its center of mass. For an axis-aligned version, see :py:class:`AxisAlignedBoundingBox3DFloat `. .. codeauthor:: Christian Emmerich .. codeauthor:: Jan Moringen .. py:attribute:: transformation :type: :py:class:`rst.geometry.Pose` Transformation, consisting of translation and orientation, of the center of mass of the bounding-box. .. py:attribute:: width :type: :py:class:`FLOAT32` **Unit**: meter The width (along the X axis) of the box. .. py:attribute:: depth :type: :py:class:`FLOAT32` **Unit**: meter The depth (along the Y axis) of the box. .. py:attribute:: height :type: :py:class:`FLOAT32` **Unit**: meter The height (along the Z axis) of the box. .. container:: message-rst-geometry-boundingbox3dfloat-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/BoundingBox3DFloat.proto :lines: 22-48 :language: protobuf :emphasize-lines: 7-7,13-13,19-19,25-25 .. _message-rst-geometry-axisalignedboundingbox3dfloat: Message AxisAlignedBoundingBox3DFloat ------------------------------------- .. container:: message-rst-geometry-axisalignedboundingbox3dfloat-multi .. container:: message-rst-geometry-axisalignedboundingbox3dfloat-documentation .. py:class:: rst.geometry.AxisAlignedBoundingBox3DFloat An axis-aligned bounding-box in 3D. The bounding-box is constructed by spanning at :py:attr:`left_front_bottom ` a rectangular volume of lengths :py:attr:`width ` x :py:attr:`depth ` x :py:attr:`height ` along the positive directions of the X, Y and Z axis respectively. .. parsed-literal:: ^ Z | | +----------------------+ ^ | / /| | / / | | / / | :py:attr:`height ` | +----------------------+ | | | | | | | | + v | Y | | / ^ | ^ | | / :py:attr:`depth ` | / | |/ | / +----------------------+ v | / :py:attr:`left_front_bottom ` | / < :py:attr:`width ` > |/ +-----------------------------> X For a bouding-box in general orientation (i.e. not axis-aligned) see :py:class:`BoundingBox3DFloat `. .. codeauthor:: Christian Emmerich .. codeauthor:: Jan Moringen .. py:attribute:: left_front_bottom :type: :py:class:`rst.geometry.Translation` Coordinates of the bottom left front corner. .. py:attribute:: width :type: :py:class:`FLOAT32` **Unit**: meter The width (along the X axis) of the box. .. py:attribute:: depth :type: :py:class:`FLOAT32` **Unit**: meter The depth (along the Y axis) of the box. .. py:attribute:: height :type: :py:class:`FLOAT32` **Unit**: meter The height (along the Z axis) of the box. .. container:: message-rst-geometry-axisalignedboundingbox3dfloat-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/AxisAlignedBoundingBox3DFloat.proto :lines: 41-66 :language: protobuf :emphasize-lines: 6-6,12-12,18-18,24-24 .. _message-rst-geometry-pose: Message Pose ------------ .. container:: message-rst-geometry-pose-multi .. container:: message-rst-geometry-pose-documentation .. py:class:: rst.geometry.Pose Pose data (camera, robot, ...). .. todo:: extend explanation .. codeauthor:: Arne Nordmann .. py:attribute:: translation :type: :py:class:`rst.geometry.Translation` TODO .. py:attribute:: rotation :type: :py:class:`rst.geometry.Rotation` TODO .. container:: message-rst-geometry-pose-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/Pose.proto :lines: 14-26 :language: protobuf :emphasize-lines: 6-6,11-11 .. _message-rst-geometry-rotation: Message Rotation ---------------- .. container:: message-rst-geometry-rotation-multi .. container:: message-rst-geometry-rotation-documentation .. py: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). .. codeauthor:: Arne Nordmann .. py:attribute:: qw :type: :py:class:`FLOAT64` TODO .. py:attribute:: qx :type: :py:class:`FLOAT64` TODO .. py:attribute:: qy :type: :py:class:`FLOAT64` TODO .. py:attribute:: qz :type: :py:class:`FLOAT64` TODO .. py:attribute:: frame_id :type: :py:class:`ASCII-STRING` Identifier for the coordinate frame of the rotation. .. container:: message-rst-geometry-rotation-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/Rotation.proto :lines: 14-40 :language: protobuf :emphasize-lines: 6-6,11-11,16-16,21-21,26-26 .. _message-rst-geometry-translation: Message Translation ------------------- .. container:: message-rst-geometry-translation-multi .. container:: message-rst-geometry-translation-documentation .. py: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. .. codeauthor:: Arne Nordmann .. py:attribute:: x :type: :py:class:`FLOAT64` **Unit**: meter Cartesian displacement along the x axis .. py:attribute:: y :type: :py:class:`FLOAT64` **Unit**: meter Cartesian displacement along the y axis .. py:attribute:: z :type: :py:class:`FLOAT64` **Unit**: meter Cartesian displacement along the z axis .. py:attribute:: frame_id :type: :py:class:`ASCII-STRING` Identifier for the coordinate frame of the rotation. .. container:: message-rst-geometry-translation-source :download:`Download this file ` .. literalinclude:: //home/jenkins/workspace/rst-manual-0.12/rst-manual/../rst-proto/proto/stable/rst/geometry/Translation.proto :lines: 13-37 :language: protobuf :emphasize-lines: 7-7,13-13,19-19,24-24