Skip to content

Commit

Permalink
[render] Deprecate RgbdSensor's CameraProperties API (RobotLocomotion…
Browse files Browse the repository at this point in the history
…#14358)

* Deprecate RgbdSensor API

- RgbdSensor
  - deprecate CameraPoses
  - deprecate the constructors on CameraProps and CameraPoses
  - Add single-camera constructor (infer color from depth).
  - bindings
    - deprecate CameraPoses binding
    - deprecated RgbdSensor constructors that use CameraPoses.
    - Add bindings for RenderCamera constructors.
- Conversion constructors on RenderCameras now take additional sensor pose.
- Add DeprecatedParamInit to facilitate deprecation of constructors that
  have otherwise been declared with ParamInit.
  • Loading branch information
SeanCurtis-TRI authored Nov 19, 2020
1 parent 4731f31 commit ff402b6
Show file tree
Hide file tree
Showing 15 changed files with 325 additions and 151 deletions.
16 changes: 16 additions & 0 deletions bindings/pydrake/common/deprecation_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,5 +98,21 @@ auto py_init_deprecated(py::str message, Func&& func) {
return py::init(WrapDeprecated(message, std::forward<Func>(func)));
}

/// The deprecated flavor of ParamInit<>.
template <typename Class>
auto DeprecatedParamInit(py::str message) {
return py::init(WrapDeprecated(message, [](py::kwargs kwargs) {
// N.B. We use `Class` here because `pybind11` strongly requires that we
// return the instance itself, not just `py::object`.
// TODO(eric.cousineau): This may hurt `keep_alive` behavior, as this
// reference may evaporate by the time the true holding pybind11 record is
// constructed. Would be alleviated using old-style pybind11 init :(
Class obj{};
py::object py_obj = py::cast(&obj, py_rvp::reference);
py::module::import("pydrake").attr("_setattr_kwargs")(py_obj, kwargs);
return obj;
}));
}

} // namespace pydrake
} // namespace drake
17 changes: 17 additions & 0 deletions bindings/pydrake/common/test/deprecation_example/cc_module_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,23 @@ PYBIND11_MODULE(cc_module, m) {
WarnDeprecated("Example emitting of deprecation", "2038-01-19");
});

{
using Class = ExampleCppStruct;
constexpr auto& cls_doc = doc.ExampleCppStruct;

// ParamInit would allow the following constructor:
// o = ExampleCppStruct(i=1, j=2)
// We're deprecating it, such that the only non-deprecated way would be:
// o = ExampleCppStruct()
// o.i = 1
// o.j = 2
py::class_<Class> cls(m, "ExampleCppStruct", cls_doc.doc);
cls // BR
.def(DeprecatedParamInit<Class>("Deprecated as of 2038-01-19"))
.def_readwrite("i", &Class::i)
.def_readwrite("j", &Class::j);
}

