Class CFBORender

Nested Relationships

Nested Types

Class Documentation

class CFBORender

Render 3D scenes off-screen directly to RGB and/or RGB+D images.

Main methods:

To define a background color, define it in your scene.getViewport()->setCustomBackgroundColor(). You can add overlaid text messages, see base class CTextMessageCapable.

The SE(3) pose from which the scene is rendered is defined by the scene "main" viewport camera pose, or can be overridden via setCamera().

Architecture (MRPT 3.0):

  • Uses mrpt::viz::Scene as the abstract scene graph

  • Internally maintains a CompiledScene for GPU-side representation

  • Automatically recompiles when the scene changes (dirty flags)

See gui_fbo_render_example for code examples.

See also

opengl_offscreen_render_example , gui_fbo_render_example

Camera Control

inline void setCamera(const mrpt::viz::CCamera &camera)

Set the camera to use for rendering, overriding the scene’s viewport camera.

If not called, the camera from the scene’s “main” viewport is used.

inline void clearCameraOverride()

Clear any camera override, reverting to using the scene’s viewport camera.

inline mrpt::viz::CCamera &getCameraOverride()

Get a mutable reference to the camera override.

Note

Only valid if setCamera() was previously called.

inline const mrpt::viz::CCamera &getCameraOverride() const

Get the camera override (const version).

inline bool hasCameraOverride() const

Returns true if a camera override is set.

Rendering Methods

void render_RGB(const mrpt::viz::Scene &scene, mrpt::img::CImage &outRGB)

Render the scene and get the rendered RGB image.

Resizes the image buffer if necessary to the configured render resolution.

See also

render_RGBD()

Note

The scene is compiled on first call, then incrementally updated.

Parameters:
  • scene – The abstract viz scene to render

  • outRGB – Output RGB image (resized if needed)

void render_RGBD(const mrpt::viz::Scene &scene, mrpt::img::CImage &outRGB, mrpt::math::CMatrixFloat &outDepth)

Render the scene and get the rendered RGB and depth images.

Resizes the provided buffers if necessary to the configured render resolution.

The output depth image is in linear depth distance units (e.g. “meters”). Note that values are depth, not range, that is, it’s the “+z” coordinate of a point as seen from the camera, with +Z pointing forward in the view direction (the common convention in computer vision).

Pixels without any observed object in the valid viewport {clipMin, clipMax} range will be returned with a depth of 0.0.

Parameters:
  • scene – The abstract viz scene to render

  • outRGB – Output RGB image (resized if needed)

  • outDepth – Output depth matrix (resized if needed)

void render_depth(const mrpt::viz::Scene &scene, mrpt::math::CMatrixFloat &outDepth)

Like render_RGBD(), but only renders the depth image.

See also

render_RGBD()

Parameters:
  • scene – The abstract viz scene to render

  • outDepth – Output depth matrix (resized if needed)

Status and Configuration

inline unsigned int width() const

Returns the current render width in pixels

inline unsigned int height() const

Returns the current render height in pixels

inline const Parameters &getParameters() const

Returns the parameters used to construct this renderer

inline void invalidateCompiledScene()

Force recompilation of the scene on next render.

Normally not needed as changes are detected automatically via dirty flags.

Public Functions

explicit CFBORender(const Parameters &p)

Main constructor

inline CFBORender(unsigned int width = 800, unsigned int height = 600)

Convenience constructor with just dimensions

~CFBORender()

Destructor

CFBORender(const CFBORender&) = delete
CFBORender &operator=(const CFBORender&) = delete
CFBORender(CFBORender&&) = delete
CFBORender &operator=(CFBORender&&) = delete

Protected Functions

void internal_render_RGBD(const mrpt::viz::Scene &scene, const mrpt::optional_ref<mrpt::img::CImage> &outRGB, const mrpt::optional_ref<mrpt::math::CMatrixFloat> &outDepth)

Internal rendering implementation

void ensureCompiledScene(const mrpt::viz::Scene &scene)

Ensures the compiled scene is up-to-date with the source scene

void convertDepthToLinear(mrpt::math::CMatrixFloat &depth, float zNear, float zFar) const

Converts raw OpenGL depth buffer to linear depth values

Protected Attributes

void *m_eglDpy = nullptr
void *m_eglCfg = nullptr
void *m_eglContext = nullptr
void *m_eglSurf = nullptr
unsigned int m_texRGB = 0
const Parameters m_params
FrameBuffer m_fb
mrpt::viz::CCamera m_cameraOverride
bool m_useCameraOverride = false
std::unique_ptr<CompiledScene> m_compiledScene
const mrpt::viz::Scene *m_lastScene = nullptr
struct Parameters

Parameters for CFBORender constructor

Public Functions

Parameters() = default
inline Parameters(unsigned int Width, unsigned int Height)

Public Members

unsigned int width = 800

Width of images to render.

unsigned int height = 600

Height of images to render.

bool raw_depth = false

If false (default), depth values returned in CFBORender::render_RGBD() or CFBORender::render_depth() are real depth values (e.g. units=meters). If this is “true”, raw OpenGL depth values in the range [0,1] are left in the returned depth matrix, so it is the user responsibility to map those logarithm depths to linear ones. Useful when only a subset of all depths are required.

bool create_EGL_context = true

By default, each CFBORender constructor will create its own EGL context, which enables using them in different threads, use in head-less applications, etc.

Set this to false to save that effort, only if it is ensured that render calls will always happen from a thread where OpenGL has been already initialized and a context created.

int deviceIndexToUse = 0

Can be used to select a particular GPU (or software-emulated) device.

Create a CFBORender object with the environment variable MRPT_FBORENDER_SHOW_DEVICES=true to see a list of available and detected GPU devices.

int blueSize = 8
int redSize = 8
int greenSize = 8
int depthSize = 24
bool conformantOpenGLES2 = false

Default: EGL_OPENGL_ES_BIT.

bool renderableOpenGLES2 = false

Default: EGL_OPENGL_ES_BIT.

bool bindOpenGLES_API = false

Default: EGL_OPENGL_API.

int contextMajorVersion = 0

0=default

int contextMinorVersion = 0

0=default

bool contextDebug = false

See https://www.khronos.org/opengl/wiki/Debug_Output.