Drake
Drake C++ Documentation
drake::geometry::render::shaders Namespace Reference

Variables

constexpr char kDepthVS []
 A vertex shader program for rendering depth images, which computes vertices and normals for the fragment shader program coming after. More...
 
constexpr char kDepthFS []
 A fragment shader program for rendering depth images, which computes depth values for each pixel in depth images, converts them to be in range [0, 1] and packs those values to three color channels. More...
 

Variable Documentation

◆ kDepthFS

constexpr char kDepthFS[]

A fragment shader program for rendering depth images, which computes depth values for each pixel in depth images, converts them to be in range [0, 1] and packs those values to three color channels.

In other words, we encode a depth image into a color image and output the color image. For the detail of packing algorithm, please refer to: https://aras-p.info/blog/2009/07/30/encoding-floats-to-rgba-the-final/ Note that we are only using three channels instead of four channels to express a float value. This differs from the example code in the link above. The reason is that we need to set one to alpha channel so that the rendered "image" will be opaque. Otherwise, we will have different colors from what we output here, thus expect, in the end.

◆ kDepthVS

constexpr char kDepthVS[]
Initial value:
= R"""(
//VTK::System::Dec
attribute vec4 vertexMC;
uniform mat4 MCDCMatrix;
uniform mat4 MCVCMatrix;
varying vec4 vertexVCVSOutput;
void main () {
vertexVCVSOutput = MCVCMatrix * vertexMC;
gl_Position = MCDCMatrix * vertexMC;
}
)"""

A vertex shader program for rendering depth images, which computes vertices and normals for the fragment shader program coming after.