Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
137 changes: 137 additions & 0 deletions bindings/generated_docstrings/geometry_render_vtk.h
Original file line number Diff line number Diff line change
Expand Up @@ -412,6 +412,14 @@ times but improve shadow fidelity (less obvious pixelation).
See the note on ``cast_shadows`` for the warning on directional lights
and shadow maps.)""";
} shadow_map_size;
// Symbol: drake::geometry::RenderEngineVtkParams::ssao
struct /* ssao */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc =
R"""(An optional SSAO (screen-space ambient occlusion) parameters set. When
specified, VTK enables screen-space ambient occlusion configured by
the given parameters.)""";
} ssao;
auto Serialize__fields() const {
return std::array{
std::make_pair("backend", backend.doc),
Expand All @@ -424,9 +432,138 @@ and shadow maps.)""";
std::make_pair("gltf_extensions", gltf_extensions.doc),
std::make_pair("lights", lights.doc),
std::make_pair("shadow_map_size", shadow_map_size.doc),
std::make_pair("ssao", ssao.doc),
};
}
} RenderEngineVtkParams;
// Symbol: drake::geometry::SsaoParameter
struct /* SsaoParameter */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc =
R"""(Screen-space ambient occlusion (SSAO) parameters.

Ambient occlusion is a shading method used to calculate how exposed
each point in a scene is to ambient lighting. The more occluded a
point is, the darker it appears. SSAO is an efficient, real-time
approximation of ambient occlusion that operates in screen space. It
enhances the depth and realism of a scene by adding subtle shadowing
effects in creases, holes, and surfaces that are close to each other.
See https://www.kitware.com/ssao/ for an overview.

The default parameter values below have been chosen as a best-guess
effort at producing good quality images. They may not be optimal for
your particular scene.

To understand how to tune these parameters, you need a bit of insight
into how ambient occlusion works generally, and how SSAO works
specifically. For each pixel, its "occlusion factor" is determined by
examining a hemispherical area around the pixel's position in 3D space
(oriented based on its normal). The fraction of the hemisphere
contained within geometry is the occlusion factor.

SSAO produces a discrete approximation of the true occlusion factor.
It evaluates a discrete number of samples within the hemisphere and
compares their depths (in the OpenGL-camera sense) with that of the
pixel being shaded to determine how much of the hemisphere is occupied
by geometry. As with all discrete approximations, there is a tradeoff
between fidelity and cost. The parameter documentation below provides
some guidance on the effect of each parameter on the final rendered
image.)""";
// Symbol: drake::geometry::SsaoParameter::Serialize
struct /* Serialize */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc =
R"""(Passes this object to an Archive. Refer to yaml_serialization "YAML
Serialization" for background.)""";
} Serialize;
// Symbol: drake::geometry::SsaoParameter::bias
struct /* bias */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc =
R"""(SSAO works in screen space; so it uses the depth image to determine
whether a sample lies within the hemisphere or not. We compare the
depth of a sample point with the recorded depth in the same direction.
In principle, if the sample point is farther than the recorded depth,
the sample is occluded. This bias pads that calculation by specifying
how far in front (in meters) the recorded distance has to be before
the sample is considered occluded. Larger bias values will classify
fewer samples as occluded, reducing the amount of ambient occlusion
(darkness) in the final image.

A non-zero value is usually helpful to help resolve potential issues
due to depth map precision issues (so-called "acne"), but it should
generally be small.)""";
} bias;
// Symbol: drake::geometry::SsaoParameter::blur
struct /* blur */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc =
R"""(The discrete sampling approach will ultimately produce shading with a
noisy pattern. More samples will reduce the noise, but you can also
apply a blur to the final occlusion image to reduce the noise. This is
a screen space blur, so it is fast. However, it will also reduce the
sharpness of occlusion patterns. You can disable blurring to speed
things up, but it will emphasize the sampling noise.)""";
} blur;
// Symbol: drake::geometry::SsaoParameter::intensity_scale
struct /* intensity_scale */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc =
R"""(Once the occlusion factor is computed, prior to applying the factor to
the shaded pixel, you can apply a final affine transformation:

occlusion = (occlusion - intensity_shift) * intensity_scale

Using these two values allows you to tune the contrast and mean
occlusion value independent of the sampling algorithm above. Remember,
the more occlusion, the more darkness. So, scale factors greater than
one will make the image darker as will *negative* shift values.

One reason to consider shifting is is based on the total lighting in
the scene. For a very brightly lit scene with a large camera exposure,
the ambient occlusion effects should have a smaller influence. A scale
less than one, or a shift greater than zero, will reduce the SSAO
effect.)""";
} intensity_scale;
// Symbol: drake::geometry::SsaoParameter::intensity_shift
struct /* intensity_shift */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc = R"""()""";
} intensity_shift;
// Symbol: drake::geometry::SsaoParameter::radius
struct /* radius */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc =
R"""(The radius (in meters) of the sampling hemisphere. There is no
"correct" value. Heuristically, it should scale with your scene. A
rubric of 1/10th the size of your scene is reasonable. For example,
0.25 meters is good for a robot working at a table top.

If the radius is too large, pixels will exhibit occlusion (darkness)
from objects that might seem too distant to be relevant. A too-small
radius would have the opposite effect; missing occlusion where it
seems it should occur.)""";
} radius;
// Symbol: drake::geometry::SsaoParameter::sample_count
struct /* sample_count */ {
// Source: drake/geometry/render_vtk/render_engine_vtk_params.h
const char* doc =
R"""(This is simply the number of samples taken. More samples lead to
smoother occlusion patterns. Large numbers will produce better images
but at a higher computational cost. You should use the smallest number
that still provides acceptable visual quality.)""";
} sample_count;
auto Serialize__fields() const {
return std::array{
std::make_pair("bias", bias.doc),
std::make_pair("blur", blur.doc),
std::make_pair("intensity_scale", intensity_scale.doc),
std::make_pair("intensity_shift", intensity_shift.doc),
std::make_pair("radius", radius.doc),
std::make_pair("sample_count", sample_count.doc),
};
}
} SsaoParameter;
// Symbol: drake::geometry::render_vtk
struct /* render_vtk */ {
} render_vtk;
Expand Down
12 changes: 12 additions & 0 deletions bindings/pydrake/geometry/geometry_py_render.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ using Eigen::Vector3d;
using geometry::GeometryId;
using geometry::PerceptionProperties;
using geometry::Shape;
using geometry::SsaoParameter;
using geometry::render::ColorRenderCamera;
using geometry::render::DepthRenderCamera;
using geometry::render::LightParameter;
Expand Down Expand Up @@ -423,6 +424,17 @@ void DoScalarIndependentDefinitions(py::module m) {
DefCopyAndDeepCopy(&cls);
}

