Skip to content

Commit

Permalink
Update RenderEngineVtk to use RenderMaterial
Browse files Browse the repository at this point in the history
RenderEngineVtk stops using vtkOBJReader and defers to RenderMesh and
RenderMaterial to get OBJ mesh data and appearance.

Behavior implications

While the "if foo.png exists for foo.obj, apply it" behavior isn't *gone*,
it *has* been supplanted in the case where foo.obj actually has a material
library (mtl). So, if models out there had let the mtl file rot when they
catered to Drake's former idiosyncracies, this will cause the appearance
to shift back towards the actual material specification.

Implementation details

  - The render engine is simply responsible for mapping those types to the
    VTK-specific representation.
  - internal_render_engine_vtk_base defines a new vtk polygon source based
    on the RenderMesh data. This is what replaces vtkOBJReader.
  - All non-mesh Shape types now use the RenderMaterial APIs to map from
    geometry properties to RenderMaterial.
  - The unit tests have simplified vis a vis meshes and textures. Now that
    it simply translates, we can rely on RenderMaterial tests to confirm
    the protocol logic and we just need to confirm RenderEngineVtk is
    exercising it and translating it correctly.
  - The RenderMesh -> vtkPolyData is capable of providing a more compact
    representation of the mesh than the vtkOBJReader (it created unique
    vertex data for each triangle). The gltf server code uses VTK to create
    gltf files. The reference gltf files used in the tests reflected the
    old, bloated mesh descriptions. They have been updated to the newer
    compact sizes.

Some incidental clean up:
 - Default diffuse color is properly stored as Rgba now.
 - Optimized the normal case of not scaling the texture.
 - Added note for clarity about the efficacy of the scaling factor; it
   seems to pass in test, but it isn't clear *why*. This needs further
   investigation.
  • Loading branch information
