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.
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.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< RenderEngine > | Clone () const |
Clones the render engine – making the RenderEngine compatible with copyable_unique_ptr. More... | |
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 with this render engine. 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 geometries marked as "needing update" (see RegisterVisual()). 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... | |
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... | |
![]() | |
virtual | ~ShapeReifier () |
virtual void | ImplementGeometry (const Sphere &sphere, void *user_data) |
virtual void | ImplementGeometry (const Cylinder &cylinder, void *user_data) |
virtual void | ImplementGeometry (const HalfSpace &half_space, void *user_data) |
virtual void | ImplementGeometry (const Box &box, void *user_data) |
virtual void | ImplementGeometry (const Capsule &capsule, void *user_data) |
virtual void | ImplementGeometry (const Ellipsoid &ellipsoid, void *user_data) |
virtual void | ImplementGeometry (const Mesh &mesh, void *user_data) |
virtual void | ImplementGeometry (const Convex &convex, void *user_data) |
virtual void | ImplementGeometry (const MeshcatCone &cone, void *user_data) |
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 geometry registration. More... | |
virtual void | DoUpdateVisualPose (GeometryId id, const math::RigidTransformd &X_WG)=0 |
The NVI-function for updating the pose of a render geometry (identified by id ) to the given pose X_WG. More... | |
virtual bool | DoRemoveGeometry (GeometryId id)=0 |
The NVI-function for removing the geometry with the given id . More... | |
virtual std::unique_ptr< RenderEngine > | DoClone () 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 | |
RenderEngine & | operator= (const RenderEngine &)=default |
RenderEngine (RenderEngine &&)=default | |
RenderEngine & | operator= (RenderEngine &&)=default |
![]() | |
ShapeReifier ()=default | |
virtual void | ThrowUnsupportedGeometry (const std::string &shape_name) |
Derived ShapeReifiers can replace the default message for unsupported geometries by overriding this method. More... | |
ShapeReifier (const ShapeReifier &)=default | |
ShapeReifier & | operator= (const ShapeReifier &)=default |
ShapeReifier (ShapeReifier &&)=default | |
ShapeReifier & | operator= (ShapeReifier &&)=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. The label-to-color conversion can produce one of two different color encodings. These encodings are not exhaustive but they are typical of the encodings that have proven useful. The supported color encodings consist of three RGB channels where each channel is either byte-valued in that they are encoded with unsigned bytes in the range [0, 255] per channel or double-valued such that each channel is encoded with a double in the range [0, 1]. Conversion to RenderLabel is only supported from byte-valued color values. | |
static RenderLabel | LabelFromColor (const systems::sensors::ColorI &color) |
Transforms the given byte-valued RGB color value into its corresponding RenderLabel. More... | |
static systems::sensors::ColorI | GetColorIFromLabel (const RenderLabel &label) |
Transforms this render label into a byte-valued RGB color. More... | |
static systems::sensors::ColorD | GetColorDFromLabel (const RenderLabel &label) |
Transforms this render label into a double-valued RGB color. More... | |
Friends | |
class | RenderEngineTester |
|
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.)
std::exception | if the default render label is not one of the two allowed labels. |
|
virtualdefault |
|
protecteddefault |
|
protecteddefault |
std::unique_ptr<RenderEngine> Clone | ( | ) | const |
Clones the render engine – making the RenderEngine compatible with copyable_unique_ptr.
RenderLabel default_render_label | ( | ) | const |
Reports the render label value this render engine has been configured to use.
|
protectedpure virtual |
The NVI-function for cloning this render engine.
|
protectedpure virtual |
The NVI-function for sub-classes to implement actual geometry registration.
If the derived class chooses not to register this particular shape, it should return false.
A derived render engine can choose not to register geometry because, e.g., it doesn't have default properties. This is the primary mechanism which enables different renderers to use different geometries for the same frame. For example, a low-fidelity renderer may use simple geometry whereas a high-fidelity renderer would require a very detailed geometry. Both geometries would have PerceptionProperties, but, based on the provided property groups and values, one would be accepted and registered with one render engine implementation and the other geometry with another render engine.
In accessing the RenderLabel property in properties
derived class should exclusively use GetRenderLabelOrThrow().
|
protectedpure virtual |
The NVI-function for removing the geometry with the given id
.
id | The id of the geometry to remove. |
|
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.
std::exception | in its default implementaiton indicating that it has not been implemented. Derived RenderEngine classes must implement this to support rendering color images. |
|
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.
std::exception | in its default implementaiton indicating that it has not been implemented. Derived RenderEngine classes must implement this to support rendering depth images. |
|
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.
std::exception | in its default implementaiton indicating that it has not been implemented. Derived RenderEngine classes must implement this to support rendering label images. |
|
protectedpure virtual |
The NVI-function for updating the pose of a render geometry (identified by id
) to the given pose X_WG.
id | The id of the render geometry whose pose is being set. |
X_WG | The pose of the render geometry in the world frame. |
|
staticprotected |
Transforms this
render label into a double-valued RGB color.
|
staticprotected |
Transforms this
render label into a byte-valued RGB color.
|
protected |
Extracts the (label, id)
RenderLabel property from the given properties
and validates it (or the configured default if no such property is defined).
std::exception | If the tested render label value is deemed invalid. |
bool has_geometry | ( | GeometryId | id | ) | const |
Reports true if a geometry with the given id
has been registered with this
engine.
|
staticprotected |
Transforms the given byte-valued RGB color value into its corresponding RenderLabel.
|
protecteddefault |
|
protecteddefault |
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 with this render engine.
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).
id | The geometry id of the shape to register. |
shape | The shape specification to add to the render engine. |
properties | The perception properties provided for this geometry. |
X_WG | The pose of the geometry relative to the world frame W. |
needs_updates | If true, the geometry's pose will be updated via UpdatePoses(). |
std::exception | if 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 . |
bool RemoveGeometry | ( | GeometryId | id | ) |
Removes the geometry indicated by the given id
from the engine.
id | The id of the geometry to remove. |
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.
camera | The render engine camera properties. | |
[out] | color_image_out | The rendered color image. |
std::exception | if color_image_out is nullptr or the size of the given input image doesn't match the size declared in camera . |
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.
camera | The render engine camera properties. | |
[out] | depth_image_out | The rendered depth image. |
std::exception | if depth_image_out is nullptr or the size of the given input image doesn't match the size declared in camera . |
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.
camera | The render engine camera properties. | |
[out] | label_image_out | The rendered label image. |
std::exception | if label_image_out is nullptr or the size of the given input image doesn't match the size declared in camera . |
|
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.
X_DL | The 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). |
|
staticprotected |
void UpdatePoses | ( | const std::unordered_map< GeometryId, math::RigidTransform< T >> & | X_WGs | ) |
Updates the poses of all geometries marked as "needing update" (see RegisterVisual()).
X_WGs | The 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. |
|
pure virtual |
Updates the renderer's viewpoint with given pose X_WR.
X_WR | The pose of renderer's viewpoint in the world coordinate system. |
Implemented in RenderEngineVtk.
|
friend |