forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
rgbd_sensor.cc
276 lines (236 loc) · 10.9 KB
/
rgbd_sensor.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
#include "drake/systems/sensors/rgbd_sensor.h"
#include <algorithm>
#include <limits>
#include <string>
#include <utility>
#include <Eigen/Dense>
#include "drake/common/text_logging.h"
#include "drake/geometry/render/camera_properties.h"
#include "drake/geometry/scene_graph.h"
#include "drake/math/rigid_transform.h"
#include "drake/math/rotation_matrix.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/primitives/zero_order_hold.h"
#include "drake/systems/rendering/pose_vector.h"
#include "drake/systems/sensors/camera_info.h"
#include "drake/systems/sensors/image.h"
namespace drake {
namespace systems {
namespace sensors {
using Eigen::Translation3d;
using geometry::FrameId;
using geometry::QueryObject;
using geometry::SceneGraph;
using geometry::render::CameraProperties;
using geometry::render::ColorRenderCamera;
using geometry::render::DepthCameraProperties;
using geometry::render::DepthRange;
using geometry::render::DepthRenderCamera;
using math::RigidTransformd;
using std::make_pair;
using std::move;
using std::pair;
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
RgbdSensor::RgbdSensor(FrameId parent_id, const RigidTransformd& X_PB,
const CameraProperties& color_properties,
const DepthCameraProperties& depth_properties,
const CameraPoses& camera_poses, bool show_window)
: RgbdSensor(
parent_id, X_PB,
ColorRenderCamera(color_properties, show_window, camera_poses.X_BC),
DepthRenderCamera(depth_properties, camera_poses.X_BD)) {
static const logging::Warn log_once(
"RgbdSensor constructors that take 'CameraProperties' have been "
"deprecated. Please use the RenderCamera variants instead.");
}
RgbdSensor::RgbdSensor(geometry::FrameId parent_id, const RigidTransformd& X_PB,
const DepthCameraProperties& properties,
const CameraPoses& camera_poses, bool show_window)
: RgbdSensor(parent_id, X_PB,
ColorRenderCamera(properties, show_window, camera_poses.X_BC),
DepthRenderCamera(properties, camera_poses.X_BD)) {
static const logging::Warn log_once(
"RgbdSensor constructors that take 'CameraProperties' have been "
"deprecated. Please use the RenderCamera variants instead.");
}
#pragma GCC diagnostic pop
RgbdSensor::RgbdSensor(FrameId parent_id, const RigidTransformd& X_PB,
const DepthRenderCamera& depth_camera,
bool show_color_window)
: RgbdSensor(parent_id, X_PB,
ColorRenderCamera(depth_camera.core(), show_color_window),
depth_camera) {}
RgbdSensor::RgbdSensor(FrameId parent_id, const RigidTransformd& X_PB,
ColorRenderCamera color_camera,
DepthRenderCamera depth_camera)
: parent_frame_id_(parent_id),
color_camera_(move(color_camera)),
depth_camera_(move(depth_camera)),
X_PB_(X_PB) {
const CameraInfo& color_intrinsics = color_camera_.core().intrinsics();
const CameraInfo& depth_intrinsics = depth_camera_.core().intrinsics();
query_object_input_port_ = &this->DeclareAbstractInputPort(
"geometry_query", Value<geometry::QueryObject<double>>{});
ImageRgba8U color_image(color_intrinsics.width(), color_intrinsics.height());
color_image_port_ = &this->DeclareAbstractOutputPort(
"color_image", color_image, &RgbdSensor::CalcColorImage);
ImageDepth32F depth32(depth_intrinsics.width(), depth_intrinsics.height());
depth_image_32F_port_ = &this->DeclareAbstractOutputPort(
"depth_image_32f", depth32, &RgbdSensor::CalcDepthImage32F);
ImageDepth16U depth16(depth_intrinsics.width(), depth_intrinsics.height());
depth_image_16U_port_ = &this->DeclareAbstractOutputPort(
"depth_image_16u", depth16, &RgbdSensor::CalcDepthImage16U);
ImageLabel16I label_image(color_intrinsics.width(),
color_intrinsics.height());
label_image_port_ = &this->DeclareAbstractOutputPort(
"label_image", label_image, &RgbdSensor::CalcLabelImage);
X_WB_pose_port_ = &this->DeclareVectorOutputPort(
"X_WB", rendering::PoseVector<double>(), &RgbdSensor::CalcX_WB);
// The depth_16U represents depth in *millimeters*. With 16 bits there is
// an absolute limit on the farthest distance it can register. This tests to
// see if the user has specified a maximum depth value that exceeds that
// value.
const float kMaxValidDepth16UInM =
(std::numeric_limits<uint16_t>::max() - 1) / 1000.;
const double max_depth = depth_camera_.depth_range().max_depth();
if (max_depth > kMaxValidDepth16UInM) {
drake::log()->warn(
"Specified max depth is {} m > max valid depth for 16 bits {} m. "
"depth_image_16u might not be able to capture the full depth range.",
max_depth, kMaxValidDepth16UInM);
}
}
const InputPort<double>& RgbdSensor::query_object_input_port() const {
return *query_object_input_port_;
}
const OutputPort<double>& RgbdSensor::color_image_output_port() const {
return *color_image_port_;
}
const OutputPort<double>& RgbdSensor::depth_image_32F_output_port() const {
return *depth_image_32F_port_;
}
const OutputPort<double>& RgbdSensor::depth_image_16U_output_port() const {
return *depth_image_16U_port_;
}
const OutputPort<double>& RgbdSensor::label_image_output_port() const {
return *label_image_port_;
}
const OutputPort<double>& RgbdSensor::X_WB_output_port() const {
return *X_WB_pose_port_;
}
void RgbdSensor::CalcColorImage(const Context<double>& context,
ImageRgba8U* color_image) const {
const QueryObject<double>& query_object = get_query_object(context);
query_object.RenderColorImage(
color_camera_, parent_frame_id_,
X_PB_ * color_camera_.core().sensor_pose_in_camera_body(), color_image);
}
void RgbdSensor::CalcDepthImage32F(const Context<double>& context,
ImageDepth32F* depth_image) const {
const QueryObject<double>& query_object = get_query_object(context);
query_object.RenderDepthImage(
depth_camera_, parent_frame_id_,
X_PB_ * depth_camera_.core().sensor_pose_in_camera_body(), depth_image);
}
void RgbdSensor::CalcDepthImage16U(const Context<double>& context,
ImageDepth16U* depth_image) const {
ImageDepth32F depth32(depth_image->width(), depth_image->height());
CalcDepthImage32F(context, &depth32);
ConvertDepth32FTo16U(depth32, depth_image);
}
void RgbdSensor::CalcLabelImage(const Context<double>& context,
ImageLabel16I* label_image) const {
const QueryObject<double>& query_object = get_query_object(context);
query_object.RenderLabelImage(
color_camera_, parent_frame_id_,
X_PB_ * color_camera_.core().sensor_pose_in_camera_body(), label_image);
}
void RgbdSensor::CalcX_WB(const Context<double>& context,
rendering::PoseVector<double>* pose_vector) const {
// Calculates X_WB.
RigidTransformd X_WB;
if (parent_frame_id_ == SceneGraph<double>::world_frame_id()) {
X_WB = X_PB_;
} else {
const QueryObject<double>& query_object = get_query_object(context);
X_WB = query_object.GetPoseInWorld(parent_frame_id_) * X_PB_;
}
Translation3d trans{X_WB.translation()};
pose_vector->set_translation(trans);
pose_vector->set_rotation(X_WB.rotation().ToQuaternion());
}
void RgbdSensor::ConvertDepth32FTo16U(const ImageDepth32F& d32,
ImageDepth16U* d16) {
// Convert to mm and 16bits.
const float kDepth16UOverflowDistance =
std::numeric_limits<uint16_t>::max() / 1000.;
for (int w = 0; w < d16->width(); w++) {
for (int h = 0; h < d16->height(); h++) {
const double dist = std::min(d32.at(w, h)[0], kDepth16UOverflowDistance);
d16->at(w, h)[0] = static_cast<uint16_t>(dist * 1000);
}
}
}
// Note: Ideally, this would be inlined. However, inlining this caused GCC
// to do something weird with GeometryState such that the rgbd_sensor_test.cc
// was unable to instantiate an GeometryStateTester that GCC recognized as a
// friend to GeometryState.
const geometry::QueryObject<double>& RgbdSensor::get_query_object(
const Context<double>& context) const {
return query_object_input_port().Eval<geometry::QueryObject<double>>(context);
}
RgbdSensorDiscrete::RgbdSensorDiscrete(std::unique_ptr<RgbdSensor> camera,
double period, bool render_label_image)
: camera_(camera.get()), period_(period) {
const auto& color_camera_info = camera->color_camera_info();
const auto& depth_camera_info = camera->depth_camera_info();
DiagramBuilder<double> builder;
builder.AddSystem(move(camera));
query_object_port_ =
builder.ExportInput(camera_->query_object_input_port(), "geometry_query");
// Color image.
const Value<ImageRgba8U> image_color(color_camera_info.width(),
color_camera_info.height());
const auto* const zoh_color =
builder.AddSystem<ZeroOrderHold>(period_, image_color);
builder.Connect(camera_->color_image_output_port(),
zoh_color->get_input_port());
output_port_color_image_ =
builder.ExportOutput(zoh_color->get_output_port(), "color_image");
// Depth images.
const Value<ImageDepth32F> image_depth_32F(depth_camera_info.width(),
depth_camera_info.height());
const auto* const zoh_depth_32F =
builder.AddSystem<ZeroOrderHold>(period_, image_depth_32F);
builder.Connect(camera_->depth_image_32F_output_port(),
zoh_depth_32F->get_input_port());
output_port_depth_image_32F_ =
builder.ExportOutput(zoh_depth_32F->get_output_port(), "depth_image_32f");
// Depth images.
const Value<ImageDepth16U> image_depth_16U(depth_camera_info.width(),
depth_camera_info.height());
const auto* const zoh_depth_16U =
builder.AddSystem<ZeroOrderHold>(period_, image_depth_16U);
builder.Connect(camera_->depth_image_16U_output_port(),
zoh_depth_16U->get_input_port());
output_port_depth_image_16U_ =
builder.ExportOutput(zoh_depth_16U->get_output_port(), "depth_image_16u");
// Label image.
if (render_label_image) {
const Value<ImageLabel16I> image_label(color_camera_info.width(),
color_camera_info.height());
const auto* const zoh_label =
builder.AddSystem<ZeroOrderHold>(period_, image_label);
builder.Connect(camera_->label_image_output_port(),
zoh_label->get_input_port());
output_port_label_image_ =
builder.ExportOutput(zoh_label->get_output_port(), "label_image");
}
// No need to place a ZOH on pose output.
X_WB_output_port_ = builder.ExportOutput(camera_->X_WB_output_port(), "X_WB");
builder.BuildInto(this);
}
} // namespace sensors
} // namespace systems
} // namespace drake