Drake
Drake C++ Documentation
RenderEngine Class Referenceabstract

Detailed Description

The engine for performing rasterization operations on geometry.

This includes rgb images and depth images. The coordinate system of RenderEngine's viewpoint R is X-right, Y-down and Z-forward with respect to the rendered images.

Output image format

  • RGB (ImageRgba8U) : the RGB image has four channels in the following order: red, green, blue, and alpha. Each channel is represented by a uint8_t.
  • Depth (ImageDepth32F) : the depth image has a depth channel represented by a float. For a point in space P, the value stored in the depth channel holds the Z-component of the position vector p_RP. Note that this is different from the range data used by laser range finders (like that provided by DepthSensor) in which the depth value represents the distance from the sensor origin to the object's surface.
  • Label (ImageLabel16I) : the label image has single channel represented by an int16_t. The value stored in the channel holds a RenderLabel value which corresponds to an object class in the scene or an "empty" pixel (see RenderLabel for more details).

RenderLabels, registering geometry, and derived classes

By convention, when registering a geometry, the provided properties should contain no more than one RenderLabel instance, and that should be the (label, id) property. RenderEngine provides the notion of a default render label that will be applied where no (label, id) RenderLabel property is found. This default value can be one of two values: RenderLabel::kDontCare or RenderLabel::kUnspecified. The choice of default RenderLabel can be made at construction and it affects registration behavior when the (label, id) property is absent:

Choosing RenderLabel::kUnspecified is best in a system that wants explicit feedback and strict enforcement on a policy of strict label enforcement – everything should receive a meaningful label. The choice of RenderLabel::kDontCare is best for a less strict system in which only some subset of geometry need be explicitly specified.

Derived classes configure their de facto default RenderLabel value, or a user-configured default value, at construction, subject to the requirements outlined above.

Derived classes should not access the (label, id) property directly. RenderEngine provides a method to safely extract a RenderLabel value from the PerceptionProperties, taking into account the configured default value and the documented RenderLabel semantics; see GetRenderLabelOrThrow().

#include <drake/geometry/render/render_engine.h>

Public Member Functions

 RenderEngine (const RenderLabel &default_label=RenderLabel::kUnspecified)
 Constructs a RenderEngine with the given default render label. More...
 
virtual ~RenderEngine ()=default
 
std::unique_ptr< RenderEngineClone () const
 Clones the render engine – making the RenderEngine compatible with copyable_unique_ptr. More...
 
bool RemoveGeometry (GeometryId id)
 Removes the geometry indicated by the given id from the engine. More...
 
bool has_geometry (GeometryId id) const
 Reports true if a geometry with the given id has been registered with this engine. More...
 
template<typename T >
void UpdatePoses (const std::unordered_map< GeometryId, math::RigidTransform< T >> &X_WGs)
 Updates the poses of all rigid geometries marked as "needing update" (see RegisterVisual()). More...
 
void UpdateDeformableConfigurations (GeometryId id, const std::vector< VectorX< double >> &q_WGs, const std::vector< VectorX< double >> &nhats_W)
 Updates the configurations of all meshes associated with the given deformable geometry (see RegisterDeformableVisual()). More...
 
virtual void UpdateViewpoint (const math::RigidTransformd &X_WR)=0
 Updates the renderer's viewpoint with given pose X_WR. More...
 
RenderLabel default_render_label () const
 Reports the render label value this render engine has been configured to use. More...
 
Registering geometry with the engine

These methods allow for requests to register new visual geometries to this RenderEngine.

The geometry is uniquely identified by the given id. The renderer is allowed to examine the given properties and choose to not register the geometry.

Typically, derived classes will attempt to validate the RenderLabel value stored in the (label, id) property (or its configured default value if no such property exists). In that case, attempting to assign RenderLabel::kEmpty or RenderLabel::kUnspecified will cause an exception to be thrown (as documented).

bool RegisterVisual (GeometryId id, const Shape &shape, const PerceptionProperties &properties, const math::RigidTransformd &X_WG, bool needs_updates=true)
 Requests registration of the given shape as a rigid geometry with this render engine. More...
 
