class mrpt::opengl::CFBORender

Overview

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. See Example: gui_fbo_render_example for code examples.

See also:

Example: opengl_offscreen_render_example, Example: gui_fbo_render_example

#include <mrpt/opengl/CFBORender.h>

class CFBORender
{
public:
    // structs

    struct Parameters;

    // construction

    CFBORender(const Parameters& p);
    CFBORender(unsigned int width = 800, unsigned int height = 600);

    // methods

    void setCamera(const Scene& scene, const CCamera& camera);
    CCamera& getCamera(const Scene& scene);
    void render_RGB(const Scene& scene, mrpt::img::CImage& outRGB);
    void render_RGBD(const Scene& scene, mrpt::img::CImage& outRGB, mrpt::math::CMatrixFloat& outDepth);
    void render_depth(const Scene& scene, mrpt::math::CMatrixFloat& outDepth);
};

Construction

CFBORender(const Parameters& p)

Main constructor.

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

Constructor.

Methods

void setCamera(const Scene& scene, const CCamera& camera)

Change the scene camera to be used when rendering the scene through this particular instance of CFBORender.

CCamera& getCamera(const Scene& scene)

Get a reference to the scene camera to be used when rendering the scene through this particular instance of CFBORender.

void render_RGB(const 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()

void render_RGBD(const 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 is 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 range of 0.0.

See also:

render_RGB(), Parameters::raw_depth

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

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

See also:

render_RGBD()