class mrpt::opengl::CFBORender
Overview
Render 3D scenes off-screen directly to RGB and/or RGB+D images.
Main methods:
render_RGB() : Renders a scene into an RGB image.
render_RGBD() : Renders a scene into an RGB and depth images.
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 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); CFBORender(const CFBORender&); CFBORender(CFBORender&&); // methods void setCamera(const mrpt::viz::CCamera& camera); void clearCameraOverride(); mrpt::viz::CCamera& getCameraOverride(); const mrpt::viz::CCamera& getCameraOverride() const; bool hasCameraOverride() const; void render_RGB(const mrpt::viz::Scene& scene, mrpt::img::CImage& outRGB); void render_RGBD(const mrpt::viz::Scene& scene, mrpt::img::CImage& outRGB, mrpt::math::CMatrixFloat& outDepth); void render_depth(const mrpt::viz::Scene& scene, mrpt::math::CMatrixFloat& outDepth); unsigned int width() const; unsigned int height() const; const Parameters& getParameters() const; void invalidateCompiledScene(); CFBORender& operator = (const CFBORender&); CFBORender& operator = (CFBORender&&); };
Construction
CFBORender(const Parameters& p)
Main constructor.
CFBORender(unsigned int width = 800, unsigned int height = 600)
Convenience constructor with just dimensions.
Methods
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.
void clearCameraOverride()
Clear any camera override, reverting to using the scene’s viewport camera.
mrpt::viz::CCamera& getCameraOverride()
Get a mutable reference to the camera override.
Only valid if setCamera() was previously called.
const mrpt::viz::CCamera& getCameraOverride() const
Get the camera override (const version).
bool hasCameraOverride() const
Returns true if a camera override is set.
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.
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) |
See also:
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) |
See also:
render_RGB(), Parameters::raw_depth
void render_depth(const mrpt::viz::Scene& scene, mrpt::math::CMatrixFloat& outDepth)
Like render_RGBD(), but only renders the depth image.
Parameters:
scene |
The abstract viz scene to render |
outDepth |
Output depth matrix (resized if needed) |
See also:
unsigned int width() const
Returns the current render width in pixels.
unsigned int height() const
Returns the current render height in pixels.
const Parameters& getParameters() const
Returns the parameters used to construct this renderer.
void invalidateCompiledScene()
Force recompilation of the scene on next render.
Normally not needed as changes are detected automatically via dirty flags.