bool RegisterDeformableVisual (GeometryId id, const std::vector< internal::RenderMesh > &render_meshes, const PerceptionProperties &properties)
 Requests registration of the given deformable geometry with this render engine. More...
 
Rendering using fully-specified camera models

These methods allow for full specification of the camera model – its intrinsics and render engine parameters.

See the documentation of ColorRenderCamera and DepthRenderCamera for the full details.

void RenderColorImage (const ColorRenderCamera &camera, systems::sensors::ImageRgba8U *color_image_out) const
 Renders the registered geometry into the given color (rgb) image based on a fully specified camera. More...
 
void RenderDepthImage (const DepthRenderCamera &camera, systems::sensors::ImageDepth32F *depth_image_out) const
 Renders the registered geometry into the given depth image based on a fully specified camera. More...
 
void RenderLabelImage (const ColorRenderCamera &camera, systems::sensors::ImageLabel16I *label_image_out) const
 Renders the registered geometry into the given label image based on a fully specified camera. More...
 

Protected Member Functions

virtual bool DoRegisterVisual (GeometryId id, const Shape &shape, const PerceptionProperties &properties, const math::RigidTransformd &X_WG)=0
 The NVI-function for sub-classes to implement actual rigid geometry registration. More...
 
virtual bool DoRegisterDeformableVisual (GeometryId id, const std::vector< internal::RenderMesh > &render_meshes, const PerceptionProperties &properties)
 The NVI-function for RegisterDeformableVisual(). More...
 
virtual void DoUpdateVisualPose (GeometryId id, const math::RigidTransformd &X_WG)=0
 The NVI-function for updating the pose of a rigid render geometry (identified by id) to the given pose X_WG. More...
 
virtual void DoUpdateDeformableConfigurations (GeometryId id, const std::vector< VectorX< double >> &q_WGs, const std::vector< VectorX< double >> &nhats_W)
 The NVI-function for UpdateDeformableConfigurations(). More...
 
virtual bool DoRemoveGeometry (GeometryId id)=0
 The NVI-function for removing the geometry with the given id. More...
 
virtual std::unique_ptr< RenderEngineDoClone () const =0
 The NVI-function for cloning this render engine. More...
 
virtual void DoRenderColorImage (const ColorRenderCamera &camera, systems::sensors::ImageRgba8U *color_image_out) const
 The NVI-function for rendering color with a fully-specified camera. More...
 
virtual void DoRenderDepthImage (const DepthRenderCamera &camera, systems::sensors::ImageDepth32F *depth_image_out) const
 The NVI-function for rendering depth with a fully-specified camera. More...
 
virtual void DoRenderLabelImage (const ColorRenderCamera &camera, systems::sensors::ImageLabel16I *label_image_out) const
 The NVI-function for rendering label with a fully-specified camera. More...
 
RenderLabel GetRenderLabelOrThrow (const PerceptionProperties &properties) const
 Extracts the (label, id) RenderLabel property from the given properties and validates it (or the configured default if no such property is defined). More...
 
virtual void SetDefaultLightPosition (const Vector3< double > &X_DL)
 Provides access to the light for manual configuration since it's currently bound to the camera position. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 RenderEngine (const RenderEngine &)=default
 
RenderEngineoperator= (const RenderEngine &)=default
 
 RenderEngine (RenderEngine &&)=default
 
RenderEngineoperator= (RenderEngine &&)=default
 

Static Protected Member Functions

template<typename ImageType >
static void ThrowIfInvalid (const systems::sensors::CameraInfo &intrinsics, const ImageType *image, const char *image_type)
 
RenderLabel-Color Utilities

Some rasterization pipelines don't support channels of RenderLabel::ValueType; typically, they operate in RGB color space.

The following utilities support those pipelines by providing conversions between labels and colors. The mapping does not produce colors that are useful to humans – two labels with "near by" values will produces colors that most humans cannot distinguish, but the computer can. Do not use these utilities to produce the prototypical "colored label" images.

These utilities are provided as a convenience to derived classes. Derived classes are not required to encode labels as colors in the same way. They are only obliged to return label images with proper label values according to the documented semantics.