SeanCurtis-TRI committed May 10, 2023
1 parent 310a17c commit 6fab7a5
Show file tree
Hide file tree
Showing 11 changed files with 256 additions and 170 deletions.
17 changes: 11 additions & 6 deletions geometry/render/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -97,17 +97,22 @@ drake_cc_library(

# === test/ ===

genrule(
name = "box_no_mtl",
srcs = ["test/meshes/box.obj"],
outs = ["test/meshes/box_no_mtl.obj"],
cmd = "sed '/mtllib/d; /usemtl/d' $< > $@",
visibility = ["//visibility:private"],
)

filegroup(
name = "test_models",
testonly = 1,
srcs = [
srcs = [":box_no_mtl"] + glob([
"test/meshes/*",
"test/box.sdf",
"test/diag_gradient.png",
"test/meshes/box.obj",
"test/meshes/box.obj.mtl",
"test/meshes/box.png",
"test/meshes/box16u.png",
],
]),
)

drake_cc_googletest(
Expand Down
3 changes: 2 additions & 1 deletion geometry/render/render_material.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,8 @@ void MaybeWarnForRedundantMaterial(
if (props.HasProperty("phong", "diffuse")) {
ignored_props.push_back(fmt::format(
"('phong', 'diffuse') = {}",
fmt_eigen(props.GetProperty<Rgba>("phong", "diffuse").rgba())));
fmt_eigen(
props.GetProperty<Rgba>("phong", "diffuse").rgba().transpose())));
}
if (props.HasProperty("phong", "diffuse_map")) {
ignored_props.push_back(
Expand Down
12 changes: 6 additions & 6 deletions geometry/render_gltf_client/test/test_color_scene.gltf
Original file line number Diff line number Diff line change
Expand Up @@ -229,16 +229,16 @@
"bufferView" : 32,
"byteOffset" : 0,
"componentType" : 5126,
"count" : 49152,
"max" : [ 0.033259999006986618, 0.0098120002076029778, 0.18814800679683685 ],
"min" : [ -0.063937999308109283, -0.056809000670909882, -0.0031530000269412994 ],
"count" : 8423,
"max" : [ 0.033259999999999998, 0.0098119999999999995, 0.18814800000000001 ],
"min" : [ -0.063937999999999995, -0.056808999999999998, -0.003153 ],
"type" : "VEC3"
},
{
"bufferView" : 33,
"byteOffset" : 0,
"componentType" : 5126,
"count" : 49152,
"count" : 8423,
"normalized" : false,
"type" : "VEC2"
},
Expand Down Expand Up @@ -419,12 +419,12 @@
},
{
"buffer" : 32,
"byteLength" : 589824,
"byteLength" : 101076,
"byteOffset" : 0
},
{
"buffer" : 33,
"byteLength" : 393216,
"byteLength" : 67384,
"byteOffset" : 0
},
{
Expand Down
12 changes: 6 additions & 6 deletions geometry/render_gltf_client/test/test_depth_scene.gltf
Original file line number Diff line number Diff line change
Expand Up @@ -229,16 +229,16 @@
"bufferView" : 28,
"byteOffset" : 0,
"componentType" : 5126,
"count" : 49152,
"max" : [ 0.033259999006986618, 0.0098120002076029778, 0.18814800679683685 ],
"min" : [ -0.063937999308109283, -0.056809000670909882, -0.0031530000269412994 ],
"count" : 8423,
"max" : [ 0.033259999999999998, 0.0098119999999999995, 0.18814800000000001 ],
"min" : [ -0.063937999999999995, -0.056808999999999998, -0.003153 ],
"type" : "VEC3"
},
{
"bufferView" : 29,
"byteOffset" : 0,
"componentType" : 5126,
"count" : 49152,
"count" : 8423,
"normalized" : false,
"type" : "VEC2"
},
Expand Down Expand Up @@ -399,12 +399,12 @@
},
{
"buffer" : 28,
"byteLength" : 589824,
"byteLength" : 101076,
"byteOffset" : 0
},
{
"buffer" : 29,
"byteLength" : 393216,
"byteLength" : 67384,
"byteOffset" : 0
},
{
Expand Down
12 changes: 6 additions & 6 deletions geometry/render_gltf_client/test/test_label_scene.gltf
Original file line number Diff line number Diff line change
Expand Up @@ -229,16 +229,16 @@
"bufferView" : 28,
"byteOffset" : 0,
"componentType" : 5126,
"count" : 49152,
"max" : [ 0.033259999006986618, 0.0098120002076029778, 0.18814800679683685 ],
"min" : [ -0.063937999308109283, -0.056809000670909882, -0.0031530000269412994 ],
"count" : 8423,
"max" : [ 0.033259999999999998, 0.0098119999999999995, 0.18814800000000001 ],
"min" : [ -0.063937999999999995, -0.056808999999999998, -0.003153 ],
"type" : "VEC3"
},
{
"bufferView" : 29,
"byteOffset" : 0,
"componentType" : 5126,
"count" : 49152,
"count" : 8423,
"normalized" : false,
"type" : "VEC2"
},
Expand Down Expand Up @@ -399,12 +399,12 @@
},
{
"buffer" : 28,
"byteLength" : 589824,
"byteLength" : 101076,
"byteOffset" : 0
},
{
"buffer" : 29,
"byteLength" : 393216,
"byteLength" : 67384,
"byteOffset" : 0
},
{
Expand Down
2 changes: 2 additions & 0 deletions geometry/render_vtk/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,8 @@ drake_cc_library(
"//common:scope_exit",
"//geometry:geometry_roles",
"//geometry:shape_specification",
"//geometry/render:render_material",
"//geometry/render:render_mesh",
"@vtk//:vtkCommonCore",
"@vtk//:vtkFiltersSources",
],
Expand Down
121 changes: 58 additions & 63 deletions geometry/render_vtk/internal_render_engine_vtk.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
#include <vtkCamera.h>
#include <vtkCylinderSource.h>
#include <vtkImageCast.h>
#include <vtkOBJReader.h>
#include <vtkOpenGLPolyDataMapper.h>
#include <vtkOpenGLShaderProperty.h>
#include <vtkOpenGLTexture.h>
Expand All @@ -21,6 +20,7 @@
#include <vtkTransformPolyDataFilter.h>

#include "drake/common/text_logging.h"
#include "drake/geometry/render/render_mesh.h"
#include "drake/geometry/render/shaders/depth_shaders.h"
#include "drake/geometry/render_vtk/internal_render_engine_vtk_base.h"
#include "drake/geometry/render_vtk/internal_vtk_util.h"
Expand All @@ -33,6 +33,10 @@ namespace internal {

using Eigen::Vector2d;
using Eigen::Vector4d;
using geometry::internal::DefineMaterial;
using geometry::internal::LoadRenderMeshFromObj;
using geometry::internal::RenderMaterial;
using geometry::internal::RenderMesh;
using math::RigidTransformd;
using render::ColorRenderCamera;
using render::DepthRenderCamera;
Expand Down Expand Up @@ -83,18 +87,8 @@ struct RegistrationData {
const PerceptionProperties& properties;
const RigidTransformd& X_WG;
const GeometryId id;
// The file name if the shape being registered is a mesh.
std::optional<std::string> mesh_filename;
};

std::string RemoveFileExtension(const std::string& filepath) {
const size_t last_dot = filepath.find_last_of(".");
if (last_dot == std::string::npos) {
throw std::logic_error("File has no extension.");
}
return filepath.substr(0, last_dot);
}

} // namespace

ShaderCallback::ShaderCallback() :
Expand All @@ -112,7 +106,7 @@ RenderEngineVtk::RenderEngineVtk(const RenderEngineVtkParams& parameters)
make_unique<RenderingPipeline>(),
make_unique<RenderingPipeline>()}} {
if (parameters.default_diffuse) {
default_diffuse_ = *parameters.default_diffuse;
default_diffuse_.set(*parameters.default_diffuse);
}

const auto& c = parameters.default_clear_color;
Expand All @@ -133,12 +127,16 @@ void RenderEngineVtk::UpdateViewpoint(const RigidTransformd& X_WC) {
void RenderEngineVtk::ImplementGeometry(const Box& box, void* user_data) {
const RegistrationData* data = static_cast<RegistrationData*>(user_data);
ImplementGeometry(CreateVtkBox(box, data->properties).GetPointer(),
DefineMaterial(data->properties, default_diffuse_),
user_data);
}

void RenderEngineVtk::ImplementGeometry(const Capsule& capsule,
void* user_data) {
ImplementGeometry(CreateVtkCapsule(capsule).GetPointer(), user_data);
const RegistrationData* data = static_cast<RegistrationData*>(user_data);
ImplementGeometry(CreateVtkCapsule(capsule).GetPointer(),
DefineMaterial(data->properties, default_diffuse_),
user_data);
}

void RenderEngineVtk::ImplementGeometry(const Convex& convex, void* user_data) {
Expand All @@ -156,19 +154,28 @@ void RenderEngineVtk::ImplementGeometry(const Cylinder& cylinder,
vtkNew<vtkTransformPolyDataFilter> transform_filter;
TransformToDrakeCylinder(transform, transform_filter, vtk_cylinder);

ImplementGeometry(transform_filter.GetPointer(), user_data);
const RegistrationData* data = static_cast<RegistrationData*>(user_data);
ImplementGeometry(transform_filter.GetPointer(),
DefineMaterial(data->properties, default_diffuse_),
user_data);
}

void RenderEngineVtk::ImplementGeometry(const Ellipsoid& ellipsoid,
void* user_data) {
ImplementGeometry(CreateVtkEllipsoid(ellipsoid).GetPointer(), user_data);
const RegistrationData* data = static_cast<RegistrationData*>(user_data);
ImplementGeometry(CreateVtkEllipsoid(ellipsoid).GetPointer(),
DefineMaterial(data->properties, default_diffuse_),
user_data);
}

void RenderEngineVtk::ImplementGeometry(const HalfSpace&,
void* user_data) {
vtkSmartPointer<vtkPlaneSource> vtk_plane = CreateSquarePlane(kTerrainSize);

ImplementGeometry(vtk_plane.GetPointer(), user_data);
const RegistrationData* data = static_cast<RegistrationData*>(user_data);
ImplementGeometry(vtk_plane.GetPointer(),
DefineMaterial(data->properties, default_diffuse_),
user_data);
}

void RenderEngineVtk::ImplementGeometry(const Mesh& mesh, void* user_data) {
Expand All @@ -178,7 +185,10 @@ void RenderEngineVtk::ImplementGeometry(const Mesh& mesh, void* user_data) {
void RenderEngineVtk::ImplementGeometry(const Sphere& sphere, void* user_data) {
vtkNew<vtkTexturedSphereSource> vtk_sphere;
SetSphereOptions(vtk_sphere.GetPointer(), sphere.radius());
ImplementGeometry(vtk_sphere.GetPointer(), user_data);
const RegistrationData* data = static_cast<RegistrationData*>(user_data);
ImplementGeometry(vtk_sphere.GetPointer(),
DefineMaterial(data->properties, default_diffuse_),
user_data);
}

bool RenderEngineVtk::DoRegisterVisual(
Expand Down Expand Up @@ -443,24 +453,34 @@ void RenderEngineVtk::InitializePipelines() {

void RenderEngineVtk::ImplementObj(const std::string& file_name, double scale,
void* user_data) {
static_cast<RegistrationData*>(user_data)->mesh_filename = file_name;
vtkNew<vtkOBJReader> mesh_reader;
mesh_reader->SetFileName(file_name.c_str());
mesh_reader->Update();
auto* data = static_cast<RegistrationData*>(user_data);

RenderMesh mesh_data =
LoadRenderMeshFromObj(file_name, data->properties, default_diffuse_,
drake::internal::DiagnosticPolicy());
const RenderMaterial material = mesh_data.material;

vtkSmartPointer<vtkPolyDataAlgorithm> mesh_source =
CreateVtkMesh(std::move(mesh_data));

if (scale == 1) {
ImplementGeometry(mesh_source.GetPointer(), material, user_data);
return;
}

vtkNew<vtkTransform> transform;
// TODO(SeanCurtis-TRI): Should I be allowing only isotropic scale.
// TODO(SeanCurtis-TRI): Only add the transform filter if scale is not all 1.
transform->Scale(scale, scale, scale);
vtkNew<vtkTransformPolyDataFilter> transform_filter;
transform_filter->SetInputConnection(mesh_reader->GetOutputPort());
transform_filter->SetInputConnection(mesh_source->GetOutputPort());
transform_filter->SetTransform(transform.GetPointer());
transform_filter->Update();

ImplementGeometry(transform_filter.GetPointer(), user_data);
ImplementGeometry(transform_filter.GetPointer(), material, user_data);
}

void RenderEngineVtk::ImplementGeometry(vtkPolyDataAlgorithm* source,
const RenderMaterial& material,
void* user_data) {
DRAKE_DEMAND(user_data != nullptr);

Expand Down Expand Up @@ -513,41 +533,16 @@ void RenderEngineVtk::ImplementGeometry(vtkPolyDataAlgorithm* source,

// Color actor.
auto& color_actor = actors[ImageType::kColor];
const std::string& diffuse_map_name =
data.properties.GetPropertyOrDefault<std::string>("phong", "diffuse_map",
"");
// Legacy support for *implied* texture maps. If we have mesh.obj, we look for
// mesh.png (unless one has been specifically called out in the properties).
// TODO(SeanCurtis-TRI): Remove this legacy texture when objects and materials
// are coherently specified by SDF/URDF/obj/mtl, etc.
std::string texture_name;
std::ifstream file_exist(diffuse_map_name);
if (file_exist) {
texture_name = diffuse_map_name;
} else {
if (!diffuse_map_name.empty()) {
log()->warn("Requested diffuse map could not be found: {}",
diffuse_map_name);
}
if (diffuse_map_name.empty() && data.mesh_filename) {
// This is the hack to search for mesh.png as a possible texture.
const std::string alt_texture_name(
RemoveFileExtension(*data.mesh_filename) + ".png");
std::ifstream alt_file_exist(alt_texture_name);
if (alt_file_exist) texture_name = alt_texture_name;
}
}
if (!texture_name.empty()) {
const Vector2d& uv_scale = data.properties.GetPropertyOrDefault(
"phong", "diffuse_scale", Vector2d{1, 1});

if (!material.diffuse_map.empty()) {
vtkNew<vtkPNGReader> texture_reader;
texture_reader->SetFileName(texture_name.c_str());
texture_reader->SetFileName(material.diffuse_map.c_str());
texture_reader->Update();
if (texture_reader->GetOutput()->GetScalarType() != VTK_UNSIGNED_CHAR) {
log()->warn(
"Texture map '{}' has an unsupported bit depth, casting it to uchar "
"channels.",
texture_name);
material.diffuse_map);
}

vtkNew<vtkImageCast> caster;
Expand All @@ -558,21 +553,21 @@ void RenderEngineVtk::ImplementGeometry(vtkPolyDataAlgorithm* source,

vtkNew<vtkOpenGLTexture> texture;
texture->SetInputConnection(caster->GetOutputPort());
// TODO(SeanCurtis-TRI): It doesn't seem like the scale is used to actually
// *scale* the image.
const Vector2d uv_scale = data.properties.GetPropertyOrDefault(
"phong", "diffuse_scale", Vector2d{1, 1});
const bool need_repeat = uv_scale[0] > 1 || uv_scale[1] > 1;
texture->SetRepeat(need_repeat);
texture->InterpolateOn();
color_actor->SetTexture(texture.Get());
} else {
const Vector4d& diffuse =
data.properties.GetPropertyOrDefault("phong", "diffuse",
default_diffuse_);
color_actor->GetProperty()->SetColor(diffuse(0), diffuse(1), diffuse(2));
color_actor->GetProperty()->SetOpacity(diffuse(3));
}
// TODO(SeanCurtis-TRI): Determine if this precludes modulating the texture
// with arbitrary rgba values (e.g., tinting red or making everything
// slightly transparent). In other words, should opacity be set regardless
// of whether a texture exists?

// Note: This allows the color map to be modulated by an arbitrary diffuse
// color and opacity.
const auto& diffuse = material.diffuse;
color_actor->GetProperty()->SetColor(diffuse.r(), diffuse.g(), diffuse.b());
color_actor->GetProperty()->SetOpacity(diffuse.a());

connect_actor(ImageType::kColor);

Expand Down

0 comments on commit 6fab7a5

Please sign in to comment.