struct mrpt::opengl::CFBORender::Parameters

Overview

Parameters for CFBORender constructor.

#include <mrpt/opengl/CFBORender.h>

struct Parameters
{
    // fields

    unsigned int width = 800;
    unsigned int height = 600;
    bool raw_depth = false;
    bool create_EGL_context = true;
    int deviceIndexToUse = 0;
    int blueSize = 8;
    int redSize = 8;
    int greenSize = 8;
    int depthSize = 24;
    bool conformantOpenGLES2 = false;
    bool renderableOpenGLES2 = false;
    bool bindOpenGLES_API = false;
    int contextMajorVersion = 0;
    int contextMinorVersion = 0;
    bool contextDebug = false;

    // construction

    Parameters();

    Parameters(
        unsigned int Width,
        unsigned int Height
        );
};

Fields

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 [-1,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.

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.