static RenderLabel MakeLabelFromRgb (uint8_t r, uint8_t g, uint8_t)
 Transforms the given RGB color into its corresponding RenderLabel. More...
 
static Rgba MakeRgbFromLabel (const RenderLabel &label)
 Transforms the given render label into an RGB color. More...
 

Friends

class RenderEngineTester
 

Constructor & Destructor Documentation

◆ RenderEngine() [1/3]

RenderEngine ( const RenderLabel default_label = RenderLabel::kUnspecified)
explicit

Constructs a RenderEngine with the given default render label.

The default render label is applied to geometries that have not otherwise specified a (label, id) property. The value must be either RenderLabel::kUnspecified or RenderLabel::kDontCare. (See this section for more details.)

Exceptions
std::exceptionif the default render label is not one of the two allowed labels.

◆ ~RenderEngine()

virtual ~RenderEngine ( )
virtualdefault

◆ RenderEngine() [2/3]

RenderEngine ( const RenderEngine )
protecteddefault

◆ RenderEngine() [3/3]

RenderEngine ( RenderEngine &&  )
protecteddefault

Member Function Documentation

◆ Clone()

std::unique_ptr<RenderEngine> Clone ( ) const

Clones the render engine – making the RenderEngine compatible with copyable_unique_ptr.

◆ default_render_label()

RenderLabel default_render_label ( ) const

Reports the render label value this render engine has been configured to use.

◆ DoClone()

virtual std::unique_ptr<RenderEngine> DoClone ( ) const
protectedpure virtual

The NVI-function for cloning this render engine.

◆ DoRegisterDeformableVisual()

virtual bool DoRegisterDeformableVisual ( GeometryId  id,
const std::vector< internal::RenderMesh > &  render_meshes,
const PerceptionProperties properties 
)
protectedvirtual

The NVI-function for RegisterDeformableVisual().

This function defaults to returning false. If the derived class chooses to register this particular geometry, it should return true. This function is invoked with the following guarantees:

  • id is unique (i.e. distinct from previously registered geometries).
  • render_meshes is non-empty.
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.

◆ DoRegisterVisual()

virtual bool DoRegisterVisual ( GeometryId  id,
const Shape shape,
const PerceptionProperties properties,
const math::RigidTransformd &  X_WG 
)
protectedpure virtual

The NVI-function for sub-classes to implement actual rigid geometry registration.

If the derived class chooses not to register this particular shape, it should return false.

A derived render engine can use arbitrary criteria to decide if the rigid geometry gets registered. In accessing the RenderLabel property in properties derived class should exclusively use GetRenderLabelOrThrow().

◆ DoRemoveGeometry()

virtual bool DoRemoveGeometry ( GeometryId  id)
protectedpure virtual

The NVI-function for removing the geometry with the given id.

Parameters
idThe id of the geometry to remove.
Returns
True if the geometry was registered with this RenderEngine and removed, false if it wasn't registered in the first place.

◆ DoRenderColorImage()

virtual void DoRenderColorImage ( const ColorRenderCamera camera,
systems::sensors::ImageRgba8U color_image_out 
) const
protectedvirtual

The NVI-function for rendering color with a fully-specified camera.

When RenderColorImage calls this, it has already confirmed that color_image_out is not nullptr and its size is consistent with the camera intrinsics.

Exceptions
std::exceptionin its default implementation indicating that it has not been implemented. Derived RenderEngine classes must implement this to support rendering color images.

◆ DoRenderDepthImage()

virtual void DoRenderDepthImage ( const DepthRenderCamera camera,
systems::sensors::ImageDepth32F depth_image_out 
) const
protectedvirtual

The NVI-function for rendering depth with a fully-specified camera.

When RenderDepthImage calls this, it has already confirmed that depth_image_out is not nullptr and its size is consistent with the camera intrinsics.

Exceptions
std::exceptionin its default implementation indicating that it has not been implemented. Derived RenderEngine classes must implement this to support rendering depth images.

◆ DoRenderLabelImage()

virtual void DoRenderLabelImage ( const ColorRenderCamera camera,
systems::sensors::ImageLabel16I label_image_out 
) const
protectedvirtual

The NVI-function for rendering label with a fully-specified camera.