{
using Class = ExampleCppClass;
constexpr auto& cls_doc = doc.ExampleCppClass;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,5 +33,13 @@ class ExampleCppClass {
void overload(int) {}
};

/// Serves as an example for binding (and deprecating) a simple struct. This
/// allows the struct to be constructed with ParamInit and deprecated using
/// the corresponding DeprecatedParamInit.
struct ExampleCppStruct {
int i{};
int j{};
};

} // namespace example_class
} // namespace drake
3 changes: 1 addition & 2 deletions bindings/pydrake/geometry_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -193,8 +193,7 @@ void def_geometry_render(py::module m) {
py::class_<Class> cls(m, "ColorRenderCamera", cls_doc.doc);
cls // BR
.def(py::init<Class const&>())
.def(py::init<RenderCameraCore, bool>(),
cls_doc.ctor.doc_2args_core_show_window)
.def(py::init<RenderCameraCore, bool>(), cls_doc.ctor.doc_2args)
.def("core", static_cast<RenderCameraCore const& (Class::*)() const>(
&Class::core))
.def("show_window",
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,7 @@ drake_pybind_library(
cc_deps = [
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake/common:cpp_template_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:eigen_geometry_pybind",
"//bindings/pydrake/common:eigen_pybind",
"//bindings/pydrake/common:type_pack",
Expand Down
36 changes: 28 additions & 8 deletions bindings/pydrake/systems/sensors_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include "pybind11/stl.h"

#include "drake/bindings/pydrake/common/cpp_template_pybind.h"
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/eigen_geometry_pybind.h"
#include "drake/bindings/pydrake/common/eigen_pybind.h"
#include "drake/bindings/pydrake/common/type_pack.h"
Expand Down Expand Up @@ -38,7 +39,9 @@ using Eigen::Map;
using Eigen::Vector3d;
using geometry::FrameId;
using geometry::render::CameraProperties;
using geometry::render::ColorRenderCamera;
using geometry::render::DepthCameraProperties;
using geometry::render::DepthRenderCamera;
using math::RigidTransformd;
using math::RollPitchYawd;

Expand Down Expand Up @@ -200,28 +203,45 @@ PYBIND11_MODULE(sensors, m) {
py::class_<RgbdSensor, LeafSystem<T>> rgbd_sensor(
m, "RgbdSensor", doc.RgbdSensor.doc);

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
py::class_<RgbdSensor::CameraPoses>(
rgbd_sensor, "CameraPoses", doc.RgbdSensor.CameraPoses.doc)
.def(ParamInit<RgbdSensor::CameraPoses>())
rgbd_sensor, "CameraPoses", doc.RgbdSensor.CameraPoses.doc_deprecated)
.def(DeprecatedParamInit<RgbdSensor::CameraPoses>(
doc.RgbdSensor.CameraPoses.doc_deprecated))
.def_readwrite("X_BC", &RgbdSensor::CameraPoses::X_BC)
.def_readwrite("X_BD", &RgbdSensor::CameraPoses::X_BD);

rgbd_sensor
.def(py::init<FrameId, const RigidTransformd&, const CameraProperties&,
const DepthCameraProperties&, const RgbdSensor::CameraPoses&,
bool>(),
.def(py_init_deprecated<RgbdSensor, FrameId, const RigidTransformd&,
const CameraProperties&, const DepthCameraProperties&,
const RgbdSensor::CameraPoses&, bool>(
doc.RgbdSensor.ctor.doc_legacy_individual_intrinsics),
py::arg("parent_id"), py::arg("X_PB"), py::arg("color_properties"),
py::arg("depth_properties"),
py::arg("camera_poses") = RgbdSensor::CameraPoses{},
py::arg("show_window") = false,
doc.RgbdSensor.ctor.doc_legacy_individual_intrinsics)
.def(py::init<FrameId, const RigidTransformd&,
.def(py_init_deprecated<RgbdSensor, FrameId, const RigidTransformd&,
const DepthCameraProperties&, const RgbdSensor::CameraPoses&,
bool>(),
bool>(doc.RgbdSensor.ctor.doc_legacy_combined_intrinsics),
py::arg("parent_id"), py::arg("X_PB"), py::arg("properties"),
py::arg("camera_poses") = RgbdSensor::CameraPoses{},
py::arg("show_window") = false,
doc.RgbdSensor.ctor.doc_legacy_combined_intrinsics)
doc.RgbdSensor.ctor.doc_legacy_combined_intrinsics);
#pragma GCC diagnostic pop

rgbd_sensor
.def(py::init<FrameId, const RigidTransformd&, ColorRenderCamera,
DepthRenderCamera>(),
py::arg("parent_id"), py::arg("X_PB"), py::arg("color_camera"),
py::arg("depth_camera"),
doc.RgbdSensor.ctor.doc_individual_intrinsics)
.def(py::init<FrameId, const RigidTransformd&, const DepthRenderCamera&,
bool>(),
py::arg("parent_id"), py::arg("X_PB"), py::arg("depth_camera"),
py::arg("show_window") = false,
doc.RgbdSensor.ctor.doc_combined_intrinsics)
.def("color_camera_info", &RgbdSensor::color_camera_info,
py_rvp::reference_internal, doc.RgbdSensor.color_camera_info.doc)
.def("depth_camera_info", &RgbdSensor::depth_camera_info,
Expand Down
124 changes: 90 additions & 34 deletions bindings/pydrake/systems/test/sensors_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,19 @@
import numpy as np

from pydrake.common import FindResourceOrThrow
from pydrake.common.test_utilities.deprecation import catch_drake_warnings
from pydrake.common.test_utilities.pickle_compare import assert_pickle
from pydrake.common.value import AbstractValue, Value
from pydrake.geometry import FrameId
from pydrake.geometry.render import CameraProperties, DepthCameraProperties
from pydrake.geometry.render import (
CameraProperties,
ClippingRange,
ColorRenderCamera,
DepthCameraProperties,
DepthRange,
DepthRenderCamera,
RenderCameraCore,
)
from pydrake.math import (
RigidTransform,
RollPitchYaw,
Expand Down Expand Up @@ -258,46 +267,89 @@ def check_ports(system):
width = 1280
height = 720

color_properties = CameraProperties(
width=width, height=height, fov_y=np.pi/6,
renderer_name="renderer")
depth_properties = DepthCameraProperties(
width=width, height=height, fov_y=np.pi/6,
renderer_name="renderer", z_near=0.1, z_far=5.5)
# There are *two* variants of the constructor for each camera
# representation: one with color and depth explicitly specified and one
# with only depth. We enumerate all four here.

def construct_deprecated(parent_id, X_PB):
# One deprecation warning for CameraPoses and one for RgbdSensor.
with catch_drake_warnings(expected_count=2):
color_properties = CameraProperties(
width=width, height=height, fov_y=np.pi/6,
renderer_name="renderer")
depth_properties = DepthCameraProperties(
width=width, height=height, fov_y=np.pi/6,
renderer_name="renderer", z_near=0.1, z_far=5.5)
camera_poses = mut.RgbdSensor.CameraPoses(
X_BC=RigidTransform(), X_BD=RigidTransform())
return mut.RgbdSensor(parent_id=parent_id, X_PB=X_PB,
color_properties=color_properties,
depth_properties=depth_properties,
camera_poses=camera_poses,
show_window=False)

def construct(parent_id, X_PB):
color_camera = ColorRenderCamera(
RenderCameraCore(
"renderer",
mut.CameraInfo(width, height, np.pi/6),
ClippingRange(0.1, 6.0),
RigidTransform()
), False)
depth_camera = DepthRenderCamera(color_camera.core(),
DepthRange(0.1, 5.5))
return mut.RgbdSensor(parent_id=parent_id, X_PB=X_PB,
color_camera=color_camera,
depth_camera=depth_camera)

def construct_single_deprecated(parent_id, X_PB):
with catch_drake_warnings(expected_count=2):
depth_properties = DepthCameraProperties(
width=width, height=height, fov_y=np.pi/6,
renderer_name="renderer", z_near=0.1, z_far=5.5)
return mut.RgbdSensor(
parent_id=parent_id, X_PB=X_PB,
properties=depth_properties,
camera_poses=mut.RgbdSensor.CameraPoses(),
show_window=False)

def construct_single(parent_id, X_PB):
depth_camera = DepthRenderCamera(
RenderCameraCore(
"renderer",
mut.CameraInfo(width, height, np.pi/6),
ClippingRange(0.1, 6.0),
RigidTransform()
),
DepthRange(0.1, 5.5))
return mut.RgbdSensor(parent_id=parent_id, X_PB=X_PB,
depth_camera=depth_camera)

# Put it at the origin.
X_WB = RigidTransform()
# This id would fail if we tried to render; no such id exists.
parent_id = FrameId.get_new_id()
camera_poses = mut.RgbdSensor.CameraPoses(
X_BC=RigidTransform(), X_BD=RigidTransform())
sensor = mut.RgbdSensor(parent_id=parent_id, X_PB=X_WB,
color_properties=color_properties,
depth_properties=depth_properties,
camera_poses=camera_poses,
show_window=False)

def check_info(camera_info):
self.assertIsInstance(camera_info, mut.CameraInfo)
self.assertEqual(camera_info.width(), width)
self.assertEqual(camera_info.height(), height)

check_info(sensor.color_camera_info())
check_info(sensor.depth_camera_info())
self.assertIsInstance(sensor.X_BC(),
RigidTransform)
self.assertIsInstance(sensor.X_BD(),
RigidTransform)
self.assertEqual(sensor.parent_frame_id(), parent_id)
check_ports(sensor)

# Test discrete camera, reconstructing using single-properties
# constructor.
color_and_depth_properties = depth_properties
sensor = mut.RgbdSensor(parent_id=parent_id, X_PB=X_WB,
properties=color_and_depth_properties,
camera_poses=camera_poses,
show_window=False)
for constructor in [construct_deprecated, construct,
construct_single_deprecated,
construct_single]:
sensor = constructor(parent_id, X_WB)
check_info(sensor.color_camera_info())
check_info(sensor.depth_camera_info())
self.assertIsInstance(sensor.X_BC(),
RigidTransform)
self.assertIsInstance(sensor.X_BD(),
RigidTransform)
self.assertEqual(sensor.parent_frame_id(), parent_id)
check_ports(sensor)

# Test discrete camera. We'll simply use the last sensor constructed.

period = mut.RgbdSensorDiscrete.kDefaultPeriod
discrete = mut.RgbdSensorDiscrete(
sensor=sensor, period=period, render_label_image=True)
Expand All @@ -308,7 +360,11 @@ def check_info(camera_info):
# That we can access the state as images.
context = discrete.CreateDefaultContext()
values = context.get_abstract_state()
self.assertIsInstance(values.get_value(0), Value[mut.ImageRgba8U])
self.assertIsInstance(values.get_value(1), Value[mut.ImageDepth32F])
self.assertIsInstance(values.get_value(2), Value[mut.ImageDepth16U])
self.assertIsInstance(values.get_value(3), Value[mut.ImageLabel16I])
self.assertIsInstance(values.get_value(0),
Value[mut.ImageRgba8U])
self.assertIsInstance(values.get_value(1),
Value[mut.ImageDepth32F])
self.assertIsInstance(values.get_value(2),
Value[mut.ImageDepth16U])
self.assertIsInstance(values.get_value(3),
Value[mut.ImageLabel16I])
12 changes: 5 additions & 7 deletions bindings/pydrake/test/geometry_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -949,13 +949,11 @@ def DoRenderLabelImage(self, camera, label_image_out):
sensor = builder.AddSystem(RgbdSensor(
parent_id=scene_graph.world_frame_id(),
X_PB=RigidTransform(),
properties=mut.render.DepthCameraProperties(
width=640, height=480, fov_y=np.pi/4,
renderer_name="renderer", z_near=0.1, z_far=5.0,
),
camera_poses=RgbdSensor.CameraPoses(),
show_window=False,
))
depth_camera=mut.render.DepthRenderCamera(
mut.render.RenderCameraCore(
renderer_name, CameraInfo(640, 480, np.pi/4),
mut.render.ClippingRange(0.1, 5.0), RigidTransform()),
mut.render.DepthRange(0.1, 5.0))))
builder.Connect(
scene_graph.get_query_output_port(),
sensor.query_object_input_port(),
Expand Down
4 changes: 2 additions & 2 deletions geometry/render/render_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,11 @@ ClippingRange::ClippingRange(double near, double far) : near_(near), far_(far) {
}

RenderCameraCore::RenderCameraCore(const CameraProperties& camera,
double clipping_far)
double clipping_far, RigidTransformd X_BS)
: RenderCameraCore(camera.renderer_name,
CameraInfo{camera.width, camera.height, camera.fov_y},
ClippingRange{kClippingNear, clipping_far},
RigidTransformd{}) {}
std::move(X_BS)) {}

Eigen::Matrix4d RenderCameraCore::CalcProjectionMatrix() const {
/* Given the camera properties we compute the projection matrix as follows:
Expand Down
19 changes: 12 additions & 7 deletions geometry/render/render_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,8 @@ class RenderCameraCore {
/** (Advanced) Constructs a %RenderCameraCore from the old, symmetric camera
representation. This constructor should only be used internally; it serves
as a stop gap measure until CameraProperties is fully deprecated. */
RenderCameraCore(const CameraProperties& camera, double clipping_far);
RenderCameraCore(const CameraProperties& camera, double clipping_far,
math::RigidTransformd X_BS = {});

/** Fully-specified constructor. See the documentation on the member getter
methods for documentation of parameters. */
Expand Down Expand Up @@ -110,9 +111,11 @@ class ColorRenderCamera {
representation. This constructor should only be used internally; it serves
as a stop gap measure until CameraProperties is fully deprecated. */
explicit ColorRenderCamera(const CameraProperties& camera,
bool show_window = false)
: ColorRenderCamera(RenderCameraCore(camera, kClippingFar), show_window) {
}
bool show_window = false,
math::RigidTransformd X_BC = {})
: ColorRenderCamera(
RenderCameraCore(camera, kClippingFar, std::move(X_BC)),
show_window) {}

/** Fully-specified constructor. See the documentation on the member getter
methods for documentation of parameters. */
Expand Down Expand Up @@ -176,9 +179,11 @@ class DepthRenderCamera {
/** Constructs a %DepthRenderCamera from the old, symmetric camera
representation. This constructor should only be used internally; it serves
as a stop gap measure until CameraProperties is fully deprecated. */
explicit DepthRenderCamera(const DepthCameraProperties& camera)
: DepthRenderCamera(RenderCameraCore(camera, camera.z_far * 1.1),
DepthRange(camera.z_near, camera.z_far)) {}
explicit DepthRenderCamera(const DepthCameraProperties& camera,
math::RigidTransformd X_BD = {})
: DepthRenderCamera(
RenderCameraCore(camera, camera.z_far * 1.1, std::move(X_BD)),
DepthRange(camera.z_near, camera.z_far)) {}

/** Fully-specified constructor. See the documentation on the member getter
methods for documentation of parameters.
Expand Down
Loading

0 comments on commit ff402b6

Please sign in to comment.