-
Notifications
You must be signed in to change notification settings - Fork 4.8k
/
Copy pathpointcloud.cpp
411 lines (360 loc) · 15.8 KB
/
pointcloud.cpp
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
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
#include "pointcloud.h"
#include "occlusion-filter.h"
#include <src/environment.h>
#include <src/core/depth-frame.h>
#include <src/option.h>
#include <src/device.h>
#include <src/stream.h>
#include <src/points.h>
#include <src/core/sensor-interface.h>
#include "device-calibration.h"
#include <librealsense2/rs.hpp>
#include <rsutils/string/from.h>
#ifdef RS2_USE_CUDA
#include "proc/cuda/cuda-pointcloud.h"
#endif
#ifdef __SSSE3__
#include "proc/sse/sse-pointcloud.h"
#endif
namespace librealsense
{
template<class MAP_DEPTH> void deproject_depth(float * points, const rs2_intrinsics & intrin, const uint16_t * depth, MAP_DEPTH map_depth)
{
for (int y = 0; y < intrin.height; ++y)
{
for (int x = 0; x < intrin.width; ++x)
{
const float pixel[] = { (float)x, (float)y };
rs2_deproject_pixel_to_point(points, &intrin, pixel, map_depth(*depth++));
points += 3;
}
}
}
const float3 * pointcloud::depth_to_points(rs2::points output,
const rs2_intrinsics &depth_intrinsics, const rs2::depth_frame& depth_frame)
{
auto image = output.get_vertices();
auto depth_scale = depth_frame.get_units();
deproject_depth((float*)image, depth_intrinsics, (const uint16_t*)depth_frame.get_data(), [depth_scale](uint16_t z) { return depth_scale * z; });
return (float3*)image;
}
float3 transform(const rs2_extrinsics *extrin, const float3 &point) { float3 p = {}; rs2_transform_point_to_point(&p.x, extrin, &point.x); return p; }
float2 project(const rs2_intrinsics *intrin, const float3 & point) { float2 pixel = {}; rs2_project_point_to_pixel(&pixel.x, intrin, &point.x); return pixel; }
float2 pixel_to_texcoord(const rs2_intrinsics *intrin, const float2 & pixel) { return{ pixel.x / (intrin->width), pixel.y / (intrin->height) }; }
float2 project_to_texcoord(const rs2_intrinsics *intrin, const float3 & point) { return pixel_to_texcoord(intrin, project(intrin, point)); }
void pointcloud::set_extrinsics()
{
if (_output_stream && _other_stream && !_extrinsics)
{
rs2_extrinsics ex;
const rs2_stream_profile* ds = _output_stream;
const rs2_stream_profile* os = _other_stream.get_profile();
if (environment::get_instance().get_extrinsics_graph().try_fetch_extrinsics(
*ds->profile, *os->profile, &ex))
{
_extrinsics = ex;
}
}
}
void pointcloud::inspect_depth_frame(const rs2::frame& depth)
{
if (!_output_stream || _depth_stream.get_profile().get() != depth.get_profile().get())
{
_output_stream = depth.get_profile().as<rs2::video_stream_profile>().clone(
RS2_STREAM_DEPTH, depth.get_profile().stream_index(), RS2_FORMAT_XYZ32F);
_depth_stream = depth;
_depth_intrinsics = optional_value<rs2_intrinsics>();
_depth_units = ((depth_frame*)depth.get())->get_units();
_extrinsics = optional_value<rs2_extrinsics>();
}
bool found_depth_intrinsics = false;
if (!_depth_intrinsics)
{
auto stream_profile = depth.get_profile();
if (auto video = stream_profile.as<rs2::video_stream_profile>())
{
_depth_intrinsics = video.get_intrinsics();
_pixels_map.resize(_depth_intrinsics->height*_depth_intrinsics->width);
_occlusion_filter->set_depth_intrinsics(_depth_intrinsics.value());
preprocess();
found_depth_intrinsics = true;
}
}
set_extrinsics();
}
template< class callback >
rs2_calibration_change_callback_sptr create_calibration_change_callback_ptr( callback&& cb )
{
return {
new rs2::calibration_change_callback< callback >( std::move( cb ) ),
[]( rs2_calibration_change_callback* p ) { p->release(); }
};
}
void pointcloud::inspect_other_frame(const rs2::frame& other)
{
if (_stream_filter != _prev_stream_filter)
{
_prev_stream_filter = _stream_filter;
if (!_registered_auto_calib_cb)
{
auto sensor = ((frame_interface*)other.get())->get_sensor();
if (sensor)
{
_registered_auto_calib_cb
= std::shared_ptr< pointcloud >( this, []( pointcloud * p ) {} );
auto dev = sensor->get_device().shared_from_this();
auto * d2r = dynamic_cast<calibration_change_device*>(dev.get());
if( d2r )
try
{
std::weak_ptr< pointcloud > wr{ _registered_auto_calib_cb };
auto fn = [=]( rs2_calibration_status status ) {
auto r = wr.lock();
if( ! r )
// nobody there any more!
return;
if( status == RS2_CALIBRATION_SUCCESSFUL )
{
stream_profile_interface *ds = nullptr, *os = nullptr;
for( size_t x = 0, N = dev->get_sensors_count(); x < N; ++x )
{
sensor_interface & s = dev->get_sensor( x );
for( auto const & sp : s.get_active_streams() )
{
if(( sp->get_stream_type() == RS2_STREAM_COLOR ) &&
( _stream_filter.stream == RS2_STREAM_COLOR ))
{
auto vspi = As< video_stream_profile_interface >(
sp.get() );
if( vspi )
{
os = vspi;
_other_intrinsics = vspi->get_intrinsics();
_occlusion_filter->set_texel_intrinsics(
_other_intrinsics.value() );
}
}
else if( sp->get_stream_type() == RS2_STREAM_DEPTH )
{
ds = sp.get();
}
}
}
if( ds && os )
{
rs2_extrinsics ex;
if( environment::get_instance()
.get_extrinsics_graph()
.try_fetch_extrinsics( *ds, *os, &ex ) )
_extrinsics = ex;
else
LOG_ERROR( "Failed to refresh extrinsics after calibration change" );
}
}
};
d2r->register_calibration_change_callback(
create_calibration_change_callback_ptr( std::move( fn ) ) );
}
catch( const std::bad_weak_ptr & )
{
LOG_WARNING( "Device destroyed" );
}
}
}
}
if (_extrinsics.has_value() && other.get_profile().get() == _other_stream.get_profile().get())
return;
_other_stream = other;
_other_intrinsics = optional_value<rs2_intrinsics>();
_extrinsics = optional_value<rs2_extrinsics>();
if (!_other_intrinsics)
{
auto stream_profile = _other_stream.get_profile();
if (auto video = stream_profile.as<rs2::video_stream_profile>())
{
_other_intrinsics = video.get_intrinsics();
_occlusion_filter->set_texel_intrinsics(_other_intrinsics.value());
}
}
set_extrinsics();
}
void pointcloud::get_texture_map(rs2::points output,
const float3* points,
const unsigned int width,
const unsigned int height,
const rs2_intrinsics &other_intrinsics,
const rs2_extrinsics& extr,
float2* pixels_ptr)
{
auto tex_ptr = (float2*)output.get_texture_coordinates();
for (unsigned int y = 0; y < height; ++y)
{
for (unsigned int x = 0; x < width; ++x)
{
if (points->z)
{
auto trans = transform(&extr, *points);
//auto tex_xy = project_to_texcoord(&mapped_intr, trans);
// Store intermediate results for poincloud filters
*pixels_ptr = project(&other_intrinsics, trans);
auto tex_xy = pixel_to_texcoord(&other_intrinsics, *pixels_ptr);
*tex_ptr = tex_xy;
}
else
{
*tex_ptr = { 0.f, 0.f };
*pixels_ptr = { 0.f, 0.f };
}
++points;
++tex_ptr;
++pixels_ptr;
}
}
}
rs2::points pointcloud::allocate_points(const rs2::frame_source& source, const rs2::frame& depth)
{
return source.allocate_points(_output_stream, depth);
}
rs2::frame pointcloud::process_depth_frame(const rs2::frame_source& source, const rs2::depth_frame& depth)
{
auto res = allocate_points(source, depth);
auto pframe = (librealsense::points*)(res.get());
const float3* points = depth_to_points(res, *_depth_intrinsics, depth);
auto vid_frame = depth.as<rs2::video_frame>();
// Pixels calculated in the mapped texture. Used in post-processing filters
float2* pixels_ptr = _pixels_map.data();
rs2_intrinsics mapped_intr;
rs2_extrinsics extr;
bool map_texture = false;
{
if (_extrinsics && _other_intrinsics)
{
mapped_intr = *_other_intrinsics;
extr = *_extrinsics;
map_texture = true;
}
}
if (map_texture)
{
auto height = vid_frame.get_height();
auto width = vid_frame.get_width();
get_texture_map(res, points, width, height, mapped_intr, extr, pixels_ptr);
if (run__occlusion_filter(extr))
{
if (_occlusion_filter->find_scanning_direction(extr) == vertical)
{
_occlusion_filter->set_scanning(static_cast<uint8_t>(vertical));
_occlusion_filter->_depth_units = _depth_units;
}
_occlusion_filter->process(pframe->get_vertices(), pframe->get_texture_coordinates(), _pixels_map, depth);
}
}
return res;
}
pointcloud::pointcloud()
: pointcloud("Pointcloud")
{}
pointcloud::pointcloud(const char* name)
: stream_filter_processing_block(name)
{
_occlusion_filter = std::make_shared<occlusion_filter>();
auto occlusion_invalidation = std::make_shared<ptr_option<uint8_t>>(
occlusion_none,
occlusion_max - 1, 1,
occlusion_monotonic_scan,
(uint8_t*)&_occlusion_filter->_occlusion_filter,
"Occlusion removal");
// Passing shared_ptr to capture list generates circular dependency and a memleak
auto occ_inv_weak = std::weak_ptr< ptr_option< uint8_t > >( occlusion_invalidation );
occlusion_invalidation->on_set( [this, occ_inv_weak]( float val )
{
auto occ_inv_shared = occ_inv_weak.lock();
if(!occ_inv_shared) return;
if( ! occ_inv_shared->is_valid( val ) )
throw invalid_value_exception( rsutils::string::from()
<< "Unsupported occlusion filtering mode requiested " << val
<< " is out of range." );
_occlusion_filter->set_mode(static_cast<uint8_t>(val));
});
occlusion_invalidation->set_description(1.f, "Off");
occlusion_invalidation->set_description(2.f, "On");
register_option(RS2_OPTION_FILTER_MAGNITUDE, occlusion_invalidation);
}
bool pointcloud::should_process(const rs2::frame& frame)
{
if (!frame)
return false;
auto set = frame.as<rs2::frameset>();
if (set)
{
//process composite frame only if it contains both a depth frame and the requested texture frame
if (_stream_filter.stream == RS2_STREAM_ANY)
return false;
auto tex = set.first_or_default(_stream_filter.stream, _stream_filter.format);
if (!tex)
return false;
auto depth = set.first_or_default(RS2_STREAM_DEPTH, RS2_FORMAT_Z16);
if (!depth)
return false;
}
else
{
auto p = frame.get_profile();
if (p.stream_type() == RS2_STREAM_DEPTH && p.format() == RS2_FORMAT_Z16)
return true;
if (p.stream_type() == _stream_filter.stream && p.format() == _stream_filter.format && p.stream_index() == _stream_filter.index)
return true;
return false;
//TODO: switch to this code when map_to api is removed
//if (_stream_filter != RS2_STREAM_ANY)
// return false;
//process single frame only if it is a depth frame
//if (frame.get_profile().stream_type() != RS2_STREAM_DEPTH || frame.get_profile().format() != RS2_FORMAT_Z16)
// return false;
}
return true;
}
rs2::frame pointcloud::process_frame(const rs2::frame_source& source, const rs2::frame& f)
{
rs2::frame rv;
if (auto composite = f.as<rs2::frameset>())
{
auto texture = composite.first(_stream_filter.stream);
inspect_other_frame(texture);
auto depth = composite.first(RS2_STREAM_DEPTH, RS2_FORMAT_Z16);
inspect_depth_frame(depth);
rv = process_depth_frame(source, depth);
}
else
{
if (f.is<rs2::depth_frame>())
{
inspect_depth_frame(f);
rv = process_depth_frame(source, f);
}
if (f.get_profile().stream_type() == _stream_filter.stream && f.get_profile().format() == _stream_filter.format)
{
inspect_other_frame(f);
}
}
return rv;
}
std::shared_ptr<pointcloud> pointcloud::create()
{
#ifdef RS2_USE_CUDA
return std::make_shared<librealsense::pointcloud_cuda>();
#else
#ifdef __SSSE3__
return std::make_shared<librealsense::pointcloud_sse>();
#else
return std::make_shared<librealsense::pointcloud>();
#endif
#endif
}
bool pointcloud::run__occlusion_filter(const rs2_extrinsics& extr)
{
return (_occlusion_filter->active() && !_occlusion_filter->is_same_sensor(extr));
}
}