Skip to content

Commit

Permalink
[render] Fully account for full camera intrinsics in RenderEngine eco…
Browse files Browse the repository at this point in the history
…system (RobotLocomotion#14357)

* Fully account for full camera intrinsics in RenderEngine ecosystem

This revisits the implementation of RenderEngine in preparation for
deprecating the old CameraProperties and DepthCameraProperties in favor of
the new ColorRenderCamera and DepthRenderCamera.

 - We implement the CameraProperties RenderEngine API by delegating to the
   RenderCamera API (it was previously purely abstract).
    - This introduces circular delegation in the default behavior and we
      add a *temporary* mechanism for catching the defective case where
      the circle gets entered.
    - A collection of tests have been added to validate all transitional
      delegation logic.
 - RenderEngineGl, RenderEngineVtk, DummyRenderEngine remove their
   CameraProperties-related APIs in favor of inheriting RenderEngine's.
   - Tests that compare equivalency between images created by the two APIs
     on the derived classes are no longer necessary.
 - Bind QueryObject::Render*Image(*RenderCamera) API
 - the python version of DummyRenderEngine (in geometry_test.py) is updated
   to match the C++ version.
  • Loading branch information
SeanCurtis-TRI authored Nov 18, 2020
1 parent 3ac311c commit 4742497
Show file tree
Hide file tree
Showing 12 changed files with 507 additions and 474 deletions.
40 changes: 38 additions & 2 deletions bindings/pydrake/geometry_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -812,6 +812,18 @@ void DoScalarDependentDefinitions(py::module m, T) {
},
py::arg("camera"), py::arg("parent_frame"), py::arg("X_PC"),
py::arg("show_window") = false, cls_doc.RenderColorImage.doc)
.def(
"RenderColorImage",
[](const Class* self, const render::ColorRenderCamera& camera,
FrameId parent_frame, const math::RigidTransformd& X_PC) {
systems::sensors::ImageRgba8U img(
camera.core().intrinsics().width(),
camera.core().intrinsics().height());
self->RenderColorImage(camera, parent_frame, X_PC, &img);
return img;
},
py::arg("camera"), py::arg("parent_frame"), py::arg("X_PC"),
cls_doc.RenderColorImage.doc)
.def(
"RenderDepthImage",
[](const Class* self, const render::DepthCameraProperties& camera,
Expand All @@ -822,6 +834,18 @@ void DoScalarDependentDefinitions(py::module m, T) {
},
py::arg("camera"), py::arg("parent_frame"), py::arg("X_PC"),
cls_doc.RenderDepthImage.doc)
.def(
"RenderDepthImage",
[](const Class* self, const render::DepthRenderCamera& camera,
FrameId parent_frame, const math::RigidTransformd& X_PC) {
systems::sensors::ImageDepth32F img(
camera.core().intrinsics().width(),
camera.core().intrinsics().height());
self->RenderDepthImage(camera, parent_frame, X_PC, &img);
return img;
},
py::arg("camera"), py::arg("parent_frame"), py::arg("X_PC"),
cls_doc.RenderDepthImage.doc)
.def(
"RenderLabelImage",
[](const Class* self, const render::CameraProperties& camera,
Expand All @@ -833,7 +857,19 @@ void DoScalarDependentDefinitions(py::module m, T) {
return img;
},
py::arg("camera"), py::arg("parent_frame"), py::arg("X_PC"),
py::arg("show_window") = false, cls_doc.RenderLabelImage.doc);
py::arg("show_window") = false, cls_doc.RenderLabelImage.doc)
.def(
"RenderLabelImage",
[](const Class* self, const render::ColorRenderCamera& camera,
FrameId parent_frame, const math::RigidTransformd& X_PC) {
systems::sensors::ImageLabel16I img(
camera.core().intrinsics().width(),
camera.core().intrinsics().height());
self->RenderLabelImage(camera, parent_frame, X_PC, &img);
return img;
},
py::arg("camera"), py::arg("parent_frame"), py::arg("X_PC"),
cls_doc.RenderLabelImage.doc);

AddValueInstantiation<QueryObject<T>>(m);
}
Expand Down Expand Up @@ -940,7 +976,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
.def("id_N", &Class::id_N, doc.ContactSurface.id_N.doc)
.def("mesh_W", &Class::mesh_W, doc.ContactSurface.mesh_W.doc);
}
}
} // NOLINT(readability/fn_size)