When RenderLabelImage calls this, it has already confirmed that label_image_out is not nullptr and its size is consistent with the camera intrinsics.

Exceptions
std::exceptionin its default implementation indicating that it has not been implemented. Derived RenderEngine classes must implement this to support rendering label images.

◆ DoUpdateDeformableConfigurations()

virtual void DoUpdateDeformableConfigurations ( GeometryId  id,
const std::vector< VectorX< double >> &  q_WGs,
const std::vector< VectorX< double >> &  nhats_W 
)
protectedvirtual

The NVI-function for UpdateDeformableConfigurations().

It is invoked with the following guarantees:

  • id references a registered deformable geometry.
  • q_WGs and nhats_W are appropriately sized for the registered meshes.
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.

◆ DoUpdateVisualPose()

virtual void DoUpdateVisualPose ( GeometryId  id,
const math::RigidTransformd &  X_WG 
)
protectedpure virtual

The NVI-function for updating the pose of a rigid render geometry (identified by id) to the given pose X_WG.

Parameters
idThe id of the render geometry whose pose is being set.
X_WGThe pose of the render geometry in the world frame.

◆ GetRenderLabelOrThrow()

RenderLabel GetRenderLabelOrThrow ( const PerceptionProperties properties) const
protected

Extracts the (label, id) RenderLabel property from the given properties and validates it (or the configured default if no such property is defined).

Exceptions
std::exceptionIf the tested render label value is deemed invalid.

◆ has_geometry()

bool has_geometry ( GeometryId  id) const

Reports true if a geometry with the given id has been registered with this engine.

◆ MakeLabelFromRgb()

static RenderLabel MakeLabelFromRgb ( uint8_t  r,
uint8_t  g,
uint8_t   
)
staticprotected

Transforms the given RGB color into its corresponding RenderLabel.

◆ MakeRgbFromLabel()

static Rgba MakeRgbFromLabel ( const RenderLabel label)
staticprotected

Transforms the given render label into an RGB color.

The alpha channel will always be 1.0.

◆ operator=() [1/2]

RenderEngine& operator= ( const RenderEngine )
protecteddefault

◆ operator=() [2/2]

RenderEngine& operator= ( RenderEngine &&  )
protecteddefault

◆ RegisterDeformableVisual()

bool RegisterDeformableVisual ( GeometryId  id,
const std::vector< internal::RenderMesh > &  render_meshes,
const PerceptionProperties properties 
)

Requests registration of the given deformable geometry with this render engine.

Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
Parameters
idThe geometry id of the shape to register.
render_meshesThe mesh representations of deformable geometry in its default state. A single geometry may be represented by more than one render mesh. This facilitates registering a geometry with more than one material for rendering.
propertiesThe perception properties provided for this geometry.
Precondition
each RenderMesh in render_meshes is valid.
Exceptions
std::exceptionif a geometry with id has already been registered with this RenderEngine.
std::exceptionif render_meshes is empty.
Returns
True if the RenderEngine implementation accepted the geometry for registration.

◆ RegisterVisual()

bool RegisterVisual ( GeometryId  id,
const Shape shape,
const PerceptionProperties properties,
const math::RigidTransformd &  X_WG,
bool  needs_updates = true 
)

Requests registration of the given shape as a rigid geometry with this render engine.

Parameters
idThe geometry id of the shape to register.
shapeThe shape specification to add to the render engine.
propertiesThe perception properties provided for this geometry.
X_WGThe pose of the geometry relative to the world frame W.
needs_updatesIf true, the geometry's pose will be updated via UpdatePoses().
Returns
True if the RenderEngine implementation accepted the shape for registration.
Exceptions
std::exceptionif the shape is an unsupported type, the shape's RenderLabel value is RenderLabel::kUnspecified or RenderLabel::kEmpty, or a geometry has already been registered with the given id.

◆ RemoveGeometry()

bool RemoveGeometry ( GeometryId  id)

Removes the geometry indicated by the given id from the engine.

