-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
rgbd_sensor_async.cc
537 lines (469 loc) · 20.9 KB
/
rgbd_sensor_async.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
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
#include "drake/systems/sensors/rgbd_sensor_async.h"
#include <future>
#include <limits>
#include <map>
#include <memory>
#include <set>
#include <string>
#include <utility>
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/sensors/rgbd_sensor.h"
/* Here's an outline of how RgbdSensorAsync is implemented.
There are two logical state variables (stored as a single abstract state
variable):
1. The Worker; this is essentially a std::future for the rendering task.
2. The RenderedImages; this is the result of rendering.
The system has two periodic update events, both at the same rate but with
different phase offsets:
1. The "capture" event updates the Worker state by launching a new render task.
2. The "output" event updates the RenderedImages state by waiting for the worker
to finish and storing the resulting images.
The only real trick is how to sufficiently encapsulate a rendering task so that
it can run on a background thread. The Worker accomplishes that using a helper
class, the SnapshotSensor. The SnapshotSensor (itself a diagram) contains a
QueryObjectChef and RgbdSensor connected in series. The Worker allocates a
standalone SnapshotSensor Context and fixes the chef's input port(s) to be a
copy of the scene graph's FramePoseVector input port(s), and uses the RgbdSensor
to produce a rendered image on its output port. */
namespace drake {
namespace systems {
namespace sensors {
using geometry::FrameId;
using geometry::FramePoseVector;
using geometry::GeometryVersion;
using geometry::QueryObject;
using geometry::Role;
using geometry::SceneGraph;
using geometry::SceneGraphInspector;
using geometry::render::ClippingRange;
using geometry::render::ColorRenderCamera;
using geometry::render::DepthRange;
using geometry::render::DepthRenderCamera;
using geometry::render::RenderCameraCore;
using math::RigidTransformd;
namespace {
/* A stateless system with the exact same input ports and output ports as the
given SceneGraph, but with a private scratch Context to allow fixed input ports
for the frame kinematics input. */
class QueryObjectChef final : public LeafSystem<double> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(QueryObjectChef)
explicit QueryObjectChef(const SceneGraph<double>* scene_graph)
: scene_graph_(scene_graph) {
DRAKE_DEMAND(scene_graph != nullptr);
// Our input ports are exactly the same as the underlying scene_graph.
for (InputPortIndex i{0}; i < scene_graph->num_input_ports(); ++i) {
const auto& port = scene_graph->get_input_port(i);
DeclareAbstractInputPort(port.get_name(), *port.Allocate());
}
// We allocate a SceneGraph context into scratch storage in *our* context.
Scratch scratch;
scratch.scene_graph_context = scene_graph->CreateDefaultContext();
scratch_index_ =
this->DeclareCacheEntry(
"scratch", ValueProducer(scratch, &ValueProducer::NoopCalc),
{this->nothing_ticket()})
.cache_index();
// Our output is calculated by the SceneGraph. We use the lambda-based port
// declaration syntax here (vs member function callback syntax) to avoid
// extra copying.
DeclareAbstractOutputPort(
"query",
[]() {
return Value<QueryObject<double>>().Clone();
},
[this](const Context<double>& context, AbstractValue* output) {
this->CalcOutput(context, output);
},
{all_input_ports_ticket()});
}
void CalcOutput(const Context<double>& context, AbstractValue* output) const {
Scratch& scratch = get_cache_entry(scratch_index_)
.get_mutable_cache_entry_value(context)
.GetMutableValueOrThrow<Scratch>();
DRAKE_DEMAND(scratch.scene_graph_context != nullptr);
Context<double>& scene_graph_context = *scratch.scene_graph_context;
for (InputPortIndex i{0}; i < num_input_ports(); ++i) {
const auto& port = get_input_port(i);
if (port.HasValue(context)) {
const auto& value = port.template Eval<AbstractValue>(context);
scene_graph_context.FixInputPort(i, value);
}
}
scene_graph_->get_query_output_port().Calc(scene_graph_context, output);
}
private:
struct Scratch {
copyable_unique_ptr<Context<double>> scene_graph_context;
};
const SceneGraph<double>* const scene_graph_;
CacheIndex scratch_index_;
};
/* Combines QueryObjectChef + RgbdSensor in series, creating a sensor that
renders from a static FramePoseVector instead of a live QueryObject. */
class SnapshotSensor final : public Diagram<double> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SnapshotSensor)
SnapshotSensor(const SceneGraph<double>* scene_graph, FrameId parent_id,
const RigidTransformd& X_PB, ColorRenderCamera color_camera,
DepthRenderCamera depth_camera) {
DRAKE_DEMAND(scene_graph != nullptr);
geometry_version_ = scene_graph->model_inspector().geometry_version();
DiagramBuilder<double> builder;
auto* chef = builder.AddNamedSystem<QueryObjectChef>("chef", scene_graph);
auto* rgbd = builder.AddNamedSystem<RgbdSensor>("camera", parent_id, X_PB,
color_camera, depth_camera);
builder.Connect(*chef, *rgbd);
for (InputPortIndex i{0}; i < chef->num_input_ports(); ++i) {
const auto& input_port = chef->get_input_port(i);
builder.ExportInput(input_port, input_port.get_name());
}
for (OutputPortIndex i{0}; i < rgbd->num_output_ports(); ++i) {
const auto& output_port = rgbd->get_output_port(i);
builder.ExportOutput(output_port, output_port.get_name());
}
builder.BuildInto(this);
}
/* Returns the version as of when this sensor was created. */
const GeometryVersion& geometry_version() const { return geometry_version_; }
private:
GeometryVersion geometry_version_;
};
/* The results of camera rendering. */
struct RenderedImages {
RigidTransformd X_WB;
double time{std::numeric_limits<double>::quiet_NaN()};
std::shared_ptr<const ImageRgba8U> color;
std::shared_ptr<const ImageDepth32F> depth;
std::shared_ptr<const ImageLabel16I> label;
};
/* The worker is an object where Start() copies the pose input for camera
rendering and launches an async task, and Finish() blocks for the task to
complete. The expected workflow is to create a Worker and then repeatedly
Start and Finish in alternation (with exactly one Finish per Start). This
encapsulates the lifetime of the async task along with the objects it must
keep alive during rendering. */
class Worker {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Worker)
Worker(std::shared_ptr<const SnapshotSensor> sensor, bool color, bool depth,
bool label)
: sensor_{std::move(sensor)},
color_{color},
depth_{depth},
label_{label} {
DRAKE_DEMAND(sensor_ != nullptr);
sensor_context_ = sensor_->CreateDefaultContext();
}
/* Begins rendering the given geometry as an async task. */
void Start(double context_time, const QueryObject<double>& query);
/* Waits until image rendering for the most recent call to Start() is finished
and then returns the result. When there is no async task (e.g., if Start has
not been called since the most recent Finish), returns a default-constructed
value (i.e., with nullptr for the images). */
RenderedImages Finish();
private:
const std::shared_ptr<const SnapshotSensor> sensor_;
const bool color_;
const bool depth_;
const bool label_;
std::unique_ptr<Context<double>> sensor_context_;
std::future<RenderedImages> future_;
};
} // namespace
/* The abstract state for an RgbdSensorAsync. The `output` is what appears on
RgbdSensorAsync output ports. The `worker` encapsulates the background task.
If the systems framework offered unrestricted update events that only updated
one specific AbstractStateIndex instead of the entire State, then it would make
sense to split this up into two separate abstract states. In the meantime, it's
simplest to keep all of our state in one place. */
struct RgbdSensorAsync::TickTockState {
std::shared_ptr<Worker> worker;
RenderedImages output;
};
RgbdSensorAsync::RgbdSensorAsync(const SceneGraph<double>* scene_graph,
FrameId parent_id, const RigidTransformd& X_PB,
double fps, double capture_offset,
double output_delay,
std::optional<ColorRenderCamera> color_camera,
std::optional<DepthRenderCamera> depth_camera,
bool render_label_image)
: scene_graph_{scene_graph},
parent_id_{parent_id},
X_PB_{X_PB},
fps_{fps},
capture_offset_{capture_offset},
output_delay_{output_delay},
color_camera_{std::move(color_camera)},
depth_camera_{std::move(depth_camera)},
render_label_image_{render_label_image} {
DRAKE_THROW_UNLESS(scene_graph != nullptr);
DRAKE_THROW_UNLESS(std::isfinite(fps) && (fps > 0));
DRAKE_THROW_UNLESS(std::isfinite(capture_offset) && (capture_offset >= 0));
DRAKE_THROW_UNLESS(std::isfinite(output_delay) && (output_delay > 0));
DRAKE_THROW_UNLESS(output_delay < (1 / fps));
DRAKE_THROW_UNLESS(color_camera_.has_value() || depth_camera_.has_value());
DRAKE_THROW_UNLESS(!render_label_image || color_camera_.has_value());
// TODO(jwnimmer-tri) Check that the render engine named by either of the two
// cameras is not the (known non-threadsafe) VTK engine.
// Input.
DeclareAbstractInputPort("geometry_query", Value<QueryObject<double>>{});
// State.
using Self = RgbdSensorAsync;
auto state_index = DeclareAbstractState(Value<TickTockState>{});
DeclareInitializationUnrestrictedUpdateEvent(&Self::Initialize);
DeclarePeriodicUnrestrictedUpdateEvent(1 / fps, capture_offset,
&Self::CalcTick);
DeclarePeriodicUnrestrictedUpdateEvent(1 / fps, capture_offset + output_delay,
&Self::CalcTock);
// Output. These port names are intended to match RgbdSensor's port names.
const std::set<DependencyTicket> state = {abstract_state_ticket(state_index)};
if (color_camera_.has_value()) {
DeclareAbstractOutputPort("color_image", &Self::CalcColor, state);
}
if (depth_camera_.has_value()) {
DeclareAbstractOutputPort("depth_image_32f", &Self::CalcDepth32F, state);
DeclareAbstractOutputPort("depth_image_16u", &Self::CalcDepth16U, state);
}
if (render_label_image) {
DeclareAbstractOutputPort("label_image", &Self::CalcLabel, state);
}
DeclareAbstractOutputPort("body_pose_in_world", &Self::CalcX_WB, state);
DeclareVectorOutputPort("image_time", 1, &Self::CalcImageTime, state);
}
const OutputPort<double>& RgbdSensorAsync::color_image_output_port() const {
constexpr char name[] = "color_image";
return this->GetOutputPort(name);
}
const OutputPort<double>& RgbdSensorAsync::depth_image_32F_output_port() const {
constexpr char name[] = "depth_image_32f";
return this->GetOutputPort(name);
}
const OutputPort<double>& RgbdSensorAsync::depth_image_16U_output_port() const {
constexpr char name[] = "depth_image_16u";
return this->GetOutputPort(name);
}
const OutputPort<double>& RgbdSensorAsync::label_image_output_port() const {
constexpr char name[] = "label_image";
return this->GetOutputPort(name);
}
const OutputPort<double>& RgbdSensorAsync::body_pose_in_world_output_port()
const {
constexpr char name[] = "body_pose_in_world";
return this->GetOutputPort(name);
}
const OutputPort<double>& RgbdSensorAsync::image_time_output_port() const {
constexpr char name[] = "image_time";
return this->GetOutputPort(name);
}
const RgbdSensorAsync::TickTockState& RgbdSensorAsync::get_state(
const Context<double>& context) const {
return context.template get_abstract_state<TickTockState>(0);
}
RgbdSensorAsync::TickTockState& RgbdSensorAsync::get_mutable_state(
State<double>* state) const {
DRAKE_DEMAND(state != nullptr);
return state->template get_mutable_abstract_state<TickTockState>(0);
}
EventStatus RgbdSensorAsync::Initialize(const Context<double>& context,
State<double>* state) const {
// Grab the downcast reference from our argument.
unused(context);
TickTockState& next_state = get_mutable_state(state);
// If we are only going to render one of color or depth, invent dummy
// properties for the other one to simplify the SnapshotSensor code.
std::optional<ColorRenderCamera> color = color_camera_;
std::optional<DepthRenderCamera> depth = depth_camera_;
if (!color.has_value()) {
DRAKE_DEMAND(depth.has_value());
const RenderCameraCore& core = depth->core();
color.emplace(core);
}
if (!depth.has_value()) {
DRAKE_DEMAND(color.has_value());
const RenderCameraCore& core = color->core();
const ClippingRange& clip = core.clipping();
// N.B. Avoid using clip.far() here; it can trip the "16 bit mm depth"
// logger spam from RgbdSensor.
depth.emplace(core, DepthRange(clip.near(), clip.near() * 1.001));
}
// The `sensor` is a separate, nested system that actually renders images.
// The outer system (`this`) is just the event shims that will tick it. Our
// job during initialization is to reset the nested system and any prior
// output.
auto sensor = std::make_shared<const SnapshotSensor>(
scene_graph_, parent_id_, X_PB_, std::move(*color), std::move(*depth));
next_state.worker =
std::make_shared<Worker>(std::move(sensor), color_camera_.has_value(),
depth_camera_.has_value(), render_label_image_);
next_state.output = {};
return EventStatus::Succeeded();
}
void RgbdSensorAsync::CalcTick(const Context<double>& context,
State<double>* state) const {
// Get the geometry pose updates.
const auto& query = get_input_port().Eval<QueryObject<double>>(context);
// Grab the downcast references from our arguments.
const TickTockState& prior_state = get_state(context);
TickTockState& next_state = get_mutable_state(state);
// Preserve the current output from the prior state. We're only going to
// launch a worker task, without any changes to our output.
next_state.output = prior_state.output;
// Latch-initialize a worker we didn't have one yet.
if (prior_state.worker == nullptr) {
Initialize(context, state);
} else {
next_state.worker = prior_state.worker;
}
// Start the worker on its next task.
next_state.worker->Start(context.get_time(), query);
}
void RgbdSensorAsync::CalcTock(const Context<double>& context,
State<double>* state) const {
// Grab the downcast references from our arguments.
const TickTockState& prior_state = get_state(context);
TickTockState& next_state = get_mutable_state(state);
// If the user manually changes the State outside of a Simulator, we might hit
// a tock without having been initialized. Guard that here to avoid crashing.
if (prior_state.worker == nullptr) {
next_state = {};
return;
}
// TODO(jwnimmer-tri) Consider adding a guard here so that out-of-sequence
// tocks due to the user manually screwing with the State result in empty
// images instead of stale images.
// Finish the worker task, and copy it to the output ports.
next_state.worker = prior_state.worker;
next_state.output = next_state.worker->Finish();
}
namespace {
/* If the rendered image is non-null, copy it to output. Otherwise, set the
the output to be empty (i.e., zero-sized width and height). */
template <typename ImageIn, typename ImageOut>
void CopyImage(const ImageIn* rendered, ImageOut* output) {
DRAKE_DEMAND(output != nullptr);
if (rendered == nullptr) {
output->resize(0, 0);
return;
}
if constexpr (std::is_same_v<ImageIn, ImageOut>) {
*output = *rendered;
} else {
ConvertDepth32FTo16U(*rendered, output);
}
}
} // namespace
void RgbdSensorAsync::CalcColor(const Context<double>& context,
ImageRgba8U* output) const {
DRAKE_DEMAND(color_camera_.has_value());
CopyImage(get_state(context).output.color.get(), output);
}
void RgbdSensorAsync::CalcLabel(const Context<double>& context,
ImageLabel16I* output) const {
DRAKE_DEMAND(color_camera_.has_value());
CopyImage(get_state(context).output.label.get(), output);
}
void RgbdSensorAsync::CalcDepth32F(const Context<double>& context,
ImageDepth32F* output) const {
DRAKE_DEMAND(depth_camera_.has_value());
CopyImage(get_state(context).output.depth.get(), output);
}
void RgbdSensorAsync::CalcDepth16U(const Context<double>& context,
ImageDepth16U* output) const {
DRAKE_DEMAND(depth_camera_.has_value());
CopyImage(get_state(context).output.depth.get(), output);
}
void RgbdSensorAsync::CalcX_WB(const Context<double>& context,
RigidTransformd* output) const {
*output = get_state(context).output.X_WB;
}
void RgbdSensorAsync::CalcImageTime(const Context<double>& context,
BasicVector<double>* output) const {
output->SetFromVector(Vector1d{get_state(context).output.time});
}
namespace {
void Worker::Start(double context_time, const QueryObject<double>& query) {
// Confirm that the geometry version number has not changed since Initialize.
const GeometryVersion& initialize_version = sensor_->geometry_version();
const GeometryVersion& current_version = query.inspector().geometry_version();
if (!current_version.IsSameAs(initialize_version, Role::kPerception)) {
// TODO(jwnimmer-tri) Ideally, here we would update our copy of the geometry
// to match `query` instead of throwing. That's somewhat complicated to
// implement and test at the moment, so for now instead we have a warning in
// our class overview docs cautioning about this.
throw std::logic_error(
"As the moment, RgbdSensorAsync cannot respond to changes in geometry "
"shapes, textures, etc. after a simulation has started. If you change "
"anything beyond poses, you must manually call Simulator::Initialize() "
"to reset things before resuming the simulation.");
}
// Read the frame poses from the QueryObject. Note that deformable geometry is
// not supported because this only propagates poses, not configurations.
// TODO(jwnimmer-tri) After the render engine API adds support for deformable
// geometry, we should upgrade this sensor to support deformables as well.
std::map<std::string, FramePoseVector<double>> poses;
const SceneGraphInspector<double>& inspector = query.inspector();
for (bool first = true; const auto& source_id : inspector.GetAllSourceIds()) {
if (first) {
first = false;
// Skip the SceneGraph source that holds the "world" frame.
DRAKE_DEMAND(
inspector.BelongsToSource(inspector.world_frame_id(), source_id));
continue;
}
const std::string& source_name = inspector.GetName(source_id);
auto& source_poses = poses[source_name + "_pose"];
for (const auto& frame_id : inspector.FramesForSource(source_id)) {
source_poses.set_value(frame_id, query.GetPoseInParent(frame_id));
}
}
// Abandon our prior task (typically not necessary; valid() is usually false).
if (future_.valid()) {
future_.wait();
future_ = {};
}
// Launch the rendering task.
auto task = [this, context_time,
poses = std::move(poses)]() -> RenderedImages {
for (const auto& [port_name, pose_vector] : poses) {
const auto& input_port = sensor_->GetInputPort(port_name);
input_port.FixValue(sensor_context_.get(), pose_vector);
}
RenderedImages result;
// TODO(jwnimmer-tri) Is there any way we can steal (move) the images from
// the output ports, to avoid extra copying? I suppose we could call the
// QueryObject directly instead of the RgbdSensor, but that would involve
// duplicating (copying) some of its functionality into this class.
if (color_) {
result.color = std::make_shared<const ImageRgba8U>(
sensor_->GetOutputPort("color_image")
.template Eval<ImageRgba8U>(*sensor_context_));
}
if (depth_) {
result.depth = std::make_shared<const ImageDepth32F>(
sensor_->GetOutputPort("depth_image_32f")
.template Eval<ImageDepth32F>(*sensor_context_));
}
if (label_) {
result.label = std::make_shared<const ImageLabel16I>(
sensor_->GetOutputPort("label_image")
.template Eval<ImageLabel16I>(*sensor_context_));
}
result.X_WB = sensor_->GetOutputPort("body_pose_in_world")
.template Eval<RigidTransformd>(*sensor_context_);
result.time = context_time;
return result;
};
future_ = std::async(std::launch::async, std::move(task));
}
RenderedImages Worker::Finish() {
if (!future_.valid()) {
return {};
}
future_.wait();
return future_.get();
}
} // namespace
} // namespace sensors
} // namespace systems
} // namespace drake