void DoScalarIndependentDefinitions(py::module m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
Expand Down
89 changes: 54 additions & 35 deletions bindings/pydrake/test/geometry_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -718,19 +718,38 @@ def test_query_object(self, T):
id_B=mut.GeometryId.get_new_id())

# Confirm rendering API returns images of appropriate type.
d_camera = mut.render.DepthCameraProperties(
camera_core = mut.render.RenderCameraCore(
renderer_name, CameraInfo(width=10, height=10, fov_y=pi/6),
mut.render.ClippingRange(0.1, 10.0), RigidTransform())
color_camera = mut.render.ColorRenderCamera(camera_core, False)
depth_camera = mut.render.DepthRenderCamera(
camera_core, mut.render.DepthRange(0.1, 5.0))
image = query_object.RenderColorImage(
camera=color_camera, parent_frame=SceneGraph.world_frame_id(),
X_PC=RigidTransform())
self.assertIsInstance(image, ImageRgba8U)
image = query_object.RenderDepthImage(
camera=depth_camera, parent_frame=SceneGraph.world_frame_id(),
X_PC=RigidTransform())
self.assertIsInstance(image, ImageDepth32F)
image = query_object.RenderLabelImage(
camera=color_camera, parent_frame=SceneGraph.world_frame_id(),
X_PC=RigidTransform())
self.assertIsInstance(image, ImageLabel16I)

depth_camera = mut.render.DepthCameraProperties(
width=320, height=240, fov_y=pi/6, renderer_name=renderer_name,
z_near=0.1, z_far=5.0)
image = query_object.RenderColorImage(
camera=d_camera, parent_frame=SceneGraph.world_frame_id(),
camera=depth_camera, parent_frame=SceneGraph.world_frame_id(),
X_PC=RigidTransform())
self.assertIsInstance(image, ImageRgba8U)
image = query_object.RenderDepthImage(
camera=d_camera, parent_frame=SceneGraph.world_frame_id(),
camera=depth_camera, parent_frame=SceneGraph.world_frame_id(),
X_PC=RigidTransform())
self.assertIsInstance(image, ImageDepth32F)
image = query_object.RenderLabelImage(
camera=d_camera, parent_frame=SceneGraph.world_frame_id(),
camera=depth_camera, parent_frame=SceneGraph.world_frame_id(),
X_PC=RigidTransform())
self.assertIsInstance(image, ImageLabel16I)

Expand Down Expand Up @@ -852,32 +871,17 @@ def __init__(self, render_label=None):
self.updated_ids = {}
self.include_group_name = "in_test"
self.X_WC = RigidTransform_[float]()
self.simple_color_count = 0
self.simple_depth_count = 0
self.simple_label_count = 0
self.color_props = None
self.depth_props = None
self.label_props = None
self.color_count = 0
self.depth_count = 0
self.label_count = 0
self.color_camera = None
self.depth_camera = None
self.label_camera = None

def UpdateViewpoint(self, X_WC):
DummyRenderEngine.latest_instance = self
self.X_WC = X_WC

def DoRenderColorImage(self, camera, color_image_out):
DummyRenderEngine.latest_instance = self
self.simple_color_count += 1
self.color_props = camera

def DoRenderDepthImage(self, camera, depth_image_out):
DummyRenderEngine.latest_instance = self
self.simple_depth_count += 1
self.depth_props = camera

def DoRenderLabelImage(self, camera, label_image_out):
DummyRenderEngine.latest_instance = self
self.simple_label_count += 1
self.label_props = camera

def ImplementGeometry(self, shape, user_data):
DummyRenderEngine.latest_instance = self

Expand Down Expand Up @@ -908,14 +912,29 @@ def DoClone(self):
new.updated_ids = copy.copy(self.updated_ids)
new.include_group_name = copy.copy(self.include_group_name)
new.X_WC = copy.copy(self.X_WC)
new.simple_color_count = copy.copy(self.simple_color_count)
new.simple_depth_count = copy.copy(self.simple_depth_count)
new.simple_label_count = copy.copy(self.simple_label_count)
new.color_props = copy.copy(self.color_props)
new.depth_props = copy.copy(self.depth_props)
new.label_props = copy.copy(self.label_props)
new.color_count = copy.copy(self.color_count)
new.depth_count = copy.copy(self.depth_count)
new.label_count = copy.copy(self.label_count)
new.color_camera = copy.copy(self.color_camera)
new.depth_camera = copy.copy(self.depth_camera)
new.label_camera = copy.copy(self.label_camera)
return new

def DoRenderColorImage(self, camera, color_image_out):
DummyRenderEngine.latest_instance = self
self.color_count += 1
self.color_camera = camera

def DoRenderDepthImage(self, camera, depth_image_out):
DummyRenderEngine.latest_instance = self
self.depth_count += 1
self.depth_camera = camera

def DoRenderLabelImage(self, camera, label_image_out):
DummyRenderEngine.latest_instance = self
self.label_count += 1
self.label_camera = camera

engine = DummyRenderEngine()
self.assertIsInstance(engine, mut.render.RenderEngine)
self.assertIsInstance(engine.Clone(), DummyRenderEngine)
Expand Down Expand Up @@ -950,19 +969,19 @@ def DoClone(self):
current_engine = DummyRenderEngine.latest_instance
self.assertIsNot(current_engine, engine)
self.assertIsInstance(image, ImageRgba8U)
self.assertEqual(current_engine.simple_color_count, 1)
self.assertEqual(current_engine.color_count, 1)

image = sensor.depth_image_32F_output_port().Eval(sensor_context)
self.assertIsInstance(image, ImageDepth32F)
self.assertEqual(current_engine.simple_depth_count, 1)
self.assertEqual(current_engine.depth_count, 1)

image = sensor.depth_image_16U_output_port().Eval(sensor_context)
self.assertIsInstance(image, ImageDepth16U)
self.assertEqual(current_engine.simple_depth_count, 2)
self.assertEqual(current_engine.depth_count, 2)

image = sensor.label_image_output_port().Eval(sensor_context)
self.assertIsInstance(image, ImageLabel16I)
self.assertEqual(current_engine.simple_label_count, 1)
self.assertEqual(current_engine.label_count, 1)

# Confirm that the CameraProperties APIs are *not* available.
cam = mut.render.CameraProperties(10, 10, np.pi / 4, "")
Expand Down
23 changes: 0 additions & 23 deletions geometry/render/gl_renderer/render_engine_gl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -483,29 +483,6 @@ void RenderEngineGl::UpdateViewpoint(const RigidTransformd& X_WR) {
X_CW_ = X_WR.inverse();
}

void RenderEngineGl::RenderColorImage(const CameraProperties& camera,
bool show_window,
ImageRgba8U* color_image_out) const {
const ColorRenderCamera cam(camera, show_window);
ThrowIfInvalid(cam.core().intrinsics(), color_image_out, "color");
DoRenderColorImage(ColorRenderCamera(camera, show_window), color_image_out);
}

void RenderEngineGl::RenderDepthImage(const DepthCameraProperties& camera,
ImageDepth32F* depth_image_out) const {
DepthRenderCamera cam(camera);
ThrowIfInvalid(cam.core().intrinsics(), depth_image_out, "depth");
DoRenderDepthImage(cam, depth_image_out);
}

void RenderEngineGl::RenderLabelImage(const CameraProperties& camera,
bool show_window,
ImageLabel16I* label_image_out) const {
const ColorRenderCamera cam(camera, show_window);
ThrowIfInvalid(cam.core().intrinsics(), label_image_out, "label");
DoRenderLabelImage(ColorRenderCamera(camera, show_window), label_image_out);
}

void RenderEngineGl::ImplementGeometry(const Sphere& sphere, void* user_data) {
OpenGlGeometry geometry = GetSphere();
const double r = sphere.radius();
Expand Down
29 changes: 0 additions & 29 deletions geometry/render/gl_renderer/render_engine_gl.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,35 +50,6 @@ class RenderEngineGl final : public RenderEngine {
/** @see RenderEngine::UpdateViewpoint(). */
void UpdateViewpoint(const math::RigidTransformd& X_WR) final;

using RenderEngine::RenderColorImage;
using RenderEngine::RenderDepthImage;
using RenderEngine::RenderLabelImage;

/** @see RenderEngine::RenderColorImage(). Currently unimplemented. Calling
this will throw an exception.
Note that the display window triggered by `show_window` is shared with
RenderLabelImage(), and only the last color or label image rendered will be
visible in the window (once these methods are implemented). */
void RenderColorImage(
const CameraProperties& camera, bool show_window,
systems::sensors::ImageRgba8U* color_image_out) const final;

/** @see RenderEngine::RenderDepthImage(). */
void RenderDepthImage(
const DepthCameraProperties& camera,
systems::sensors::ImageDepth32F* depth_image_out) const final;

/** @see RenderEngine::RenderLabelImage(). Currently unimplemented. Calling
this will throw an exception.
Note that the display window triggered by `show_window` is shared with
RenderColorImage(), and only the last color or label image rendered will be
visible in the window (once these methods are implemented). */
void RenderLabelImage(
const CameraProperties& camera, bool show_window,
systems::sensors::ImageLabel16I* label_image_out) const final;

const RenderEngineGlParams& parameters() const { return parameters_; }

/** @name Shape reification */
Expand Down
41 changes: 0 additions & 41 deletions geometry/render/gl_renderer/test/render_engine_gl_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1482,47 +1482,6 @@ TEST_F(RenderEngineGlTest, MeshGeometryReuse) {
second_geometry.index_buffer_size);
}

// A reality check that confirms that the conversion from CameraProperties
// to intrinsics is as expected -- they produce equivalent images.
TEST_F(RenderEngineGlTest, CameraPropertiesVsCameraIntrinsics) {
Init(X_WR_, true /* add_terrain */);
PopulateSimpleBoxTest(renderer_.get());

// We're going to render some baseline images using the CameraProperties.
ImageRgba8U ref_color(camera_.width, camera_.height);
ImageDepth32F ref_depth(camera_.width, camera_.height);
ImageLabel16I ref_label(camera_.width, camera_.height);
Render(renderer_.get(), &camera_, &ref_color, &ref_depth, &ref_label);

// Instantiating camear models with the same data as in DepthCameraProperties
// should produce the *same* images.
const CameraInfo intrinsics{camera_.width, camera_.height, camera_.fov_y};
const ColorRenderCamera color_camera{camera_, kShowWindow};
const DepthRenderCamera depth_camera{camera_};

ImageRgba8U equiv_color(camera_.width, camera_.height);
ImageDepth32F equiv_depth(camera_.width, camera_.height);
ImageLabel16I equiv_label(camera_.width, camera_.height);
renderer_->RenderColorImage(color_camera, &equiv_color);
renderer_->RenderDepthImage(depth_camera, &equiv_depth);
renderer_->RenderLabelImage(color_camera, &equiv_label);

// The color and label images should be *bit* identical.
EXPECT_EQ(memcmp(ref_color.at(0, 0), equiv_color.at(0, 0), ref_color.size()),
0);

EXPECT_EQ(memcmp(ref_label.at(0, 0), equiv_label.at(0, 0), ref_label.size()),
0);
// The depth values take a slightly more numerically complex path and can
// lead to small rounding errors that the color channels are less
// susceptible to. To show the images are equal, we need to compare with
// tolerance.
for (int d = 0; d < ref_depth.size(); ++d) {
ASSERT_NEAR(ref_depth.at(0, 0)[d], equiv_depth.at(0, 0)[d],
4 * std::numeric_limits<float>::epsilon());
}
}

namespace {

// Defines the relationship between two adjacent pixels in a rendering of a box.
Expand Down
Loading

0 comments on commit 4742497

Please sign in to comment.