-
Notifications
You must be signed in to change notification settings - Fork 4.8k
/
ds5-device.cpp
1334 lines (1122 loc) · 61.9 KB
/
ds5-device.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
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
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2016 Intel Corporation. All Rights Reserved.
#include <mutex>
#include <chrono>
#include <vector>
#include <iterator>
#include <string>
#include "device.h"
#include "context.h"
#include "image.h"
#include "metadata-parser.h"
#include "ds5-device.h"
#include "ds5-private.h"
#include "ds5-options.h"
#include "ds5-timestamp.h"
#include "stream.h"
#include "environment.h"
#include "ds5-color.h"
#include "ds5-nonmonochrome.h"
#include "proc/decimation-filter.h"
#include "proc/threshold.h"
#include "proc/disparity-transform.h"
#include "proc/spatial-filter.h"
#include "proc/colorizer.h"
#include "proc/temporal-filter.h"
#include "proc/y8i-to-y8y8.h"
#include "proc/y12i-to-y16y16.h"
#include "proc/color-formats-converter.h"
#include "proc/syncer-processing-block.h"
#include "proc/hole-filling-filter.h"
#include "proc/depth-formats-converter.h"
#include "proc/depth-decompress.h"
#include "proc/hdr-merge.h"
#include "proc/sequence-id-filter.h"
#include "hdr-config.h"
#include "ds5-thermal-monitor.h"
#include "../common/fw/firmware-version.h"
#include "fw-update/fw-update-unsigned.h"
#include "../third-party/json.hpp"
#ifdef HWM_OVER_XU
constexpr bool hw_mon_over_xu = true;
#else
constexpr bool hw_mon_over_xu = false;
#endif
namespace librealsense
{
std::map<uint32_t, rs2_format> ds5_depth_fourcc_to_rs2_format = {
{rs_fourcc('Y','U','Y','2'), RS2_FORMAT_YUYV},
{rs_fourcc('Y','U','Y','V'), RS2_FORMAT_YUYV},
{rs_fourcc('U','Y','V','Y'), RS2_FORMAT_UYVY},
{rs_fourcc('G','R','E','Y'), RS2_FORMAT_Y8},
{rs_fourcc('Y','8','I',' '), RS2_FORMAT_Y8I},
{rs_fourcc('W','1','0',' '), RS2_FORMAT_W10},
{rs_fourcc('Y','1','6',' '), RS2_FORMAT_Y16},
{rs_fourcc('Y','1','2','I'), RS2_FORMAT_Y12I},
{rs_fourcc('Z','1','6',' '), RS2_FORMAT_Z16},
{rs_fourcc('Z','1','6','H'), RS2_FORMAT_Z16H},
{rs_fourcc('R','G','B','2'), RS2_FORMAT_BGR8},
{rs_fourcc('M','J','P','G'), RS2_FORMAT_MJPEG},
{rs_fourcc('B','Y','R','2'), RS2_FORMAT_RAW16}
};
std::map<uint32_t, rs2_stream> ds5_depth_fourcc_to_rs2_stream = {
{rs_fourcc('Y','U','Y','2'), RS2_STREAM_COLOR},
{rs_fourcc('Y','U','Y','V'), RS2_STREAM_COLOR},
{rs_fourcc('U','Y','V','Y'), RS2_STREAM_INFRARED},
{rs_fourcc('G','R','E','Y'), RS2_STREAM_INFRARED},
{rs_fourcc('Y','8','I',' '), RS2_STREAM_INFRARED},
{rs_fourcc('W','1','0',' '), RS2_STREAM_INFRARED},
{rs_fourcc('Y','1','6',' '), RS2_STREAM_INFRARED},
{rs_fourcc('Y','1','2','I'), RS2_STREAM_INFRARED},
{rs_fourcc('R','G','B','2'), RS2_STREAM_INFRARED},
{rs_fourcc('Z','1','6',' '), RS2_STREAM_DEPTH},
{rs_fourcc('Z','1','6','H'), RS2_STREAM_DEPTH},
{rs_fourcc('B','Y','R','2'), RS2_STREAM_COLOR},
{rs_fourcc('M','J','P','G'), RS2_STREAM_COLOR}
};
ds5_auto_exposure_roi_method::ds5_auto_exposure_roi_method(
const hw_monitor& hwm,
ds::fw_cmd cmd)
: _hw_monitor(hwm), _cmd(cmd) {}
void ds5_auto_exposure_roi_method::set(const region_of_interest& roi)
{
command cmd(_cmd);
cmd.param1 = roi.min_y;
cmd.param2 = roi.max_y;
cmd.param3 = roi.min_x;
cmd.param4 = roi.max_x;
_hw_monitor.send(cmd);
}
region_of_interest ds5_auto_exposure_roi_method::get() const
{
region_of_interest roi;
command cmd(_cmd + 1);
auto res = _hw_monitor.send(cmd);
if (res.size() < 4 * sizeof(uint16_t))
{
throw std::runtime_error("Invalid result size!");
}
auto words = reinterpret_cast<uint16_t*>(res.data());
roi.min_y = words[0];
roi.max_y = words[1];
roi.min_x = words[2];
roi.max_x = words[3];
return roi;
}
std::vector<uint8_t> ds5_device::send_receive_raw_data(const std::vector<uint8_t>& input)
{
return _hw_monitor->send(input);
}
void ds5_device::hardware_reset()
{
command cmd(ds::HWRST);
_hw_monitor->send(cmd);
}
void ds5_device::enter_update_state() const
{
// Stop all data streaming/exchange pipes with HW
stop_activity();
using namespace std;
using namespace std::chrono;
try
{
LOG_INFO( "entering to update state, device disconnect is expected" );
command cmd( ds::DFU );
cmd.param1 = 1;
_hw_monitor->send( cmd );
// We allow 6 seconds because on Linux the removal status is updated at a 5 seconds rate.
const int MAX_ITERATIONS_FOR_DEVICE_DISCONNECTED_LOOP = (POLLING_DEVICES_INTERVAL_MS + 1000) / DELAY_FOR_RETRIES;
for( auto i = 0; i < MAX_ITERATIONS_FOR_DEVICE_DISCONNECTED_LOOP; i++ )
{
// If the device was detected as removed we assume the device is entering update mode
// Note: if no device status callback is registered we will wait the whole time and it is OK
if( ! is_valid() )
return;
this_thread::sleep_for( milliseconds( DELAY_FOR_RETRIES ) );
}
if (device_changed_notifications_on())
LOG_WARNING( "Timeout waiting for device disconnect after DFU command!" );
}
catch( std::exception & e )
{
LOG_WARNING( e.what() );
}
catch( ... )
{
LOG_ERROR( "Unknown error during entering DFU state" );
}
}
std::vector<uint8_t> ds5_device::backup_flash(update_progress_callback_ptr callback)
{
int flash_size = 1024 * 2048;
int max_bulk_size = 1016;
int max_iterations = int(flash_size / max_bulk_size + 1);
std::vector<uint8_t> flash;
flash.reserve(flash_size);
LOG_DEBUG("Flash backup started...");
uvc_sensor& raw_depth_sensor = get_raw_depth_sensor();
raw_depth_sensor.invoke_powered([&](platform::uvc_device& dev)
{
for (int i = 0; i < max_iterations; i++)
{
int offset = max_bulk_size * i;
int size = max_bulk_size;
if (i == max_iterations - 1)
{
size = flash_size - offset;
}
bool appended = false;
const int retries = 3;
for (int j = 0; j < retries && !appended; j++)
{
try
{
command cmd(ds::FRB);
cmd.param1 = offset;
cmd.param2 = size;
auto res = _hw_monitor->send(cmd);
flash.insert(flash.end(), res.begin(), res.end());
appended = true;
LOG_DEBUG("Flash backup - " << flash.size() << "/" << flash_size << " bytes downloaded");
}
catch (...)
{
if (i < retries - 1) std::this_thread::sleep_for(std::chrono::milliseconds(100));
else throw;
}
}
if (callback) callback->on_update_progress((float)i / max_iterations);
}
if (callback) callback->on_update_progress(1.0);
});
return flash;
}
void update_flash_section(std::shared_ptr<hw_monitor> hwm, const std::vector<uint8_t>& image, uint32_t offset, uint32_t size, update_progress_callback_ptr callback, float continue_from, float ratio)
{
size_t sector_count = size / ds::FLASH_SECTOR_SIZE;
size_t first_sector = offset / ds::FLASH_SECTOR_SIZE;
if (sector_count * ds::FLASH_SECTOR_SIZE != size)
sector_count++;
sector_count += first_sector;
for (auto sector_index = first_sector; sector_index < sector_count; sector_index++)
{
command cmdFES(ds::FES);
cmdFES.require_response = false;
cmdFES.param1 = (int)sector_index;
cmdFES.param2 = 1;
auto res = hwm->send(cmdFES);
for (int i = 0; i < ds::FLASH_SECTOR_SIZE; )
{
auto index = sector_index * ds::FLASH_SECTOR_SIZE + i;
if (index >= offset + size)
break;
int packet_size = std::min((int)(HW_MONITOR_COMMAND_SIZE - (i % HW_MONITOR_COMMAND_SIZE)), (int)(ds::FLASH_SECTOR_SIZE - i));
command cmdFWB(ds::FWB);
cmdFWB.require_response = false;
cmdFWB.param1 = (int)index;
cmdFWB.param2 = packet_size;
cmdFWB.data.assign(image.data() + index, image.data() + index + packet_size);
res = hwm->send(cmdFWB);
i += packet_size;
}
if (callback)
callback->on_update_progress(continue_from + (float)sector_index / (float)sector_count * ratio);
}
}
void update_section(std::shared_ptr<hw_monitor> hwm, const std::vector<uint8_t>& merged_image, flash_section fs, uint32_t tables_size,
update_progress_callback_ptr callback, float continue_from, float ratio)
{
auto first_table_offset = fs.tables.front().offset;
float total_size = float(fs.app_size + tables_size);
float app_ratio = fs.app_size / total_size * ratio;
float tables_ratio = tables_size / total_size * ratio;
update_flash_section(hwm, merged_image, fs.offset, fs.app_size, callback, continue_from, app_ratio);
update_flash_section(hwm, merged_image, first_table_offset, tables_size, callback, app_ratio, tables_ratio);
}
void update_flash_internal(std::shared_ptr<hw_monitor> hwm, const std::vector<uint8_t>& image, std::vector<uint8_t>& flash_backup, update_progress_callback_ptr callback, int update_mode)
{
auto flash_image_info = ds::get_flash_info(image);
auto flash_backup_info = ds::get_flash_info(flash_backup);
auto merged_image = merge_images(flash_backup_info, flash_image_info, image);
// update read-write section
auto first_table_offset = flash_image_info.read_write_section.tables.front().offset;
auto tables_size = flash_image_info.header.read_write_start_address + flash_image_info.header.read_write_size - first_table_offset;
update_section(hwm, merged_image, flash_image_info.read_write_section, tables_size, callback, 0, update_mode == RS2_UNSIGNED_UPDATE_MODE_READ_ONLY ? 0.5f : 1.0f);
if (update_mode == RS2_UNSIGNED_UPDATE_MODE_READ_ONLY)
{
// update read-only section
auto first_table_offset = flash_image_info.read_only_section.tables.front().offset;
auto tables_size = flash_image_info.header.read_only_start_address + flash_image_info.header.read_only_size - first_table_offset;
update_section(hwm, merged_image, flash_image_info.read_only_section, tables_size, callback, 0.5, 0.5);
}
}
void ds5_device::update_flash(const std::vector<uint8_t>& image, update_progress_callback_ptr callback, int update_mode)
{
if (_is_locked)
throw std::runtime_error("this camera is locked and doesn't allow direct flash write, for firmware update use rs2_update_firmware method (DFU)");
auto& raw_depth_sensor = get_raw_depth_sensor();
raw_depth_sensor.invoke_powered([&](platform::uvc_device& dev)
{
command cmdPFD(ds::PFD);
cmdPFD.require_response = false;
auto res = _hw_monitor->send(cmdPFD);
switch (update_mode)
{
case RS2_UNSIGNED_UPDATE_MODE_FULL:
update_flash_section(_hw_monitor, image, 0, ds::FLASH_SIZE, callback, 0, 1.0);
break;
case RS2_UNSIGNED_UPDATE_MODE_UPDATE:
case RS2_UNSIGNED_UPDATE_MODE_READ_ONLY:
{
auto flash_backup = backup_flash(nullptr);
update_flash_internal(_hw_monitor, image, flash_backup, callback, update_mode);
break;
}
default:
throw std::runtime_error("invalid update mode value");
}
if (callback) callback->on_update_progress(1.0);
command cmdHWRST(ds::HWRST);
res = _hw_monitor->send(cmdHWRST);
});
}
bool ds5_device::check_fw_compatibility(const std::vector<uint8_t>& image) const
{
std::string fw_version = extract_firmware_version_string((const void*)image.data(), image.size());
auto it = ds::device_to_fw_min_version.find(_pid);
if (it == ds::device_to_fw_min_version.end())
throw std::runtime_error("Minimum firmware version has not been defined for this device!");
return (firmware_version(fw_version) >= firmware_version(it->second));
}
class ds5_depth_sensor : public synthetic_sensor, public video_sensor_interface, public depth_stereo_sensor, public roi_sensor_base
{
public:
explicit ds5_depth_sensor(ds5_device* owner,
std::shared_ptr<uvc_sensor> uvc_sensor)
: synthetic_sensor(ds::DEPTH_STEREO, uvc_sensor, owner, ds5_depth_fourcc_to_rs2_format, ds5_depth_fourcc_to_rs2_stream),
_owner(owner),
_depth_units(-1),
_hdr_cfg(nullptr)
{ }
processing_blocks get_recommended_processing_blocks() const override
{
return get_ds5_depth_recommended_proccesing_blocks();
};
rs2_intrinsics get_intrinsics(const stream_profile& profile) const override
{
rs2_intrinsics result;
if (ds::try_get_intrinsic_by_resolution_new(*_owner->_new_calib_table_raw,
profile.width, profile.height, &result))
{
return result;
}
else
{
return get_intrinsic_by_resolution(
*_owner->_coefficients_table_raw,
ds::calibration_table_id::coefficients_table_id,
profile.width, profile.height);
}
}
void open(const stream_profiles& requests) override
{
_depth_units = get_option(RS2_OPTION_DEPTH_UNITS).query();
synthetic_sensor::open(requests);
// needed in order to restore the HDR sub-preset when streaming is turned off and on
if (_hdr_cfg && _hdr_cfg->is_enabled())
get_option(RS2_OPTION_HDR_ENABLED).set(1.f);
// Activate Thermal Compensation tracking
if (supports_option(RS2_OPTION_THERMAL_COMPENSATION))
_owner->_thermal_monitor->update(true);
}
void close() override
{
// Deactivate Thermal Compensation tracking
if (supports_option(RS2_OPTION_THERMAL_COMPENSATION))
_owner->_thermal_monitor->update(false);
synthetic_sensor::close();
}
rs2_intrinsics get_color_intrinsics(const stream_profile& profile) const
{
return get_intrinsic_by_resolution(
*_owner->_color_calib_table_raw,
ds::calibration_table_id::rgb_calibration_id,
profile.width, profile.height);
}
/*
Infrared profiles are initialized with the following logic:
- If device has color sensor (D415 / D435), infrared profile is chosen with Y8 format
- If device does not have color sensor:
* if it is a rolling shutter device (D400 / D410 / D415 / D405), infrared profile is chosen with RGB8 format
* for other devices (D420 / D430), infrared profile is chosen with Y8 format
*/
stream_profiles init_stream_profiles() override
{
auto lock = environment::get_instance().get_extrinsics_graph().lock();
auto&& results = synthetic_sensor::init_stream_profiles();
for (auto&& p : results)
{
// Register stream types
if (p->get_stream_type() == RS2_STREAM_DEPTH)
{
assign_stream(_owner->_depth_stream, p);
}
else if (p->get_stream_type() == RS2_STREAM_INFRARED && p->get_stream_index() < 2)
{
assign_stream(_owner->_left_ir_stream, p);
}
else if (p->get_stream_type() == RS2_STREAM_INFRARED && p->get_stream_index() == 2)
{
assign_stream(_owner->_right_ir_stream, p);
}
else if (p->get_stream_type() == RS2_STREAM_COLOR)
{
assign_stream(_owner->_color_stream, p);
}
auto&& vid_profile = dynamic_cast<video_stream_profile_interface*>(p.get());
// used when color stream comes from depth sensor (as in D405)
if (p->get_stream_type() == RS2_STREAM_COLOR)
{
const auto&& profile = to_profile(p.get());
std::weak_ptr<ds5_depth_sensor> wp =
std::dynamic_pointer_cast<ds5_depth_sensor>(this->shared_from_this());
vid_profile->set_intrinsics([profile, wp]()
{
auto sp = wp.lock();
if (sp)
return sp->get_color_intrinsics(profile);
else
return rs2_intrinsics{};
});
}
// Register intrinsics
else if (p->get_format() != RS2_FORMAT_Y16) // Y16 format indicate unrectified images, no intrinsics are available for these
{
const auto&& profile = to_profile(p.get());
std::weak_ptr<ds5_depth_sensor> wp =
std::dynamic_pointer_cast<ds5_depth_sensor>(this->shared_from_this());
vid_profile->set_intrinsics([profile, wp]()
{
auto sp = wp.lock();
if (sp)
return sp->get_intrinsics(profile);
else
return rs2_intrinsics{};
});
}
}
return results;
}
float get_depth_scale() const override
{
if (_depth_units < 0)
_depth_units = get_option(RS2_OPTION_DEPTH_UNITS).query();
return _depth_units;
}
void set_depth_scale(float val){ _depth_units = val; }
void init_hdr_config(const option_range& exposure_range, const option_range& gain_range)
{
_hdr_cfg = std::make_shared<hdr_config>(*(_owner->_hw_monitor), get_raw_sensor(),
exposure_range, gain_range);
}
std::shared_ptr<hdr_config> get_hdr_config() { return _hdr_cfg; }
float get_stereo_baseline_mm() const override { return _owner->get_stereo_baseline_mm(); }
void create_snapshot(std::shared_ptr<depth_sensor>& snapshot) const override
{
snapshot = std::make_shared<depth_sensor_snapshot>(get_depth_scale());
}
void create_snapshot(std::shared_ptr<depth_stereo_sensor>& snapshot) const override
{
snapshot = std::make_shared<depth_stereo_sensor_snapshot>(get_depth_scale(), get_stereo_baseline_mm());
}
void enable_recording(std::function<void(const depth_sensor&)> recording_function) override
{
//does not change over time
}
void enable_recording(std::function<void(const depth_stereo_sensor&)> recording_function) override
{
//does not change over time
}
float get_preset_max_value() const override
{
float preset_max_value = RS2_RS400_VISUAL_PRESET_COUNT - 1;
switch (_owner->_pid)
{
case ds::RS400_PID:
case ds::RS410_PID:
case ds::RS415_PID:
case ds::RS465_PID:
case ds::RS460_PID:
preset_max_value = static_cast<float>(RS2_RS400_VISUAL_PRESET_REMOVE_IR_PATTERN);
break;
default:
preset_max_value = static_cast<float>(RS2_RS400_VISUAL_PRESET_MEDIUM_DENSITY);
}
return preset_max_value;
}
protected:
const ds5_device* _owner;
mutable std::atomic<float> _depth_units;
float _stereo_baseline_mm;
std::shared_ptr<hdr_config> _hdr_cfg;
};
class ds5u_depth_sensor : public ds5_depth_sensor
{
public:
explicit ds5u_depth_sensor(ds5u_device* owner,
std::shared_ptr<uvc_sensor> uvc_sensor)
: ds5_depth_sensor(owner, uvc_sensor), _owner(owner)
{}
stream_profiles init_stream_profiles() override
{
auto lock = environment::get_instance().get_extrinsics_graph().lock();
auto&& results = synthetic_sensor::init_stream_profiles();
for (auto&& p : results)
{
// Register stream types
if (p->get_stream_type() == RS2_STREAM_DEPTH)
{
assign_stream(_owner->_depth_stream, p);
}
else if (p->get_stream_type() == RS2_STREAM_INFRARED && p->get_stream_index() < 2)
{
assign_stream(_owner->_left_ir_stream, p);
}
else if (p->get_stream_type() == RS2_STREAM_INFRARED && p->get_stream_index() == 2)
{
assign_stream(_owner->_right_ir_stream, p);
}
else if (p->get_stream_type() == RS2_STREAM_COLOR)
{
assign_stream(_owner->_color_stream, p);
}
auto&& video = dynamic_cast<video_stream_profile_interface*>(p.get());
// Register intrinsics
if (p->get_format() != RS2_FORMAT_Y16) // Y16 format indicate unrectified images, no intrinsics are available for these
{
const auto&& profile = to_profile(p.get());
std::weak_ptr<ds5_depth_sensor> wp = std::dynamic_pointer_cast<ds5_depth_sensor>(this->shared_from_this());
video->set_intrinsics([profile, wp]()
{
auto sp = wp.lock();
if (sp)
return sp->get_intrinsics(profile);
else
return rs2_intrinsics{};
});
}
}
return results;
}
private:
const ds5u_device* _owner;
};
bool ds5_device::is_camera_in_advanced_mode() const
{
command cmd(ds::UAMG);
assert(_hw_monitor);
auto ret = _hw_monitor->send(cmd);
if (ret.empty())
throw invalid_value_exception("command result is empty!");
return (0 != ret.front());
}
float ds5_device::get_stereo_baseline_mm() const
{
using namespace ds;
auto table = check_calib<coefficients_table>(*_coefficients_table_raw);
return fabs(table->baseline);
}
std::vector<uint8_t> ds5_device::get_raw_calibration_table(ds::calibration_table_id table_id) const
{
command cmd(ds::GETINTCAL, table_id);
return _hw_monitor->send(cmd);
}
std::vector<uint8_t> ds5_device::get_new_calibration_table() const
{
if (_fw_version >= firmware_version("5.11.9.5"))
{
command cmd(ds::RECPARAMSGET);
return _hw_monitor->send(cmd);
}
return {};
}
ds::d400_caps ds5_device::parse_device_capabilities() const
{
using namespace ds;
std::array<unsigned char,HW_MONITOR_BUFFER_SIZE> gvd_buf;
_hw_monitor->get_gvd(gvd_buf.size(), gvd_buf.data(), GVD);
// Opaque retrieval
d400_caps val{d400_caps::CAP_UNDEFINED};
if (gvd_buf[active_projector]) // DepthActiveMode
val |= d400_caps::CAP_ACTIVE_PROJECTOR;
if (gvd_buf[rgb_sensor]) // WithRGB
val |= d400_caps::CAP_RGB_SENSOR;
if (gvd_buf[imu_sensor])
{
val |= d400_caps::CAP_IMU_SENSOR;
if (gvd_buf[imu_acc_chip_id] == I2C_IMU_BMI055_ID_ACC)
val |= d400_caps::CAP_BMI_055;
else if (gvd_buf[imu_acc_chip_id] == I2C_IMU_BMI085_ID_ACC)
val |= d400_caps::CAP_BMI_085;
else if (hid_bmi_055_pid.end() != hid_bmi_055_pid.find(_pid))
val |= d400_caps::CAP_BMI_055;
else if (hid_bmi_085_pid.end() != hid_bmi_085_pid.find(_pid))
val |= d400_caps::CAP_BMI_085;
else
LOG_WARNING("The IMU sensor is undefined for PID " << std::hex << _pid << " and imu_chip_id: " << gvd_buf[imu_acc_chip_id] << std::dec);
}
if (0xFF != (gvd_buf[fisheye_sensor_lb] & gvd_buf[fisheye_sensor_hb]))
val |= d400_caps::CAP_FISHEYE_SENSOR;
if (0x1 == gvd_buf[depth_sensor_type])
val |= d400_caps::CAP_ROLLING_SHUTTER; // e.g. ASRC
if (0x2 == gvd_buf[depth_sensor_type])
val |= d400_caps::CAP_GLOBAL_SHUTTER; // e.g. AWGC
// Option INTER_CAM_SYNC_MODE is not enabled in D405
if (_pid != ds::RS405_PID)
val |= d400_caps::CAP_INTERCAM_HW_SYNC;
return val;
}
std::shared_ptr<synthetic_sensor> ds5_device::create_depth_device(std::shared_ptr<context> ctx,
const std::vector<platform::uvc_device_info>& all_device_infos)
{
using namespace ds;
auto&& backend = ctx->get_backend();
std::vector<std::shared_ptr<platform::uvc_device>> depth_devices;
for (auto&& info : filter_by_mi(all_device_infos, 0)) // Filter just mi=0, DEPTH
depth_devices.push_back(backend.create_uvc_device(info));
std::unique_ptr<frame_timestamp_reader> timestamp_reader_backup(new ds5_timestamp_reader(backend.create_time_service()));
std::unique_ptr<frame_timestamp_reader> timestamp_reader_metadata(new ds5_timestamp_reader_from_metadata(std::move(timestamp_reader_backup)));
auto enable_global_time_option = std::shared_ptr<global_time_option>(new global_time_option());
auto raw_depth_ep = std::make_shared<uvc_sensor>("Raw Depth Sensor", std::make_shared<platform::multi_pins_uvc_device>(depth_devices),
std::unique_ptr<frame_timestamp_reader>(new global_timestamp_reader(std::move(timestamp_reader_metadata), _tf_keeper, enable_global_time_option)), this);
raw_depth_ep->register_xu(depth_xu); // make sure the XU is initialized every time we power the camera
auto depth_ep = std::make_shared<ds5_depth_sensor>(this, raw_depth_ep);
depth_ep->register_info(RS2_CAMERA_INFO_PHYSICAL_PORT, filter_by_mi(all_device_infos, 0).front().device_path);
depth_ep->register_option(RS2_OPTION_GLOBAL_TIME_ENABLED, enable_global_time_option);
depth_ep->register_processing_block(processing_block_factory::create_id_pbf(RS2_FORMAT_Y8, RS2_STREAM_INFRARED, 1));
depth_ep->register_processing_block(processing_block_factory::create_id_pbf(RS2_FORMAT_Z16, RS2_STREAM_DEPTH));
depth_ep->register_processing_block({ {RS2_FORMAT_W10} }, { {RS2_FORMAT_RAW10, RS2_STREAM_INFRARED, 1} }, []() { return std::make_shared<w10_converter>(RS2_FORMAT_RAW10); });
depth_ep->register_processing_block({ {RS2_FORMAT_W10} }, { {RS2_FORMAT_Y10BPACK, RS2_STREAM_INFRARED, 1} }, []() { return std::make_shared<w10_converter>(RS2_FORMAT_Y10BPACK); });
return depth_ep;
}
ds5_device::ds5_device(std::shared_ptr<context> ctx,
const platform::backend_device_group& group)
: device(ctx, group), global_time_interface(),
auto_calibrated(_hw_monitor),
_device_capabilities(ds::d400_caps::CAP_UNDEFINED),
_depth_stream(new stream(RS2_STREAM_DEPTH)),
_left_ir_stream(new stream(RS2_STREAM_INFRARED, 1)),
_right_ir_stream(new stream(RS2_STREAM_INFRARED, 2)),
_color_stream(nullptr)
{
_depth_device_idx = add_sensor(create_depth_device(ctx, group.uvc_devices));
init(ctx, group);
}
void ds5_device::init(std::shared_ptr<context> ctx,
const platform::backend_device_group& group)
{
using namespace ds;
auto&& backend = ctx->get_backend();
auto& raw_sensor = get_raw_depth_sensor();
auto pid = group.uvc_devices.front().pid;
_color_calib_table_raw = [this]()
{
return get_raw_calibration_table(rgb_calibration_id);
};
if (((hw_mon_over_xu) && (RS400_IMU_PID != pid)) || (!group.usb_devices.size()))
{
_hw_monitor = std::make_shared<hw_monitor>(
std::make_shared<locked_transfer>(
std::make_shared<command_transfer_over_xu>(
raw_sensor, depth_xu, DS5_HWMONITOR),
raw_sensor));
}
else
{
_hw_monitor = std::make_shared<hw_monitor>(
std::make_shared<locked_transfer>(
backend.create_usb_device(group.usb_devices.front()), raw_sensor));
}
// Define Left-to-Right extrinsics calculation (lazy)
// Reference CS - Right-handed; positive [X,Y,Z] point to [Left,Up,Forward] accordingly.
_left_right_extrinsics = std::make_shared<lazy<rs2_extrinsics>>([this]()
{
rs2_extrinsics ext = identity_matrix();
auto table = check_calib<coefficients_table>(*_coefficients_table_raw);
ext.translation[0] = 0.001f * table->baseline; // mm to meters
return ext;
});
environment::get_instance().get_extrinsics_graph().register_same_extrinsics(*_depth_stream, *_left_ir_stream);
environment::get_instance().get_extrinsics_graph().register_extrinsics(*_depth_stream, *_right_ir_stream, _left_right_extrinsics);
register_stream_to_extrinsic_group(*_depth_stream, 0);
register_stream_to_extrinsic_group(*_left_ir_stream, 0);
register_stream_to_extrinsic_group(*_right_ir_stream, 0);
_coefficients_table_raw = [this]() { return get_raw_calibration_table(coefficients_table_id); };
_new_calib_table_raw = [this]() { return get_new_calibration_table(); };
_pid = group.uvc_devices.front().pid;
std::string device_name = (rs400_sku_names.end() != rs400_sku_names.find(_pid)) ? rs400_sku_names.at(_pid) : "RS4xx";
std::vector<uint8_t> gvd_buff(HW_MONITOR_BUFFER_SIZE);
_hw_monitor->get_gvd(gvd_buff.size(), gvd_buff.data(), GVD);
auto optic_serial = _hw_monitor->get_module_serial_string(gvd_buff, module_serial_offset);
auto asic_serial = _hw_monitor->get_module_serial_string(gvd_buff, module_asic_serial_offset);
auto fwv = _hw_monitor->get_firmware_version_string(gvd_buff, camera_fw_version_offset);
_fw_version = firmware_version(fwv);
_recommended_fw_version = firmware_version(D4XX_RECOMMENDED_FIRMWARE_VERSION);
if (_fw_version >= firmware_version("5.10.4.0"))
_device_capabilities = parse_device_capabilities();
auto& depth_sensor = get_depth_sensor();
auto& raw_depth_sensor = get_raw_depth_sensor();
auto advanced_mode = is_camera_in_advanced_mode();
using namespace platform;
auto _usb_mode = usb3_type;
std::string usb_type_str(usb_spec_names.at(_usb_mode));
bool usb_modality = (_fw_version >= firmware_version("5.9.8.0"));
if (usb_modality)
{
_usb_mode = raw_depth_sensor.get_usb_specification();
if (usb_spec_names.count(_usb_mode) && (usb_undefined != _usb_mode))
usb_type_str = usb_spec_names.at(_usb_mode);
else // Backend fails to provide USB descriptor - occurs with RS3 build. Requires further work
usb_modality = false;
}
if (_fw_version >= firmware_version("5.12.1.1"))
{
depth_sensor.register_processing_block(processing_block_factory::create_id_pbf(RS2_FORMAT_Z16H, RS2_STREAM_DEPTH));
}
depth_sensor.register_processing_block(
{ {RS2_FORMAT_Y8I} },
{ {RS2_FORMAT_Y8, RS2_STREAM_INFRARED, 1} , {RS2_FORMAT_Y8, RS2_STREAM_INFRARED, 2} },
[]() { return std::make_shared<y8i_to_y8y8>(); }
); // L+R
depth_sensor.register_processing_block(
{ RS2_FORMAT_Y12I },
{ {RS2_FORMAT_Y16, RS2_STREAM_INFRARED, 1}, {RS2_FORMAT_Y16, RS2_STREAM_INFRARED, 2} },
[]() {return std::make_shared<y12i_to_y16y16>(); }
);
auto pid_hex_str = hexify(_pid);
if ((_pid == RS416_PID || _pid == RS416_RGB_PID) && _fw_version >= firmware_version("5.12.0.1"))
{
depth_sensor.register_option(RS2_OPTION_HARDWARE_PRESET,
std::make_shared<uvc_xu_option<uint8_t>>(raw_depth_sensor, depth_xu, DS5_HARDWARE_PRESET,
"Hardware pipe configuration"));
depth_sensor.register_option(RS2_OPTION_LED_POWER,
std::make_shared<uvc_xu_option<uint16_t>>(raw_depth_sensor, depth_xu, DS5_LED_PWR,
"Set the power level of the LED, with 0 meaning LED off"));
}
if (_fw_version >= firmware_version("5.6.3.0"))
{
_is_locked = _hw_monitor->is_camera_locked(GVD, is_camera_locked_offset);
}
if (_fw_version >= firmware_version("5.5.8.0"))
{
depth_sensor.register_option(RS2_OPTION_OUTPUT_TRIGGER_ENABLED,
std::make_shared<uvc_xu_option<uint8_t>>(raw_depth_sensor, depth_xu, DS5_EXT_TRIGGER,
"Generate trigger from the camera to external device once per frame"));
auto error_control = std::make_shared<uvc_xu_option<uint8_t>>(raw_depth_sensor, depth_xu, DS5_ERROR_REPORTING, "Error reporting");
_polling_error_handler = std::make_shared<polling_error_handler>(1000,
error_control,
raw_depth_sensor.get_notifications_processor(),
std::make_shared<ds5_notification_decoder>());
depth_sensor.register_option(RS2_OPTION_ERROR_POLLING_ENABLED, std::make_shared<polling_errors_disable>(_polling_error_handler));
depth_sensor.register_option(RS2_OPTION_ASIC_TEMPERATURE,
std::make_shared<asic_and_projector_temperature_options>(raw_depth_sensor,
RS2_OPTION_ASIC_TEMPERATURE));
}
if ((val_in_range(pid, { RS455_PID })) && (_fw_version >= firmware_version("5.12.11.0")))
{
auto thermal_compensation_toggle = std::make_shared<protected_xu_option<uint8_t>>(raw_depth_sensor, depth_xu,
ds::DS5_THERMAL_COMPENSATION, "Toggle Thermal Compensation Mechanism");
auto temperature_sensor = depth_sensor.get_option_handler(RS2_OPTION_ASIC_TEMPERATURE);
_thermal_monitor = std::make_shared<ds5_thermal_monitor>(temperature_sensor, thermal_compensation_toggle);
depth_sensor.register_option(RS2_OPTION_THERMAL_COMPENSATION,
std::make_shared<thermal_compensation>(_thermal_monitor,thermal_compensation_toggle));
}
// minimal firmware version in which hdr feature is supported
firmware_version hdr_firmware_version("5.12.8.100");
std::shared_ptr<option> exposure_option = nullptr;
std::shared_ptr<option> gain_option = nullptr;
std::shared_ptr<hdr_option> hdr_enabled_option = nullptr;
//EXPOSURE AND GAIN - preparing uvc options
auto uvc_xu_exposure_option = std::make_shared<uvc_xu_option<uint32_t>>(raw_depth_sensor,
depth_xu,
DS5_EXPOSURE,
"Depth Exposure (usec)");
option_range exposure_range = uvc_xu_exposure_option->get_range();
auto uvc_pu_gain_option = std::make_shared<uvc_pu_option>(raw_depth_sensor, RS2_OPTION_GAIN);
option_range gain_range = uvc_pu_gain_option->get_range();
//AUTO EXPOSURE
auto enable_auto_exposure = std::make_shared<uvc_xu_option<uint8_t>>(raw_depth_sensor,
depth_xu,
DS5_ENABLE_AUTO_EXPOSURE,
"Enable Auto Exposure");
depth_sensor.register_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, enable_auto_exposure);
// register HDR options
//auto global_shutter_mask = d400_caps::CAP_GLOBAL_SHUTTER;
if ((_fw_version >= hdr_firmware_version))// && ((_device_capabilities & global_shutter_mask) == global_shutter_mask) )
{
auto ds5_depth = As<ds5_depth_sensor, synthetic_sensor>(&get_depth_sensor());
ds5_depth->init_hdr_config(exposure_range, gain_range);
auto&& hdr_cfg = ds5_depth->get_hdr_config();
// values from 4 to 14 - for internal use
// value 15 - saved for emiter on off subpreset
option_range hdr_id_range = { 0.f /*min*/, 3.f /*max*/, 1.f /*step*/, 1.f /*default*/ };
auto hdr_id_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_SEQUENCE_NAME, hdr_id_range,
std::map<float, std::string>{ {0.f, "0"}, { 1.f, "1" }, { 2.f, "2" }, { 3.f, "3" } });
depth_sensor.register_option(RS2_OPTION_SEQUENCE_NAME, hdr_id_option);
option_range hdr_sequence_size_range = { 2.f /*min*/, 2.f /*max*/, 1.f /*step*/, 2.f /*default*/ };
auto hdr_sequence_size_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_SEQUENCE_SIZE, hdr_sequence_size_range,
std::map<float, std::string>{ { 2.f, "2" } });
depth_sensor.register_option(RS2_OPTION_SEQUENCE_SIZE, hdr_sequence_size_option);
option_range hdr_sequ_id_range = { 0.f /*min*/, 2.f /*max*/, 1.f /*step*/, 0.f /*default*/ };
auto hdr_sequ_id_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_SEQUENCE_ID, hdr_sequ_id_range,
std::map<float, std::string>{ {0.f, "UVC"}, { 1.f, "1" }, { 2.f, "2" } });
depth_sensor.register_option(RS2_OPTION_SEQUENCE_ID, hdr_sequ_id_option);
option_range hdr_enable_range = { 0.f /*min*/, 1.f /*max*/, 1.f /*step*/, 0.f /*default*/ };
hdr_enabled_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_HDR_ENABLED, hdr_enable_range);
depth_sensor.register_option(RS2_OPTION_HDR_ENABLED, hdr_enabled_option);
//EXPOSURE AND GAIN - preparing hdr options
auto hdr_exposure_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_EXPOSURE, exposure_range);
auto hdr_gain_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_GAIN, gain_range);
//EXPOSURE AND GAIN - preparing hybrid options
auto hdr_conditional_exposure_option = std::make_shared<hdr_conditional_option>(hdr_cfg, uvc_xu_exposure_option, hdr_exposure_option);
auto hdr_conditional_gain_option = std::make_shared<hdr_conditional_option>(hdr_cfg, uvc_pu_gain_option, hdr_gain_option);
exposure_option = hdr_conditional_exposure_option;
gain_option = hdr_conditional_gain_option;
std::vector<std::pair<std::shared_ptr<option>, std::string>> options_and_reasons = { std::make_pair(hdr_enabled_option,
"Auto Exposure cannot be set while HDR is enabled") };
depth_sensor.register_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE,
std::make_shared<gated_option>(
enable_auto_exposure,
options_and_reasons));
}
else
{
exposure_option = uvc_xu_exposure_option;
gain_option = uvc_pu_gain_option;
}
//EXPOSURE
depth_sensor.register_option(RS2_OPTION_EXPOSURE,
std::make_shared<auto_disabling_control>(
exposure_option,
enable_auto_exposure));
//GAIN
depth_sensor.register_option(RS2_OPTION_GAIN,
std::make_shared<auto_disabling_control>(
gain_option,
enable_auto_exposure));
// Alternating laser pattern is applicable for global shutter/active SKUs
auto mask = d400_caps::CAP_GLOBAL_SHUTTER | d400_caps::CAP_ACTIVE_PROJECTOR;
// Alternating laser pattern should be set and query in a different way according to the firmware version
if ((_fw_version >= firmware_version("5.11.3.0")) && ((_device_capabilities & mask) == mask))
{
bool is_fw_version_using_id = (_fw_version >= firmware_version("5.12.8.100"));
auto alternating_emitter_opt = std::make_shared<alternating_emitter_option>(*_hw_monitor, &raw_depth_sensor, is_fw_version_using_id);
auto emitter_always_on_opt = std::make_shared<emitter_always_on_option>(*_hw_monitor, &depth_sensor);
if ((_fw_version >= firmware_version("5.12.1.0")) && ((_device_capabilities & d400_caps::CAP_GLOBAL_SHUTTER) == d400_caps::CAP_GLOBAL_SHUTTER))
{
std::vector<std::pair<std::shared_ptr<option>, std::string>> options_and_reasons = { std::make_pair(alternating_emitter_opt,
"Emitter always ON cannot be set while Emitter ON/OFF is enabled") };
depth_sensor.register_option(RS2_OPTION_EMITTER_ALWAYS_ON,
std::make_shared<gated_option>(
emitter_always_on_opt,
options_and_reasons));
}
if (_fw_version >= hdr_firmware_version)
{
std::vector<std::pair<std::shared_ptr<option>, std::string>> options_and_reasons = { std::make_pair(hdr_enabled_option, "Emitter ON/OFF cannot be set while HDR is enabled"),
std::make_pair(emitter_always_on_opt, "Emitter ON/OFF cannot be set while Emitter always ON is enabled") };
depth_sensor.register_option(RS2_OPTION_EMITTER_ON_OFF,
std::make_shared<gated_option>(
alternating_emitter_opt,
options_and_reasons
));
}
else if ((_fw_version >= firmware_version("5.12.1.0")) && ((_device_capabilities & d400_caps::CAP_GLOBAL_SHUTTER) == d400_caps::CAP_GLOBAL_SHUTTER))
{
std::vector<std::pair<std::shared_ptr<option>, std::string>> options_and_reasons = { std::make_pair(emitter_always_on_opt,
"Emitter ON/OFF cannot be set while Emitter always ON is enabled") };
depth_sensor.register_option(RS2_OPTION_EMITTER_ON_OFF,
std::make_shared<gated_option>(
alternating_emitter_opt,
options_and_reasons));
}
else
{
depth_sensor.register_option(RS2_OPTION_EMITTER_ON_OFF, alternating_emitter_opt);
}
}