Skip to content

Commit

Permalink
[render] Modify vtk cube texture coordinate generation (RobotLocomoti…
Browse files Browse the repository at this point in the history
…on#12972)

* Modify vtk cube texture coordinate generation

The default vtk cube source produces texture coordinates based on the
size *and* position of the cube in the geometry frame. More or less, the
vertex position becomes a uv coordinate (projected onto one of six planes).
This has several undesirable properties:

  1. Small boxes will only be mapped with small portions of the texture.
  2. Large boxes will have the texture tiled multiple times.

This introduces a new cube geometry that is equivalent to the vtk cube
source, except it defaults to the texture being stretched over each face,
with the possibility of tiling it via a (currently hidden) uv_scale
property. It also removes all mention of the vtkCubeSource.
  • Loading branch information
SeanCurtis-TRI authored Apr 2, 2020
1 parent 7558bb6 commit f5a7ad5
Show file tree
Hide file tree
Showing 9 changed files with 419 additions and 46 deletions.
10 changes: 10 additions & 0 deletions geometry/render/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,8 @@ drake_cc_library(
],
visibility = ["//visibility:private"],
deps = [
"//common:scope_exit",
"//geometry:geometry_roles",
"//geometry:shape_specification",
"//third_party/com_github_finetjul_bender:vtkCapsuleSource",
"@vtk//:vtkCommonCore",
Expand Down Expand Up @@ -160,6 +162,12 @@ drake_cc_library(

# === test/ ===

filegroup(
name = "test_models",
testonly = 1,
srcs = ["test/diag_gradient.png"],
)

drake_cc_googletest(
name = "render_engine_test",
deps = [
Expand All @@ -173,6 +181,7 @@ drake_cc_googletest(
drake_cc_googletest(
name = "render_engine_ospray_test",
data = [
":test_models",
"//systems/sensors:test_models",
],
# This generally flakes on CI for unknown reasons.
Expand All @@ -193,6 +202,7 @@ drake_cc_googletest(
drake_cc_googletest(
name = "render_engine_vtk_test",
data = [
":test_models",
"//systems/sensors:test_models",
],
tags = vtk_test_tags(),
Expand Down
9 changes: 3 additions & 6 deletions geometry/render/render_engine_ospray.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#include <utility>

#include <vtkCamera.h>
#include <vtkCubeSource.h>
#include <vtkCylinderSource.h>
#include <vtkOBJReader.h>
#include <vtkOSPRayLightNode.h>
Expand Down Expand Up @@ -203,11 +202,9 @@ void RenderEngineOspray::ImplementGeometry(const HalfSpace&, void* user_data) {
}

void RenderEngineOspray::ImplementGeometry(const Box& box, void* user_data) {
vtkNew<vtkCubeSource> cube;
cube->SetXLength(box.width());
cube->SetYLength(box.depth());
cube->SetZLength(box.height());
ImplementGeometry(cube.GetPointer(), user_data);
const RegistrationData* data = static_cast<RegistrationData*>(user_data);
ImplementGeometry(CreateVtkBox(box, data->properties).GetPointer(),
user_data);
}

void RenderEngineOspray::ImplementGeometry(const Capsule& capsule,
Expand Down
14 changes: 8 additions & 6 deletions geometry/render/render_engine_vtk.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#include <utility>

#include <vtkCamera.h>
#include <vtkCubeSource.h>
#include <vtkCylinderSource.h>
#include <vtkOBJReader.h>
#include <vtkOpenGLPolyDataMapper.h>
Expand All @@ -28,6 +27,7 @@ namespace drake {
namespace geometry {
namespace render {

using Eigen::Vector2d;
using Eigen::Vector4d;
using std::make_unique;
using math::RigidTransformd;
Expand Down Expand Up @@ -253,11 +253,9 @@ void RenderEngineVtk::ImplementGeometry(const HalfSpace&,
}

void RenderEngineVtk::ImplementGeometry(const Box& box, void* user_data) {
vtkNew<vtkCubeSource> cube;
cube->SetXLength(box.width());
cube->SetYLength(box.depth());
cube->SetZLength(box.height());
ImplementGeometry(cube.GetPointer(), user_data);
const RegistrationData* data = static_cast<RegistrationData*>(user_data);
ImplementGeometry(CreateVtkBox(box, data->properties).GetPointer(),
user_data);
}

void RenderEngineVtk::ImplementGeometry(const Capsule& capsule,
Expand Down Expand Up @@ -547,11 +545,15 @@ void RenderEngineVtk::ImplementGeometry(vtkPolyDataAlgorithm* source,
}
}
if (!texture_name.empty()) {
const Vector2d& uv_scale = data.properties.GetPropertyOrDefault(
"phong", "diffuse_scale", Vector2d{1, 1});
vtkNew<vtkPNGReader> texture_reader;
texture_reader->SetFileName(texture_name.c_str());
texture_reader->Update();
vtkNew<vtkOpenGLTexture> texture;
texture->SetInputConnection(texture_reader->GetOutputPort());
const bool need_repeat = uv_scale[0] > 1 || uv_scale[1] > 1;
texture->SetRepeat(need_repeat);
texture->InterpolateOn();
color_actor->SetTexture(texture.Get());
} else {
Expand Down
235 changes: 234 additions & 1 deletion geometry/render/render_engine_vtk_base.cc
Original file line number Diff line number Diff line change
@@ -1,14 +1,236 @@
#include "drake/geometry/render/render_engine_vtk_base.h"

#include <ostream>
#include <utility>
#include <vector>

#include <vtkCellArray.h>
#include <vtkFloatArray.h>
#include <vtkInformation.h>
#include <vtkInformationVector.h>
#include <vtkObjectFactory.h>
#include <vtkPointData.h>
#include <vtkPoints.h>
#include <vtkPolyData.h>
#include <vtkPolyDataAlgorithm.h>
#include <vtkStreamingDemandDrivenPipeline.h>
#include "third_party/com_github_finetjul_bender/vtkCapsuleSource.h"

#include "drake/common/scope_exit.h"

namespace drake {
namespace geometry {
namespace render {

using com_github_finetjul_bender::vtkCapsuleSource;
using Eigen::Vector2d;

namespace {

using Eigen::Vector3d;

// TODO(SeanCurtis-TRI): The semantics of this textured box needs to be
// explained *somewhere* in the documentation. The layout of the texture on the
// box and (eventually) its ability to be transformed. But also for all shapes.

/* A custom poly data algorithm for creating a Box for Drake. This differs from
(and is preferred over) the vtkCubeSource for the following reasons.
1. The definition is always centered around the origin of the box's canonical
frame. This matches the shape specification cleanly.
2. The vtkCubeSource generates texture coordinates (uvs) in a strange way.
The vertices are assigned uv values based on where they are in space. This
leads to tiling of texture for large boxes, and truncating of textures for
small boxes.
For texture coordinates, this cube source fits the image to each face,
regardless of the size or aspect ratio of the face. It does support the ability
to scale those texture coordinates if tiling is desired or aspect ratios
should be tweaked. */
class DrakeCubeSource : public vtkPolyDataAlgorithm {
public:
/* This represents adherence to the vtk standard for writing a source. The
implementation is an explicit spelling of the vtkStandardNewMacro effect. */
static DrakeCubeSource* New() {
DrakeCubeSource* result = new DrakeCubeSource;
result->InitializeObjectBase();
return result;
}

/* More VTK boiler plate. */
vtkTypeMacro(DrakeCubeSource, vtkPolyDataAlgorithm);

/* VTK boilerplate to support printing the source. */
void PrintSelf(std::ostream& os, vtkIndent indent) override {
this->Superclass::PrintSelf(os, indent);
os << indent << "Size: " << size_.transpose() << "\n";
os << indent << "UV Scale: " << uv_scale_.transpose() << "\n";
}

/* Set the size of the box along each of its principal axes.
@pre Measures must all be positive. */
void set_size(const Vector3d& size) {
DRAKE_DEMAND((size.array() > 0).all());
size_ = size;
}

/* Set the scaling of the per-face uv coordinates. This can be used to adjust
aspect ratio of the rendered texture or introduce tiling. Negative values are
allowed and reverse the texture along the axes with the negative value. */
void set_uv_scale(const Vector2d& uv_scale) { uv_scale_ = uv_scale; }

protected:
DrakeCubeSource() : size_(1, 1, 1), uv_scale_(1, 1) {
this->SetNumberOfInputPorts(0);
}

~DrakeCubeSource() override {}

int RequestData(vtkInformation*, vtkInformationVector**,
vtkInformationVector* outputVector) override {
// Initializes and allocates the accumulators for the box data.
vtkPoints* newPoints = vtkPoints::New(VTK_DOUBLE);
vtkFloatArray* newNormals = vtkFloatArray::New();
vtkFloatArray* newTCoords = vtkFloatArray::New();
vtkCellArray* newPolys = vtkCellArray::New();

ScopeExit guard([newPoints, newNormals, newTCoords, newPolys](){
newPoints->Delete();
newNormals->Delete();
newTCoords->Delete();
newPolys->Delete();
});

const int num_polys = 6;
const int num_points = 24;
newPoints->Allocate(num_points);
newNormals->SetNumberOfComponents(3);
newNormals->Allocate(num_points);
newNormals->SetName("Normals");
newTCoords->SetNumberOfComponents(2);
newTCoords->Allocate(num_points);
newTCoords->SetName("TCoords");
// This estimate is exact because every polygon is a quad.
newPolys->Allocate(newPolys->EstimateSize(num_polys, 4));

/* Each face is defined w.r.t. a particular axis (e.g., +x, -x, +y, ...,
etc.,) Looking *down* the vector of that axis there is a Frame on which
we define the face.
Fy
^
v3 │ v2
┏━━━━━━┿━━━━━━┓
┃ │ ┃
┃ └──────╂─> Fx
┃ ┃
┗━━━━━━━━━━━━━┛
v0 v1
The texture coordinates for the vertices map the image directly:
- v0 -> (0, 0)
- v2 -> (1, 1), etc.
The box itself is defined in frame B. So, for each face (+x, -x, etc.)
there is a mapping from the bases of B to the bases of F.
face axis | Fx | Fy | map key
--------- | --- | --- | -------
+x | -By | Bz | 0
-x | By | Bz | 1
+y | -Bx | Bz | 2
-y | Bx | Bz | 3
+z | Bx | By | 4
-z | Bx | -By | 5
We encode the basis for each face in the table below as:
{Bi, si, Bj, sj, Bk, sk} such that:
Fx = si * Vector3d::Unit(Bi);
Fy = sj * Vector3d::Unit(Bj);
Fz = sk * Vector3d::Unit(Bk);
*/
constexpr int basis_F[6][6] = {{1, 1, 2, 1, 0, 1}, // +x face.
{1, -1, 2, 1, 0, -1}, // -x face.
{0, -1, 2, 1, 1, 1}, // +y face.
{0, 1, 2, 1, 1, -1}, // -y face.
{0, 1, 1, 1, 2, 1}, // +z face.
{0, 1, 1, -1, 2, -1}}; // -z face.
for (int face = 0; face < 6; ++face) {
// The indices of the basis of frame F.
const int fx = basis_F[face][0];
const int fy = basis_F[face][2];
const int fz = basis_F[face][4];
// The half sizes in the Frame F basis directions.
const double sx = 0.5 * this->size_[fx];
const double sy = 0.5 * this->size_[fy];
const double sz = 0.5 * this->size_[fz];
// The basis vectors in the box frame B.
const Vector3d Fx = basis_F[face][1] * Vector3d::Unit(fx);
const Vector3d Fy = basis_F[face][3] * Vector3d::Unit(fy);
const Vector3d Fz = basis_F[face][5] * Vector3d::Unit(fz);

// The face normal is always in the Fz direction.
const double normal_F[] = {Fz[0], Fz[1], Fz[2]};

// Position vector from Frame F's origin, to the center of the polygon.
const Vector3d p_FPc = sz * Fz;
// Coordinates of the "unit" faces. I.e., if the box were (2 x 2 x 2), it
// would have vertices at positions <±1, ±1, ±1>. We'll scale it based
// on the box dimensions.
std::vector<std::pair<double, double>> vertices = {{-1, -1}, // v0.
{1, -1}, // v1.
{1, 1}, // v2.
{-1, 1}}; // v3.
// The index of the first vertex we're about to add.
const vtkIdType first = newPoints->GetNumberOfPoints();
for (const auto [x, y] : vertices) {
const Vector3d p_FV = p_FPc + (x * sx) * Fx + (y * sy) * Fy;
newPoints->InsertNextPoint(p_FV[0], p_FV[1], p_FV[2]);
newNormals->InsertNextTuple(normal_F);
// Note: The texture coordinates are a simple affine transformation of
// the unit face coordinates. For vertex P in the unit face, its
// corresponding uv coordinate UV = s * (P + 1) / 2. In other words, we:
// - shift the square from (-1, -1)x(1, 1) to (0, 0)x(2, 2)
// - scale to (0, 0)x(1, 1)
// - scale again by the uv_scale to (0, 0)x(s, s).
const double uv[] = {(x + 1) * 0.5 * uv_scale_[0],
(y + 1) * 0.5 * uv_scale_[1]};
newTCoords->InsertNextTuple(uv);
}

const vtkIdType polygon[] = {first, first + 1, first + 2, first + 3};
newPolys->InsertNextCell(4, polygon);
}

// Populates the output with the compute data.
vtkInformation* out_info = outputVector->GetInformationObject(0);
vtkPolyData* output =
vtkPolyData::SafeDownCast(out_info->Get(vtkDataObject::DATA_OBJECT()));
output->SetPoints(newPoints);
output->GetPointData()->SetNormals(newNormals);
output->GetPointData()->SetTCoords(newTCoords);
output->SetPolys(newPolys);

return 1;
}

// The full measure of the box along its principal axes.
Vector3d size_;

// TODO(SeanCurtis-TRI): This would be better off as a uv _transform_ such
// that the texture can be scaled _and_ positioned.
// The scale factors to apply to the texture coordinates.
Vector2d uv_scale_;

private:
DrakeCubeSource(const DrakeCubeSource&) = delete;
void operator=(const DrakeCubeSource&) = delete;
};

} // namespace

vtkSmartPointer<vtkPolyDataAlgorithm> CreateVtkCapsule(const Capsule& capsule) {
using com_github_finetjul_bender::vtkCapsuleSource;

vtkNew<vtkCapsuleSource> vtk_capsule;
vtk_capsule->SetCylinderLength(capsule.length());
vtk_capsule->SetRadius(capsule.radius());
Expand All @@ -27,6 +249,17 @@ vtkSmartPointer<vtkPolyDataAlgorithm> CreateVtkCapsule(const Capsule& capsule) {
return transform_filter;
}

vtkSmartPointer<vtkPolyDataAlgorithm> CreateVtkBox(
const Box& box, const PerceptionProperties& properties) {
vtkSmartPointer<DrakeCubeSource> vtk_box =
vtkSmartPointer<DrakeCubeSource>::New();
vtk_box->set_size({box.width(), box.depth(), box.height()});
const Vector2d& uv_scale = properties.GetPropertyOrDefault(
"phong", "diffuse_scale", Vector2d{1, 1});
vtk_box->set_uv_scale(uv_scale);
return vtk_box;
}

vtkSmartPointer<vtkPolyDataAlgorithm> CreateVtkEllipsoid(
const Ellipsoid& ellipsoid) {
vtkNew<vtkTexturedSphereSource> vtk_ellipsoid;
Expand Down
7 changes: 7 additions & 0 deletions geometry/render/render_engine_vtk_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <vtkTransform.h>
#include <vtkTransformPolyDataFilter.h>

#include "drake/geometry/geometry_roles.h"
#include "drake/geometry/shape_specification.h"

namespace drake {
Expand All @@ -15,6 +16,12 @@ namespace render {
// Creates a z-axis aligned VTK capsule.
vtkSmartPointer<vtkPolyDataAlgorithm> CreateVtkCapsule(const Capsule& capsule);

// Creates a box with texture coordinates such that the image is stretched
// over each face. The texture can be optionally scaled/tiled via texture
// scale properties in the given properties.
vtkSmartPointer<vtkPolyDataAlgorithm> CreateVtkBox(
const Box& box, const PerceptionProperties& properties);

// Creates a VTK ellipsoid scaled from a sphere.
vtkSmartPointer<vtkPolyDataAlgorithm> CreateVtkEllipsoid(
const Ellipsoid& ellipsoid);
Expand Down
Binary file added geometry/render/test/diag_gradient.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading

0 comments on commit f5a7ad5

Please sign in to comment.