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().
|
| 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 | 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...
|
|
|
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...
|
|
|
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 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< 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...
|
|
|
| RenderEngine (const RenderEngine &)=default |
|
RenderEngine & | operator= (const RenderEngine &)=default |
|
| RenderEngine (RenderEngine &&)=default |
|
RenderEngine & | operator= (RenderEngine &&)=default |
|
|
template<typename ImageType > |
static void | ThrowIfInvalid (const systems::sensors::CameraInfo &intrinsics, const ImageType *image, const char *image_type) |
|
|
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...
|
|
static RenderLabel | LabelFromColor (const deprecated::internal::Color< int > &color) |
| (Deprecated.) More...
|
|
static deprecated::internal::Color< int > | GetColorIFromLabel (const RenderLabel &label) |
| (Deprecated.) More...
|
|
static deprecated::internal::Color< double > | GetColorDFromLabel (const RenderLabel &label) |
| (Deprecated.) More...
|
|