Parameters
idThe id of the geometry to remove.
Returns
True if the geometry was removed (false implies that this id wasn't registered with this engine).

◆ RenderColorImage()

void RenderColorImage ( const ColorRenderCamera camera,
systems::sensors::ImageRgba8U color_image_out 
) const

Renders the registered geometry into the given color (rgb) image based on a fully specified camera.

Parameters
cameraThe render engine camera properties.
[out]color_image_outThe rendered color image.
Exceptions
std::exceptionif color_image_out is nullptr or the size of the given input image doesn't match the size declared in camera.

◆ RenderDepthImage()

void RenderDepthImage ( const DepthRenderCamera camera,
systems::sensors::ImageDepth32F depth_image_out 
) const

Renders the registered geometry into the given depth image based on a fully specified camera.

In contrast to the other rendering operations, depth images don't have an option to display the window; generally, basic depth images are not readily communicative to humans.

Parameters
cameraThe render engine camera properties.
[out]depth_image_outThe rendered depth image.
Exceptions
std::exceptionif depth_image_out is nullptr or the size of the given input image doesn't match the size declared in camera.

◆ RenderLabelImage()

void RenderLabelImage ( const ColorRenderCamera camera,
systems::sensors::ImageLabel16I label_image_out 
) const

Renders the registered geometry into the given label image based on a fully specified camera.

Note
This uses the ColorRenderCamera as label images are typically rendered to be exactly registered with a corresponding color image.
Parameters
cameraThe render engine camera properties.
[out]label_image_outThe rendered label image.
Exceptions
std::exceptionif label_image_out is nullptr or the size of the given input image doesn't match the size declared in camera.

◆ SetDefaultLightPosition()

virtual void SetDefaultLightPosition ( const Vector3< double > &  X_DL)
protectedvirtual

Provides access to the light for manual configuration since it's currently bound to the camera position.

This is a temporary measure to facilitate benchmarking and create visible shadows, and should not be used publicly.

Parameters
X_DLThe pose of the light in a frame D that is attached to the camera position. In this frame D, the camera is located at (0, 0, 1), looking towards (0, 0, 0) at a distance of 1, with up being (0, 1, 0).

◆ ThrowIfInvalid()

static void ThrowIfInvalid ( const systems::sensors::CameraInfo intrinsics,
const ImageType *  image,
const char *  image_type 
)
staticprotected

◆ UpdateDeformableConfigurations()

void UpdateDeformableConfigurations ( GeometryId  id,
const std::vector< VectorX< double >> &  q_WGs,
const std::vector< VectorX< double >> &  nhats_W 
)

Updates the configurations of all meshes associated with the given deformable geometry (see RegisterDeformableVisual()).

The number of elements in the supplied vertex position vector q_WGs and the vertex normal vector nhats_W must be equal to the number of render meshes registered to the geometry associated with id. Within each mesh, the vertex positions and normals must be ordered the same way as the vertices specified in the render mesh at registration when reshaped to be an Nx3 matrix with N being the number of vertices in the mesh.

Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
Parameters
idThe unique identifier of a deformable geometry registered with this RenderEngine.
q_WGsThe vertex positions of all meshes associated with the given deformable geometry (measured and expressed in the world frame).
nhats_WThe vertex normals of all meshes associated with the given deformable geometry (measured and expressed in the world frame).
Exceptions
std::exceptionif no geometry with the given id is registered as deformable geometry in this RenderEngine.
std::exceptionif the sizes of q_WGs or nhats_W are incompatible with the number of degrees of freedom of the meshes registered with the deformable geometry.

◆ UpdatePoses()

void UpdatePoses ( const std::unordered_map< GeometryId, math::RigidTransform< T >> &  X_WGs)

Updates the poses of all rigid geometries marked as "needing update" (see RegisterVisual()).

Parameters
X_WGsThe poses of all geometries in SceneGraph (measured and expressed in the world frame). The pose for a geometry is accessed by that geometry's id.

◆ UpdateViewpoint()

virtual void UpdateViewpoint ( const math::RigidTransformd &  X_WR)
pure virtual

Updates the renderer's viewpoint with given pose X_WR.

Parameters
X_WRThe pose of renderer's viewpoint in the world coordinate system.

Friends And Related Function Documentation

◆ RenderEngineTester

friend class RenderEngineTester
friend

The documentation for this class was generated from the following file: