Skip to content

Commit

Permalink
sensors: Deprecate InvalidDepth and Label constants (RobotLocomotion#…
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored May 10, 2021
1 parent 76ca1de commit 9c56baa
Show file tree
Hide file tree
Showing 7 changed files with 62 additions and 39 deletions.
8 changes: 6 additions & 2 deletions bindings/pydrake/systems/sensors_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -167,14 +167,18 @@ PYBIND11_MODULE(sensors, m) {
type_visit(instantiation_visitor, PixelTypeList{});
}

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// Constants.
py::class_<InvalidDepth> invalid_depth(m, "InvalidDepth");
py::class_<InvalidDepth> invalid_depth(
m, "InvalidDepth", doc.InvalidDepth.doc_deprecated);
invalid_depth.attr("kTooFar") = InvalidDepth::kTooFar;
invalid_depth.attr("kTooClose") = InvalidDepth::kTooClose;

py::class_<Label> label(m, "Label");
py::class_<Label> label(m, "Label", doc.Label.doc_deprecated);
label.attr("kNoBody") = Label::kNoBody;
label.attr("kFlatTerrain") = Label::kFlatTerrain;
#pragma GCC diagnostic pop

using T = double;

Expand Down
5 changes: 3 additions & 2 deletions geometry/render/gl_renderer/render_engine_gl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@ using systems::sensors::ColorI;
using systems::sensors::ImageDepth32F;
using systems::sensors::ImageLabel16I;
using systems::sensors::ImageRgba8U;
using systems::sensors::InvalidDepth;
using systems::sensors::ImageTraits;
using systems::sensors::PixelType;

namespace {

Expand Down Expand Up @@ -736,7 +737,7 @@ void RenderEngineGl::DoRenderDepthImage(const DepthRenderCamera& camera,
// pixel value if nothing draws there -- i.e., nothing there implies that
// whatever *might* be there is "too far" beyond the depth range.
glClearNamedFramebufferfv(render_target.frame_buffer, GL_COLOR, 0,
&InvalidDepth::kTooFar);
&ImageTraits<PixelType::kDepth32F>::kTooFar);
glClear(GL_DEPTH_BUFFER_BIT);

// Matrix mapping a geometry vertex from the camera frame C to the device
Expand Down
33 changes: 20 additions & 13 deletions geometry/render/gl_renderer/test/render_engine_gl_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ using systems::sensors::ColorI;
using systems::sensors::ImageDepth32F;
using systems::sensors::ImageLabel16I;
using systems::sensors::ImageRgba8U;
using systems::sensors::InvalidDepth;
using systems::sensors::ImageTraits;
using systems::sensors::PixelType;

// Default camera properties.
const int kWidth = 640;
Expand Down Expand Up @@ -537,7 +538,7 @@ TEST_F(RenderEngineGlTest, TerrainTest) {
renderer_->UpdateViewpoint(X_WR_);
Render();
SCOPED_TRACE("TerrainTest: ground closer than z-near");
VerifyUniformDepth(InvalidDepth::kTooClose);
VerifyUniformDepth(ImageTraits<PixelType::kDepth32F>::kTooClose);
VerifyUniformLabel(RenderLabel::kDontCare);
}
{
Expand All @@ -547,7 +548,7 @@ TEST_F(RenderEngineGlTest, TerrainTest) {
renderer_->UpdateViewpoint(X_WR_);
Render();
SCOPED_TRACE("TerrainTest: ground farther than z-far");
VerifyUniformDepth(InvalidDepth::kTooFar);
VerifyUniformDepth(ImageTraits<PixelType::kDepth32F>::kTooFar);
VerifyUniformLabel(RenderLabel::kDontCare);
}
}
Expand Down Expand Up @@ -1791,10 +1792,12 @@ TEST_F(RenderEngineGlTest, IntrinsicsAndRenderProperties) {
renderer_->RenderDepthImage(depth_camera, &depth);

// Confirm pixel in corner (ground) and pixel in center (box).
EXPECT_TRUE(IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
InvalidDepth::kTooClose, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0}, InvalidDepth::kTooFar, 0.0));
IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
ImageTraits<PixelType::kDepth32F>::kTooClose, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0},
ImageTraits<PixelType::kDepth32F>::kTooFar, 0.0));
}

{
Expand All @@ -1808,10 +1811,12 @@ TEST_F(RenderEngineGlTest, IntrinsicsAndRenderProperties) {
renderer_->RenderDepthImage(depth_camera, &depth);

// Confirm pixel in corner (ground) and pixel in center (box).
EXPECT_TRUE(IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
InvalidDepth::kTooFar, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0}, InvalidDepth::kTooFar, 0.0));
IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
ImageTraits<PixelType::kDepth32F>::kTooFar, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0},
ImageTraits<PixelType::kDepth32F>::kTooFar, 0.0));
}

{
Expand All @@ -1828,10 +1833,12 @@ TEST_F(RenderEngineGlTest, IntrinsicsAndRenderProperties) {
renderer_->RenderDepthImage(depth_camera, &depth);

// Confirm pixel in corner (ground) and pixel in center (box).
EXPECT_TRUE(IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
InvalidDepth::kTooClose, 0.0));
EXPECT_TRUE(IsExpectedDepth(depth, ScreenCoord{0, 0},
InvalidDepth::kTooClose, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
ImageTraits<PixelType::kDepth32F>::kTooClose, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0},
ImageTraits<PixelType::kDepth32F>::kTooClose, 0.0));
}
}

Expand Down
10 changes: 6 additions & 4 deletions geometry/render/render_engine_vtk.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ using systems::sensors::ColorI;
using systems::sensors::ImageDepth32F;
using systems::sensors::ImageLabel16I;
using systems::sensors::ImageRgba8U;
using systems::sensors::InvalidDepth;
using systems::sensors::ImageTraits;
using systems::sensors::PixelType;
using vtk_util::ConvertToVtkTransform;
using vtk_util::CreateSquarePlane;
using vtk_util::MakeVtkPointerArray;
Expand Down Expand Up @@ -66,8 +67,8 @@ float CheckRangeAndConvertToMeters(float z_buffer_value, double z_near,
// inside the image itself. This includes sentinel values:
// - The value 1 indicates the depth is too far away.
// - The value 0 indicates the depth is too near.
if (z_buffer_value == 0) return InvalidDepth::kTooClose;
if (z_buffer_value == 1) return InvalidDepth::kTooFar;
if (z_buffer_value == 0) return ImageTraits<PixelType::kDepth32F>::kTooClose;
if (z_buffer_value == 1) return ImageTraits<PixelType::kDepth32F>::kTooFar;
return static_cast<float>(z_buffer_value * (z_far - z_near) + z_near);
}

Expand Down Expand Up @@ -259,7 +260,8 @@ void RenderEngineVtk::DoRenderDepthImage(
for (int u = 0; u < intrinsics.width(); ++u) {
if (image.at(u, v)[0] == 255u && image.at(u, v)[1] == 255u &&
image.at(u, v)[2] == 255u) {
depth_image_out->at(u, v)[0] = InvalidDepth::kTooFar;
depth_image_out->at(u, v)[0] =
ImageTraits<PixelType::kDepth32F>::kTooFar;
} else {
// Decoding three channel color values to a float value. For the detail,
// see depth_shaders.h.
Expand Down
33 changes: 20 additions & 13 deletions geometry/render/test/render_engine_vtk_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,8 @@ using systems::sensors::ColorI;
using systems::sensors::ImageDepth32F;
using systems::sensors::ImageLabel16I;
using systems::sensors::ImageRgba8U;
using systems::sensors::InvalidDepth;
using systems::sensors::ImageTraits;
using systems::sensors::PixelType;

// Default camera properties.
const int kWidth = 640;
Expand Down Expand Up @@ -533,7 +534,7 @@ TEST_F(RenderEngineVtkTest, TerrainTest) {
SCOPED_TRACE("Closer than near");
VerifyUniformColor(kTerrainColorI, 255u);
VerifyUniformLabel(RenderLabel::kDontCare);
VerifyUniformDepth(InvalidDepth::kTooClose);
VerifyUniformDepth(ImageTraits<PixelType::kDepth32F>::kTooClose);

// Farther than kZFar.
X_WC_.set_translation({p_WR(0), p_WR(1), kZFar + 1e-3});
Expand All @@ -542,7 +543,7 @@ TEST_F(RenderEngineVtkTest, TerrainTest) {
SCOPED_TRACE("Farther than far");
VerifyUniformColor(kTerrainColorI, 255u);
VerifyUniformLabel(RenderLabel::kDontCare);
VerifyUniformDepth(InvalidDepth::kTooFar);
VerifyUniformDepth(ImageTraits<PixelType::kDepth32F>::kTooFar);
}

// Creates a terrain and then positions the camera such that a horizon between
Expand Down Expand Up @@ -1592,10 +1593,12 @@ TEST_F(RenderEngineVtkTest, IntrinsicsAndRenderProperties) {
renderer_->RenderDepthImage(depth_camera, &depth);

// Confirm pixel in corner (ground) and pixel in center (box).
EXPECT_TRUE(IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
InvalidDepth::kTooClose, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0}, InvalidDepth::kTooFar, 0.0));
IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
ImageTraits<PixelType::kDepth32F>::kTooClose, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0},
ImageTraits<PixelType::kDepth32F>::kTooFar, 0.0));
}

{
Expand All @@ -1609,10 +1612,12 @@ TEST_F(RenderEngineVtkTest, IntrinsicsAndRenderProperties) {
renderer_->RenderDepthImage(depth_camera, &depth);

// Confirm pixel in corner (ground) and pixel in center (box).
EXPECT_TRUE(IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
InvalidDepth::kTooFar, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0}, InvalidDepth::kTooFar, 0.0));
IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
ImageTraits<PixelType::kDepth32F>::kTooFar, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0},
ImageTraits<PixelType::kDepth32F>::kTooFar, 0.0));
}

{
Expand All @@ -1629,10 +1634,12 @@ TEST_F(RenderEngineVtkTest, IntrinsicsAndRenderProperties) {
renderer_->RenderDepthImage(depth_camera, &depth);

// Confirm pixel in corner (ground) and pixel in center (box).
EXPECT_TRUE(IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
InvalidDepth::kTooClose, 0.0));
EXPECT_TRUE(IsExpectedDepth(depth, ScreenCoord{0, 0},
InvalidDepth::kTooClose, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{w / 2, h / 2},
ImageTraits<PixelType::kDepth32F>::kTooClose, 0.0));
EXPECT_TRUE(
IsExpectedDepth(depth, ScreenCoord{0, 0},
ImageTraits<PixelType::kDepth32F>::kTooClose, 0.0));
}
}

Expand Down
1 change: 0 additions & 1 deletion perception/depth_image_to_point_cloud.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ using drake::systems::sensors::ImageDepth16U;
using drake::systems::sensors::ImageDepth32F;
using drake::systems::sensors::ImageRgba8U;
using drake::systems::sensors::ImageTraits;
using drake::systems::sensors::InvalidDepth;
using drake::systems::sensors::PixelType;

namespace drake {
Expand Down
11 changes: 7 additions & 4 deletions systems/sensors/image.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/common/reset_after_move.h"
#include "drake/systems/sensors/pixel_types.h"

Expand Down Expand Up @@ -155,12 +156,12 @@ class Image {
std::vector<T> data_;
};

// TODO(jwnimmer-tri) Deprecate these float-only constants; code should be
// using ImageTraits exclusively (i.e., based on the pixel type).
/// Set of constants used to represent invalid depth values.
/// Note that in the case that a depth is not measurable, the constants defined
/// here are not used. Instead we set the depth to NaN.
class InvalidDepth {
class DRAKE_DEPRECATED("2021-09-01",
"Use ImageTraits<PixelType::kDepth32F> instead.")
InvalidDepth {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(InvalidDepth)

Expand All @@ -174,7 +175,9 @@ class InvalidDepth {
};

/// Set of labels used for label image.
class Label {
class DRAKE_DEPRECATED("2021-09-01",
"There is no replacement; these values are unused within Drake.")
Label {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Label)
/// The label used for pixels correspond to nothing.
Expand Down

0 comments on commit 9c56baa

Please sign in to comment.