Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Parameterize RgbdSensorAsync #22427

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,7 @@ drake_pybind_library(
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake/common:cpp_template_pybind",
"//bindings/pydrake/common:default_scalars_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:eigen_pybind",
"//bindings/pydrake/common:ref_cycle_pybind",
"//bindings/pydrake/common:serialize_pybind",
Expand Down
62 changes: 57 additions & 5 deletions bindings/pydrake/systems/sensors_py_rgbd.cc
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/ref_cycle_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/systems/sensors_py.h"
Expand Down Expand Up @@ -170,7 +171,9 @@ void DefineSensorsRgbd(py::module m) {
{
using Class = RgbdSensorAsync;
constexpr auto& cls_doc = doc.RgbdSensorAsync;
py::class_<Class, LeafSystem<double>>(m, "RgbdSensorAsync", cls_doc.doc)
py::class_<Class, LeafSystem<double>> rgbd_sensor_async(
m, "RgbdSensorAsync", cls_doc.doc);
rgbd_sensor_async
.def(py::init<const geometry::SceneGraph<double>*, geometry::FrameId,
const math::RigidTransformd&, double, double, double,
std::optional<ColorRenderCamera>,
Expand All @@ -179,14 +182,46 @@ void DefineSensorsRgbd(py::module m) {
py::arg("fps"), py::arg("capture_offset"), py::arg("output_delay"),
py::arg("color_camera"), py::arg("depth_camera") = std::nullopt,
py::arg("render_label_image") = false, cls_doc.ctor.doc)
.def("parent_id", &Class::parent_id, cls_doc.parent_id.doc)
.def("X_PB", &Class::X_PB, cls_doc.X_PB.doc)
.def("fps", &Class::fps, cls_doc.fps.doc)
.def("capture_offset", &Class::capture_offset,
cls_doc.capture_offset.doc)
.def("output_delay", &Class::output_delay, cls_doc.output_delay.doc)
.def("color_camera", &Class::color_camera, cls_doc.color_camera.doc)
.def("depth_camera", &Class::depth_camera, cls_doc.depth_camera.doc)
.def("default_parent_frame_id", &Class::default_parent_frame_id,
cls_doc.default_parent_frame_id.doc)
.def("set_default_parent_frame_id", &Class::set_default_parent_frame_id,
py::arg("id"), cls_doc.set_default_parent_frame_id.doc)
.def("GetParentFrameId", &Class::GetParentFrameId, py::arg("context"),
cls_doc.GetParentFrameId.doc)
.def("SetParentFrameId", &Class::SetParentFrameId, py::arg("context"),
py::arg("id"), cls_doc.SetParentFrameId.doc)
.def("default_X_PB", &Class::default_X_PB, py_rvp::reference_internal,
cls_doc.default_X_PB.doc)
.def("set_default_X_PB", &Class::set_default_X_PB,
py::arg("sensor_pose"), cls_doc.set_default_X_PB.doc)
.def(
"GetX_PB", &Class::GetX_PB, py::arg("context"), cls_doc.GetX_PB.doc)
.def("SetX_PB", &Class::SetX_PB, py::arg("context"),
py::arg("sensor_pose"), cls_doc.SetX_PB.doc)
.def("default_color_render_camera", &Class::default_color_render_camera,
py_rvp::reference_internal, cls_doc.default_color_render_camera.doc)
.def("set_default_color_render_camera",
&Class::set_default_color_render_camera, py::arg("color_camera"),
cls_doc.set_default_color_render_camera.doc)
.def("GetColorRenderCamera", &Class::GetColorRenderCamera,
py::arg("context"), cls_doc.GetColorRenderCamera.doc)
.def("SetColorRenderCamera", &Class::SetColorRenderCamera,
py::arg("context"), py::arg("color_camera"),
cls_doc.SetColorRenderCamera.doc)
.def("default_depth_render_camera", &Class::default_depth_render_camera,
py_rvp::reference_internal, cls_doc.default_depth_render_camera.doc)
.def("set_default_depth_render_camera",
&Class::set_default_depth_render_camera, py::arg("depth_camera"),
cls_doc.set_default_depth_render_camera.doc)
.def("GetDepthRenderCamera", &Class::GetDepthRenderCamera,
py::arg("context"), cls_doc.GetDepthRenderCamera.doc)
.def("SetDepthRenderCamera", &Class::SetDepthRenderCamera,
py::arg("context"), py::arg("depth_camera"),
cls_doc.SetDepthRenderCamera.doc)
.def("color_image_output_port", &Class::color_image_output_port,
py_rvp::reference_internal, cls_doc.color_image_output_port.doc)
.def("depth_image_32F_output_port", &Class::depth_image_32F_output_port,
Expand All @@ -200,6 +235,23 @@ void DefineSensorsRgbd(py::module m) {
cls_doc.body_pose_in_world_output_port.doc)
.def("image_time_output_port", &Class::image_time_output_port,
py_rvp::reference_internal, cls_doc.image_time_output_port.doc);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
rgbd_sensor_async // BR
.def("parent_id",
WrapDeprecated(cls_doc.parent_id.doc_deprecated, &Class::parent_id),
cls_doc.parent_id.doc_deprecated)
.def("X_PB", WrapDeprecated(cls_doc.X_PB.doc_deprecated, &Class::X_PB),
cls_doc.X_PB.doc_deprecated)
.def("color_camera",
WrapDeprecated(
cls_doc.color_camera.doc_deprecated, &Class::color_camera),
cls_doc.color_camera.doc_deprecated)
.def("depth_camera",
WrapDeprecated(
cls_doc.depth_camera.doc_deprecated, &Class::depth_camera),
cls_doc.depth_camera.doc_deprecated);
#pragma GCC diagnostic pop
}
}

Expand Down
66 changes: 55 additions & 11 deletions bindings/pydrake/systems/test/sensors_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import numpy as np
from pydrake.common import FindResourceOrThrow
from pydrake.common.test_utilities import numpy_compare
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 (
Expand Down Expand Up @@ -465,25 +466,31 @@ def check_info(camera_info):

for constructor in [construct, construct_single]:
sensor = constructor(parent_id, X_WB)

# Check default accessors.
check_info(sensor.default_color_render_camera()
.core().intrinsics())
check_info(sensor.default_depth_render_camera()
.core().intrinsics())
self.assertIsInstance(sensor.default_X_PB(), RigidTransform)
self.assertEqual(sensor.default_parent_frame_id(), parent_id)
sensor.set_default_parent_frame_id(parent_id)
sensor.set_default_parent_frame_id(id=parent_id)
sensor.set_default_X_PB(sensor_pose=RigidTransform())
color_camera = sensor.default_color_render_camera()
sensor.set_default_color_render_camera(color_camera=color_camera)
depth_camera = sensor.default_depth_render_camera()
sensor.set_default_depth_render_camera(depth_camera=depth_camera)

check_ports(sensor)

# Check parameter API.
context = sensor.CreateDefaultContext()
self.assertIsInstance(sensor.GetColorRenderCamera(context=context),
ColorRenderCamera)
color_camera = sensor.default_color_render_camera()
sensor.SetColorRenderCamera(context=context,
color_camera=color_camera)
self.assertIsInstance(sensor.GetDepthRenderCamera(context=context),
DepthRenderCamera)
depth_camera = sensor.default_depth_render_camera()
sensor.SetDepthRenderCamera(context=context,
depth_camera=depth_camera)
self.assertIsInstance(sensor.GetX_PB(context=context),
Expand Down Expand Up @@ -520,22 +527,59 @@ def test_rgbd_sensor_async(self):
camera_core = self._make_render_camera_core()
color_camera = ColorRenderCamera(camera_core)
depth_camera = DepthRenderCamera(camera_core, DepthRange(0.1, 5.5))
parent_id = FrameId.get_new_id()
dut = mut.RgbdSensorAsync(scene_graph=scene_graph,
parent_id=FrameId.get_new_id(),
parent_id=parent_id,
X_PB=RigidTransform(),
fps=1.0,
capture_offset=0.1,
output_delay=0.01,
color_camera=color_camera,
depth_camera=depth_camera,
render_label_image=True)
dut.parent_id()
dut.X_PB()
dut.fps()
dut.capture_offset()
dut.output_delay()
dut.color_camera()
dut.depth_camera()

# Test deprecated methods.
with catch_drake_warnings(expected_count=1):
dut.parent_id()
with catch_drake_warnings(expected_count=1):
dut.X_PB()
with catch_drake_warnings(expected_count=1):
dut.color_camera()
with catch_drake_warnings(expected_count=1):
dut.depth_camera()

# Check const configuration accessors.
self.assertIsInstance(dut.fps(), float)
self.assertIsInstance(dut.capture_offset(), float)
self.assertIsInstance(dut.output_delay(), float)

# Check default accessors.
self.assertEqual(dut.default_parent_frame_id(), parent_id)
self.assertIsInstance(dut.default_X_PB(), RigidTransform)
self.assertIsInstance(dut.default_color_render_camera(),
ColorRenderCamera)
self.assertIsInstance(dut.default_depth_render_camera(),
DepthRenderCamera)
dut.set_default_parent_frame_id(id=parent_id)
dut.set_default_X_PB(sensor_pose=RigidTransform())
color_camera = dut.default_color_render_camera()
dut.set_default_color_render_camera(color_camera=color_camera)
depth_camera = dut.default_depth_render_camera()
dut.set_default_depth_render_camera(depth_camera=depth_camera)

# Check parameter API.
context = dut.CreateDefaultContext()
self.assertEqual(dut.GetParentFrameId(context=context), parent_id)
dut.SetParentFrameId(context=context, id=parent_id)
self.assertIsInstance(dut.GetX_PB(context=context), RigidTransform)
dut.SetX_PB(context=context, sensor_pose=RigidTransform())
self.assertIsInstance(dut.GetColorRenderCamera(context=context),
ColorRenderCamera)
dut.SetColorRenderCamera(context=context, color_camera=color_camera)
self.assertIsInstance(dut.GetDepthRenderCamera(context=context),
DepthRenderCamera)
dut.SetDepthRenderCamera(context=context, depth_camera=depth_camera)

dut.color_image_output_port()
dut.depth_image_32F_output_port()
dut.depth_image_16U_output_port()
Expand Down
1 change: 1 addition & 0 deletions systems/sensors/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -560,6 +560,7 @@ drake_cc_googletest(
name = "rgbd_sensor_async_test",
deps = [
":rgbd_sensor_async",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_throws_message",
"//geometry/test_utilities:dummy_render_engine",
"//multibody/plant",
Expand Down
Loading