{
using Class = geometry::SsaoParameter;
constexpr auto& cls_doc = doc_vtk.SsaoParameter;
py::class_<Class> cls(m, "SsaoParameter", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}

{
using Class = RenderEngineVtkParams;
constexpr auto& cls_doc = doc_vtk.RenderEngineVtkParams;
Expand Down
22 changes: 22 additions & 0 deletions bindings/pydrake/geometry/test/render_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,28 @@ def test_light_param(self):
self.assertIn("spot", repr(light))
copy.copy(light)

def test_ssao_param(self):
# A default constructor exists.
mut.SsaoParameter()

# The kwarg constructor also works.
params = mut.SsaoParameter(
radius=0.2,
bias=0.01,
sample_count=8,
intensity_scale=1.5,
intensity_shift=0.05,
blur=False)
self.assertEqual(params.radius, 0.2)
self.assertEqual(params.bias, 0.01)
self.assertEqual(params.sample_count, 8)
self.assertEqual(params.intensity_scale, 1.5)
self.assertEqual(params.intensity_shift, 0.05)
self.assertFalse(params.blur)

self.assertIn("bias", repr(params))
copy.copy(params)

def test_equirectangular_map(self):
# A default constructor exists.
mut.EquirectangularMap()
Expand Down
1 change: 1 addition & 0 deletions geometry/render_vtk/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,7 @@ drake_cc_googletest(
timeout = "moderate",
data = [
":test/multi_material_mesh.png",
":test/ssao_reference.png",
":test/whole_image_custom_color.png",
":test/whole_image_custom_depth.png",
":test/whole_image_custom_label.png",
Expand Down
23 changes: 22 additions & 1 deletion geometry/render_vtk/internal_render_engine_vtk.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <vtkPointData.h> // vtkCommonDataModel
#include <vtkProperty.h> // vtkRenderingCore
#include <vtkRenderPassCollection.h> // vtkRenderingOpenGL2
#include <vtkSSAOPass.h> // vtkRenderingOpenGL2
#include <vtkSequencePass.h> // vtkRenderingOpenGL2
#include <vtkShadowMapBakerPass.h> // vtkRenderingOpenGL2
#include <vtkShadowMapPass.h> // vtkRenderingOpenGL2
Expand Down Expand Up @@ -962,7 +963,27 @@ void RenderEngineVtk::InitializePipelines() {
vtkNew<vtkSequencePass> full_seq;
vtkNew<vtkRenderPassCollection> full_passes;
full_passes->AddItem(vtkNew<vtkLightsPass>());
full_passes->AddItem(vtkNew<vtkOpaquePass>());
if (parameters_.ssao.has_value()) {
vtkNew<vtkOpaquePass> opaque_pass;

vtkNew<vtkCameraPass> ssao_camera_pass;
ssao_camera_pass->SetDelegatePass(opaque_pass);

vtkNew<vtkSSAOPass> ssao_pass;
ssao_pass->SetDelegatePass(ssao_camera_pass);

const auto& ssao_parameter = parameters_.ssao.value();
ssao_pass->SetRadius(ssao_parameter.radius);
ssao_pass->SetBias(ssao_parameter.bias);
ssao_pass->SetKernelSize(ssao_parameter.sample_count);
ssao_pass->SetIntensityScale(ssao_parameter.intensity_scale);
ssao_pass->SetIntensityShift(ssao_parameter.intensity_shift);
ssao_pass->SetBlur(ssao_parameter.blur);

full_passes->AddItem(ssao_pass);
} else {
full_passes->AddItem(vtkNew<vtkOpaquePass>());
}
full_passes->AddItem(vtkNew<vtkTranslucentPass>());
full_seq->SetPasses(full_passes);

Expand Down
102 changes: 102 additions & 0 deletions geometry/render_vtk/render_engine_vtk_params.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,102 @@
namespace drake {
namespace geometry {

/** Screen-space ambient occlusion (SSAO) parameters.

Ambient occlusion is a shading method used to calculate how exposed each point
in a scene is to ambient lighting. The more occluded a point is, the darker it
appears. SSAO is an efficient, real-time approximation of ambient occlusion
that operates in screen space. It enhances the depth and realism of a scene by
adding subtle shadowing effects in creases, holes, and surfaces that are close
to each other. See https://www.kitware.com/ssao/ for an overview.

The default parameter values below have been chosen as a best-guess effort at
producing good quality images. They may not be optimal for your particular
scene.

To understand how to tune these parameters, you need a bit of insight into how
ambient occlusion works generally, and how SSAO works specifically. For each
pixel, its "occlusion factor" is determined by examining a hemispherical area
around the pixel's position in 3D space (oriented based on its normal). The
fraction of the hemisphere contained within geometry is the occlusion factor.

SSAO produces a discrete approximation of the true occlusion factor. It
evaluates a discrete number of samples within the hemisphere and compares their
depths (in the OpenGL-camera sense) with that of the pixel being shaded to
determine how much of the hemisphere is occupied by geometry. As with all
discrete approximations, there is a tradeoff between fidelity and cost. The
parameter documentation below provides some guidance on the effect of each
parameter on the final rendered image. */
struct SsaoParameter {
/** Passes this object to an Archive.
Refer to @ref yaml_serialization "YAML Serialization" for background. */
template <typename Archive>
void Serialize(Archive* a) {
a->Visit(DRAKE_NVP(radius));
a->Visit(DRAKE_NVP(bias));
a->Visit(DRAKE_NVP(sample_count));
a->Visit(DRAKE_NVP(intensity_scale));
a->Visit(DRAKE_NVP(intensity_shift));
a->Visit(DRAKE_NVP(blur));
}

/** The radius (in meters) of the sampling hemisphere. There is no "correct"
value. Heuristically, it should scale with your scene. A rubric of 1/10th the
size of your scene is reasonable. For example, 0.25 meters is good for a
robot working at a table top.

If the radius is too large, pixels will exhibit occlusion (darkness) from
objects that might seem too distant to be relevant. A too-small radius would
have the opposite effect; missing occlusion where it seems it should occur.
*/
double radius{0.25};

/** SSAO works in screen space; so it uses the depth image to determine
whether a sample lies within the hemisphere or not. We compare the depth of
a sample point with the recorded depth in the same direction. In principle,
if the sample point is farther than the recorded depth, the sample is
occluded. This bias pads that calculation by specifying how far in front (in
meters) the recorded distance has to be before the sample is considered
occluded. Larger bias values will classify fewer samples as occluded,
reducing the amount of ambient occlusion (darkness) in the final image.

A non-zero value is usually helpful to help resolve potential issues due to
depth map precision issues (so-called "acne"), but it should generally be
small. */
double bias{0.01};

/** This is simply the number of samples taken. More samples lead to smoother
occlusion patterns. Large numbers will produce better images but at a higher
computational cost. You should use the smallest number that still provides
acceptable visual quality. */
int sample_count{128};

/** Once the occlusion factor is computed, prior to applying the factor to
the shaded pixel, you can apply a final affine transformation:

occlusion = (occlusion - intensity_shift) * intensity_scale

Using these two values allows you to tune the contrast and mean occlusion
value independent of the sampling algorithm above. Remember, the more
occlusion, the more darkness. So, scale factors greater than one will make
the image darker as will *negative* shift values.

One reason to consider shifting is is based on the total lighting in the
scene. For a very brightly lit scene with a large camera exposure, the
ambient occlusion effects should have a smaller influence. A scale less
than one, or a shift greater than zero, will reduce the SSAO effect. */
double intensity_scale{1.0};
double intensity_shift{0.0};

/** The discrete sampling approach will ultimately produce shading with a
noisy pattern. More samples will reduce the noise, but you can also apply a
blur to the final occlusion image to reduce the noise. This is a screen
space blur, so it is fast. However, it will also reduce the sharpness of
occlusion patterns. You can disable blurring to speed things up, but it will
emphasize the sampling noise. */
bool blur{true};
};

// TODO(SeanCurtis-TRI): When CubeMap is implemented, replace NullTexture with
// CubeMap.

Expand Down Expand Up @@ -101,6 +197,7 @@ struct RenderEngineVtkParams {
a->Visit(DRAKE_NVP(lights));
a->Visit(DRAKE_NVP(environment_map));
a->Visit(DRAKE_NVP(exposure));
a->Visit(DRAKE_NVP(ssao));
a->Visit(DRAKE_NVP(cast_shadows));
a->Visit(DRAKE_NVP(shadow_map_size));
a->Visit(DRAKE_NVP(force_to_pbr));
Expand Down Expand Up @@ -174,6 +271,11 @@ struct RenderEngineVtkParams {
*/
std::optional<double> exposure{};

/** An optional SSAO (screen-space ambient occlusion) parameters set. When
specified, VTK enables screen-space ambient occlusion configured by the
given parameters. */
std::optional<SsaoParameter> ssao{};

/** If `true`, *all* lights that are *able* to cast shadows will do so.

Several important notes when designing your lighting:
Expand Down
Loading