-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
Copy pathgeometry_py_render.cc
476 lines (441 loc) · 18.6 KB
/
geometry_py_render.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
/* This contains the bindings for the public API in the drake/geometry/render
and drake/geometry/render* directories. They can be found in the
pydrake.geometry module. */
#include "drake/bindings/pydrake/common/default_scalars_pybind.h"
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/serialize_pybind.h"
#include "drake/bindings/pydrake/common/value_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/geometry/geometry_py.h"
#include "drake/geometry/render/light_parameter.h"
#include "drake/geometry/render/render_engine.h"
#include "drake/geometry/render/render_label.h"
#include "drake/geometry/render_gl/factory.h"
#include "drake/geometry/render_gltf_client/factory.h"
#include "drake/geometry/render_vtk/factory.h"
namespace drake {
namespace pydrake {
using Eigen::Vector3d;
using geometry::GeometryId;
using geometry::PerceptionProperties;
using geometry::Shape;
using geometry::render::ColorRenderCamera;
using geometry::render::DepthRenderCamera;
using geometry::render::LightParameter;
using geometry::render::LightType;
using geometry::render::RenderEngine;
using math::RigidTransformd;
using systems::sensors::CameraInfo;
using systems::sensors::Image;
using systems::sensors::ImageDepth32F;
using systems::sensors::ImageLabel16I;
using systems::sensors::ImageRgba8U;
using systems::sensors::PixelType;
namespace {
class PyRenderEngine : public py::wrapper<RenderEngine> {
public:
using Base = RenderEngine;
using BaseWrapper = py::wrapper<Base>;
PyRenderEngine() : BaseWrapper() {}
void UpdateViewpoint(RigidTransformd const& X_WR) override {
PYBIND11_OVERLOAD_PURE(void, Base, UpdateViewpoint, X_WR);
}
bool DoRegisterVisual(GeometryId id, Shape const& shape,
PerceptionProperties const& properties,
RigidTransformd const& X_WG) override {
PYBIND11_OVERLOAD_PURE(
bool, Base, DoRegisterVisual, id, shape, properties, X_WG);
}
void DoUpdateVisualPose(GeometryId id, RigidTransformd const& X_WG) override {
PYBIND11_OVERLOAD_PURE(void, Base, DoUpdateVisualPose, id, X_WG);
}
bool DoRemoveGeometry(GeometryId id) override {
PYBIND11_OVERLOAD_PURE(bool, Base, DoRemoveGeometry, id);
}
std::unique_ptr<RenderEngine> DoClone() const override {
throw std::logic_error(
"Python subclasses of RenderEngine do not support calling "
"Clone<std::unique_ptr>; the C++ code which tried to call "
"it needs to be updated to call using shared_ptr instead.");
}
std::shared_ptr<RenderEngine> DoCloneShared() const override {
py::gil_scoped_acquire guard;
// RenderEngine subclasses in Python must implement cloning by defining
// either a __deepcopy__ (preferred) or DoClone (legacy) method. We'll try
// DoClone first so it has priority, but if it doesn't exist we'll fall back
// to __deepcopy__ and just let the "no such method deepcopy" error message
// propagate if both were missing. Because the PYBIND11_OVERLOAD_INT macro
// embeds a `return ...;` statement, we must wrap it in lambda so that we
// can post-process the return value.
auto make_python_deepcopy = [&]() -> py::object {
PYBIND11_OVERLOAD_INT(py::object, Base, "DoClone");
auto deepcopy = py::module_::import("copy").attr("deepcopy");
py::object copied = deepcopy(this);
if (copied.is_none()) {
throw pybind11::type_error(fmt::format(
"{}.__deepcopy__ returned None", NiceTypeName::Get(*this)));
}
return copied;
};
py::object py_engine = make_python_deepcopy();
// Convert the py_engine to a shared_ptr<RenderEngine> whose C++ lifetime
// keeps the python object alive.
RenderEngine* cpp_engine = py::cast<RenderEngine*>(py_engine);
DRAKE_DEMAND(cpp_engine != nullptr);
return std::shared_ptr<RenderEngine>(
/* stored pointer = */ cpp_engine,
/* deleter = */ [captured_py_engine = std::move(py_engine)](
void*) mutable {
py::gil_scoped_acquire deleter_guard;
captured_py_engine = py::none();
});
}
void DoRenderColorImage(ColorRenderCamera const& camera,
ImageRgba8U* color_image_out) const override {
PYBIND11_OVERLOAD_PURE(
void, Base, DoRenderColorImage, camera, color_image_out);
}
void DoRenderDepthImage(DepthRenderCamera const& camera,
ImageDepth32F* depth_image_out) const override {
PYBIND11_OVERLOAD_PURE(
void, Base, DoRenderDepthImage, camera, depth_image_out);
}
void DoRenderLabelImage(ColorRenderCamera const& camera,
ImageLabel16I* label_image_out) const override {
PYBIND11_OVERLOAD_PURE(
void, Base, DoRenderLabelImage, camera, label_image_out);
}
void SetDefaultLightPosition(Vector3d const& X_DL) override {
PYBIND11_OVERLOAD(void, Base, SetDefaultLightPosition, X_DL);
}
// Expose these protected methods (which are either virtual methods with
// default implementations, or helper functions) so that Python
// implementations can access them.
using Base::GetRenderLabelOrThrow;
using Base::SetDefaultLightPosition;
template <typename ImageType>
static void ThrowIfInvalid(const systems::sensors::CameraInfo& intrinsics,
const ImageType* image, const char* image_type) {
return Base::ThrowIfInvalid<ImageType>(intrinsics, image, image_type);
}
};
void DoScalarIndependentDefinitions(py::module m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake;
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::geometry;
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::geometry::render;
constexpr auto& doc_geometry = pydrake_doc.drake.geometry;
constexpr auto& doc = doc_geometry.render;
{
using Class = ClippingRange;
const auto& cls_doc = doc.ClippingRange;
py::class_<Class>(m, "ClippingRange", cls_doc.doc)
.def(py::init<Class const&>(), py::arg("other"), "Copy constructor")
.def(py::init<double, double>(), py::arg("near"), py::arg("far"),
cls_doc.ctor.doc)
.def("far", static_cast<double (Class::*)() const>(&Class::far),
cls_doc.far.doc)
.def("near", static_cast<double (Class::*)() const>(&Class::near),
cls_doc.near.doc);
}
{
using Class = RenderCameraCore;
const auto& cls_doc = doc.RenderCameraCore;
py::class_<Class> cls(m, "RenderCameraCore");
cls // BR
.def(py::init<Class const&>(), py::arg("other"), "Copy constructor")
.def(
py::init<std::string, CameraInfo, ClippingRange, RigidTransformd>(),
py::arg("renderer_name"), py::arg("intrinsics"),
py::arg("clipping"), py::arg("X_BS"), cls_doc.ctor.doc)
.def("clipping",
static_cast<ClippingRange const& (Class::*)() const>(
&Class::clipping),
cls_doc.clipping.doc)
.def("intrinsics",
static_cast<CameraInfo const& (Class::*)() const>(
&Class::intrinsics),
cls_doc.intrinsics.doc)
.def("renderer_name",
static_cast<::std::string const& (Class::*)() const>(
&Class::renderer_name),
cls_doc.renderer_name.doc)
.def("sensor_pose_in_camera_body",
static_cast<RigidTransformd const& (Class::*)() const>(
&Class::sensor_pose_in_camera_body),
cls_doc.sensor_pose_in_camera_body.doc);
DefCopyAndDeepCopy(&cls);
}
{
using Class = ColorRenderCamera;
const auto& cls_doc = doc.ColorRenderCamera;
py::class_<Class> cls(m, "ColorRenderCamera", cls_doc.doc);
cls // BR
.def(py::init<Class const&>(), py::arg("other"), "Copy constructor")
.def(py::init<RenderCameraCore, bool>(), py::arg("core"),
py::arg("show_window") = false, cls_doc.ctor.doc)
.def("core",
static_cast<RenderCameraCore const& (Class::*)() const>(
&Class::core),
cls_doc.core.doc)
.def("show_window",
static_cast<bool (Class::*)() const>(&Class::show_window),
cls_doc.show_window.doc);
DefCopyAndDeepCopy(&cls);
}
{
using Class = DepthRange;
const auto& cls_doc = doc.DepthRange;
py::class_<Class> cls(m, "DepthRange");
cls // BR
.def(py::init<Class const&>(), py::arg("other"), "Copy constructor")
.def(py::init<double, double>(), py::arg("min_in"), py::arg("min_out"),
cls_doc.ctor.doc)
.def("max_depth",
static_cast<double (Class::*)() const>(&Class::max_depth),
cls_doc.max_depth.doc)
.def("min_depth",
static_cast<double (Class::*)() const>(&Class::min_depth),
cls_doc.min_depth.doc);
DefCopyAndDeepCopy(&cls);
}
{
using Class = DepthRenderCamera;
const auto& cls_doc = doc.DepthRenderCamera;
py::class_<Class> cls(m, "DepthRenderCamera");
cls // BR
.def(py::init<Class const&>(), py::arg("other"), "Copy constructor")
.def(py::init<RenderCameraCore, DepthRange>(), py::arg("core"),
py::arg("depth_range"), cls_doc.ctor.doc)
.def("core",
static_cast<RenderCameraCore const& (Class::*)() const>(
&Class::core),
cls_doc.core.doc)
.def("depth_range",
static_cast<DepthRange const& (Class::*)() const>(
&Class::depth_range),
cls_doc.depth_range.doc);
DefCopyAndDeepCopy(&cls);
}
{
py::class_<RenderLabel> render_label(m, "RenderLabel", doc.RenderLabel.doc);
render_label
.def(py::init<int>(), py::arg("value"), doc.RenderLabel.ctor.doc_1args)
.def("is_reserved", &RenderLabel::is_reserved)
.def("__int__", [](const RenderLabel& self) -> int { return self; })
.def("__repr__",
[](const RenderLabel& self) -> std::string {
if (self == RenderLabel::kEmpty) {
return "RenderLabel.kEmpty";
}
if (self == RenderLabel::kDoNotRender) {
return "RenderLabel.kDoNotRender";
}
if (self == RenderLabel::kDontCare) {
return "RenderLabel.kDontCare";
}
if (self == RenderLabel::kUnspecified) {
return "RenderLabel.kUnspecified";
}
if (self == RenderLabel::kMaxUnreserved) {
return "RenderLabel.kMaxUnreserved";
}
return fmt::format("RenderLabel({})", int{self});
})
// EQ(==).
.def(py::self == py::self)
.def(py::self == int{})
.def(int{} == py::self)
// NE(!=).
.def(py::self != py::self)
.def(py::self != int{})
.def(int{} != py::self);
render_label.attr("kEmpty") = RenderLabel::kEmpty;
render_label.attr("kDoNotRender") = RenderLabel::kDoNotRender;
render_label.attr("kDontCare") = RenderLabel::kDontCare;
render_label.attr("kUnspecified") = RenderLabel::kUnspecified;
render_label.attr("kMaxUnreserved") = RenderLabel::kMaxUnreserved;
}
{
using Class = RenderEngine;
const auto& cls_doc = doc.RenderEngine;
py::class_<Class, PyRenderEngine, std::shared_ptr<Class>> cls(
m, "RenderEngine");
cls // BR
.def(py::init<>(), cls_doc.ctor.doc)
.def("Clone",
static_cast<std::shared_ptr<Class> (Class::*)() const>(
&Class::Clone),
cls_doc.Clone.doc)
.def("RegisterVisual",
static_cast<bool (Class::*)(GeometryId, Shape const&,
PerceptionProperties const&, RigidTransformd const&, bool)>(
&Class::RegisterVisual),
py::arg("id"), py::arg("shape"), py::arg("properties"),
py::arg("X_WG"), py::arg("needs_updates") = true,
cls_doc.RegisterVisual.doc)
.def("RemoveGeometry",
static_cast<bool (Class::*)(GeometryId)>(&Class::RemoveGeometry),
py::arg("id"), cls_doc.RemoveGeometry.doc)
.def("has_geometry",
static_cast<bool (Class::*)(GeometryId) const>(
&Class::has_geometry),
py::arg("id"), cls_doc.has_geometry.doc)
.def("UpdateViewpoint",
static_cast<void (Class::*)(RigidTransformd const&)>(
&Class::UpdateViewpoint),
py::arg("X_WR"), cls_doc.UpdateViewpoint.doc)
.def("RenderColorImage",
static_cast<void (Class::*)(ColorRenderCamera const&, ImageRgba8U*)
const>(&Class::RenderColorImage),
py::arg("camera"), py::arg("color_image_out"),
cls_doc.RenderColorImage.doc)
.def("RenderDepthImage",
static_cast<void (Class::*)(DepthRenderCamera const&,
ImageDepth32F*) const>(&Class::RenderDepthImage),
py::arg("camera"), py::arg("depth_image_out"),
cls_doc.RenderDepthImage.doc)
.def("RenderLabelImage",
static_cast<void (Class::*)(ColorRenderCamera const&,
ImageLabel16I*) const>(&Class::RenderLabelImage),
py::arg("camera"), py::arg("label_image_out"),
cls_doc.RenderLabelImage.doc)
.def("default_render_label",
static_cast<RenderLabel (Class::*)() const>(
&Class::default_render_label),
cls_doc.default_render_label.doc)
// N.B. We're binding against the trampoline class PyRenderEngine,
// rather than the direct class RenderEngine, solely for protected
// helper methods and non-pure virtual functions because we want them
// exposed for Python implementations of the interface.
.def("GetRenderLabelOrThrow",
static_cast<RenderLabel (Class::*)(PerceptionProperties const&)
const>(&PyRenderEngine::GetRenderLabelOrThrow),
py::arg("properties"), cls_doc.GetRenderLabelOrThrow.doc)
.def("SetDefaultLightPosition",
static_cast<void (Class::*)(Vector3d const&)>(
&PyRenderEngine::SetDefaultLightPosition),
py::arg("X_DL"), cls_doc.SetDefaultLightPosition.doc)
.def_static("ThrowIfInvalid",
static_cast<void (*)(CameraInfo const&,
Image<PixelType::kRgba8U> const*, char const*)>(
&PyRenderEngine::ThrowIfInvalid<Image<PixelType::kRgba8U>>),
py::arg("intrinsics"), py::arg("image"), py::arg("image_type"),
cls_doc.ThrowIfInvalid.doc)
.def_static("ThrowIfInvalid",
static_cast<void (*)(CameraInfo const&,
Image<PixelType::kDepth32F> const*, char const*)>(
&PyRenderEngine::ThrowIfInvalid<Image<PixelType::kDepth32F>>),
py::arg("intrinsics"), py::arg("image"), py::arg("image_type"),
cls_doc.ThrowIfInvalid.doc)
.def_static("ThrowIfInvalid",
static_cast<void (*)(CameraInfo const&,
Image<PixelType::kLabel16I> const*, char const*)>(
&PyRenderEngine::ThrowIfInvalid<Image<PixelType::kLabel16I>>),
py::arg("intrinsics"), py::arg("image"), py::arg("image_type"),
cls_doc.ThrowIfInvalid.doc);
// Note that we do not bind MakeRgbFromLabel nor MakeLabelFromRgb, because
// crossing the C++ <=> Python boundary one pixel at a time would be
// extraordinarily inefficient.
}
{
using Class = geometry::NullTexture;
constexpr auto& cls_doc = doc_geometry.NullTexture;
py::class_<Class> cls(m, "NullTexture", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}
{
using Class = geometry::EquirectangularMap;
constexpr auto& cls_doc = doc_geometry.EquirectangularMap;
py::class_<Class> cls(m, "EquirectangularMap", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}
{
using Class = geometry::EnvironmentMap;
constexpr auto& cls_doc = doc_geometry.EnvironmentMap;
py::class_<Class> cls(m, "EnvironmentMap", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}
{
using Class = geometry::GltfExtension;
constexpr auto& cls_doc = doc_geometry.GltfExtension;
py::class_<Class> cls(m, "GltfExtension", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}
{
using Class = geometry::render::LightParameter;
constexpr auto& cls_doc = doc.LightParameter;
py::class_<Class> cls(m, "LightParameter", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}
{
using Class = RenderEngineVtkParams;
constexpr auto& cls_doc = doc_geometry.RenderEngineVtkParams;
py::class_<Class> cls(m, "RenderEngineVtkParams", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls, cls_doc);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}
m.def("MakeRenderEngineVtk", &MakeRenderEngineVtk, py::arg("params"),
doc_geometry.MakeRenderEngineVtk.doc);
{
using Class = RenderEngineGlParams;
constexpr auto& cls_doc = doc_geometry.RenderEngineGlParams;
py::class_<Class> cls(m, "RenderEngineGlParams", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls, cls_doc);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}
m.def("MakeRenderEngineGl", &MakeRenderEngineGl,
py::arg("params") = RenderEngineGlParams(),
doc_geometry.MakeRenderEngineGl.doc);
{
using Class = RenderEngineGltfClientParams;
constexpr auto& cls_doc = doc_geometry.RenderEngineGltfClientParams;
py::class_<Class> cls(m, "RenderEngineGltfClientParams", cls_doc.doc);
cls // BR
.def(ParamInit<Class>());
DefAttributesUsingSerialize(&cls, cls_doc);
DefReprUsingSerialize(&cls);
DefCopyAndDeepCopy(&cls);
}
m.def("MakeRenderEngineGltfClient", &MakeRenderEngineGltfClient,
py::arg("params") = RenderEngineGltfClientParams(),
doc_geometry.MakeRenderEngineGltfClient.doc);
AddValueInstantiation<RenderLabel>(m);
}
} // namespace
void DefineGeometryRender(py::module m) {
m.doc() =
"Local bindings for render artifacts found in `drake::geometry` and "
"`drake::geometry::render`";
DoScalarIndependentDefinitions(m);
}
} // namespace pydrake
} // namespace drake