forked from IntelRealSense/librealsense
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathsensor.cpp
1562 lines (1334 loc) · 59.3 KB
/
sensor.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) 2015 Intel Corporation. All Rights Reserved.
#include "sensor.h"
#include <array>
#include <set>
#include <unordered_set>
#include <iomanip>
#include "source.h"
#include "device.h"
#include "stream.h"
#include "metadata.h"
#include "proc/synthetic-stream.h"
#include "proc/decimation-filter.h"
#include "proc/depth-decompress.h"
#include "global_timestamp_reader.h"
namespace librealsense
{
//////////////////////////////////////////////////////
/////////////////// Sensor Base //////////////////////
//////////////////////////////////////////////////////
sensor_base::sensor_base(std::string name, device* dev,
recommended_proccesing_blocks_interface* owner)
: recommended_proccesing_blocks_base(owner),
_is_streaming(false),
_is_opened(false),
_notifications_processor(std::shared_ptr<notifications_processor>(new notifications_processor())),
_on_open(nullptr),
_metadata_parsers(std::make_shared<metadata_parser_map>()),
_owner(dev),
_profiles([this]() {
auto profiles = this->init_stream_profiles();
_owner->tag_profiles(profiles);
return profiles;
})
{
register_option(RS2_OPTION_FRAMES_QUEUE_SIZE, _source.get_published_size_option());
register_metadata(RS2_FRAME_METADATA_TIME_OF_ARRIVAL, std::make_shared<librealsense::md_time_of_arrival_parser>());
register_info(RS2_CAMERA_INFO_NAME, name);
}
const std::string& sensor_base::get_info(rs2_camera_info info) const
{
if (info_container::supports_info(info)) return info_container::get_info(info);
else return _owner->get_info(info);
}
bool sensor_base::supports_info(rs2_camera_info info) const
{
return info_container::supports_info(info) || _owner->supports_info(info);
}
stream_profiles sensor_base::get_active_streams() const
{
std::lock_guard<std::mutex> lock(_active_profile_mutex);
return _active_profiles;
}
void sensor_base::register_notifications_callback(notifications_callback_ptr callback)
{
if (supports_option(RS2_OPTION_ERROR_POLLING_ENABLED))
{
auto&& opt = get_option(RS2_OPTION_ERROR_POLLING_ENABLED);
opt.set(1.0f);
}
_notifications_processor->set_callback(std::move(callback));
}
notifications_callback_ptr sensor_base::get_notifications_callback() const
{
return _notifications_processor->get_callback();
}
int sensor_base::register_before_streaming_changes_callback(std::function<void(bool)> callback)
{
int token = (on_before_streaming_changes += callback);
LOG_DEBUG("Registered token #" << token << " to \"on_before_streaming_changes\"");
return token;
}
void sensor_base::unregister_before_start_callback(int token)
{
bool successful_unregister = on_before_streaming_changes -= token;
if (!successful_unregister)
{
LOG_WARNING("Failed to unregister token #" << token << " from \"on_before_streaming_changes\"");
}
}
frame_callback_ptr sensor_base::get_frames_callback() const
{
return _source.get_callback();
}
void sensor_base::set_frames_callback(frame_callback_ptr callback)
{
return _source.set_callback(callback);
}
bool sensor_base::is_streaming() const
{
return _is_streaming;
}
bool sensor_base::is_opened() const
{
return _is_opened;
}
std::shared_ptr<notifications_processor> sensor_base::get_notifications_processor() const
{
return _notifications_processor;
}
void sensor_base::register_metadata(rs2_frame_metadata_value metadata, std::shared_ptr<md_attribute_parser_base> metadata_parser) const
{
if (_metadata_parsers.get()->end() != _metadata_parsers.get()->find(metadata))
throw invalid_value_exception(to_string() << "Metadata attribute parser for " << rs2_frame_metadata_to_string(metadata)
<< " is already defined");
_metadata_parsers.get()->insert(std::pair<rs2_frame_metadata_value, std::shared_ptr<md_attribute_parser_base>>(metadata, metadata_parser));
}
std::shared_ptr<std::map<uint32_t, rs2_format>>& sensor_base::get_fourcc_to_rs2_format_map()
{
return _fourcc_to_rs2_format;
}
std::shared_ptr<std::map<uint32_t, rs2_stream>>& sensor_base::get_fourcc_to_rs2_stream_map()
{
return _fourcc_to_rs2_stream;
}
rs2_format sensor_base::fourcc_to_rs2_format(uint32_t fourcc_format) const
{
rs2_format f = RS2_FORMAT_ANY;
std::find_if(_fourcc_to_rs2_format->begin(), _fourcc_to_rs2_format->end(), [&fourcc_format, &f](const std::pair<uint32_t, rs2_format>& p) {
if (p.first == fourcc_format)
{
f = p.second;
return true;
}
return false;
});
return f;
}
rs2_stream sensor_base::fourcc_to_rs2_stream(uint32_t fourcc_format) const
{
rs2_stream s = RS2_STREAM_ANY;
std::find_if(_fourcc_to_rs2_stream->begin(), _fourcc_to_rs2_stream->end(), [&fourcc_format, &s](const std::pair<uint32_t, rs2_stream>& p) {
if (p.first == fourcc_format)
{
s = p.second;
return true;
}
return false;
});
return s;
}
void sensor_base::raise_on_before_streaming_changes(bool streaming)
{
on_before_streaming_changes(streaming);
}
void sensor_base::set_active_streams(const stream_profiles& requests)
{
std::lock_guard<std::mutex> lock(_active_profile_mutex);
_active_profiles = requests;
}
void sensor_base::assign_stream(const std::shared_ptr<stream_interface>& stream, std::shared_ptr<stream_profile_interface> target) const
{
environment::get_instance().get_extrinsics_graph().register_same_extrinsics(*stream, *target);
auto uid = stream->get_unique_id();
target->set_unique_id(uid);
}
void sensor_base::set_source_owner(sensor_base* owner)
{
_source_owner = owner;
}
stream_profiles sensor_base::get_stream_profiles(int tag) const
{
if (tag == profile_tag::PROFILE_TAG_ANY)
return *_profiles;
stream_profiles results;
for (auto p : *_profiles)
{
auto curr_tag = p->get_tag();
if (curr_tag & tag)
results.push_back(p);
}
return results;
}
processing_blocks get_color_recommended_proccesing_blocks()
{
processing_blocks res;
auto dec = std::make_shared<decimation_filter>();
if (!dec->supports_option(RS2_OPTION_STREAM_FILTER))
return res;
dec->get_option(RS2_OPTION_STREAM_FILTER).set(RS2_STREAM_COLOR);
dec->get_option(RS2_OPTION_STREAM_FORMAT_FILTER).set(RS2_FORMAT_ANY);
res.push_back(dec);
return res;
}
processing_blocks get_depth_recommended_proccesing_blocks()
{
processing_blocks res;
auto huffman_decode = std::make_shared<depth_decompression_huffman>();
res.push_back(huffman_decode);
auto dec = std::make_shared<decimation_filter>();
if (dec->supports_option(RS2_OPTION_STREAM_FILTER))
{
dec->get_option(RS2_OPTION_STREAM_FILTER).set(RS2_STREAM_DEPTH);
dec->get_option(RS2_OPTION_STREAM_FORMAT_FILTER).set(RS2_FORMAT_Z16);
res.push_back(dec);
}
return res;
}
device_interface& sensor_base::get_device()
{
return *_owner;
}
std::shared_ptr<frame> sensor_base::generate_frame_from_data(const platform::frame_object& fo,
frame_timestamp_reader* timestamp_reader,
const rs2_time_t& last_timestamp,
const unsigned long long& last_frame_number,
std::shared_ptr<stream_profile_interface> profile)
{
auto system_time = environment::get_instance().get_time_service()->get_time();
auto fr = std::make_shared<frame>();
byte* pix = (byte*)fo.pixels;
std::vector<byte> pixels(pix, pix + fo.frame_size);
fr->data = pixels;
fr->set_stream(profile);
// generate additional data
frame_additional_data additional_data(0,
0,
system_time,
static_cast<uint8_t>(fo.metadata_size),
(const uint8_t*)fo.metadata,
fo.backend_time,
last_timestamp,
last_frame_number,
false,
fo.frame_size);
fr->additional_data = additional_data;
// update additional data
additional_data.timestamp = timestamp_reader->get_frame_timestamp(fr);
additional_data.last_frame_number = last_frame_number;
additional_data.frame_number = timestamp_reader->get_frame_counter(fr);
fr->additional_data = additional_data;
return fr;
}
//////////////////////////////////////////////////////
/////////////////// UVC Sensor ///////////////////////
//////////////////////////////////////////////////////
uvc_sensor::~uvc_sensor()
{
try
{
if (_is_streaming)
uvc_sensor::stop();
if (_is_opened)
uvc_sensor::close();
}
catch (...)
{
LOG_ERROR("An error has occurred while stop_streaming()!");
}
}
void uvc_sensor::open(const stream_profiles& requests)
{
std::lock_guard<std::mutex> lock(_configure_lock);
if (_is_streaming)
throw wrong_api_call_sequence_exception("open(...) failed. UVC device is streaming!");
else if (_is_opened)
throw wrong_api_call_sequence_exception("open(...) failed. UVC device is already opened!");
auto on = std::unique_ptr<power>(new power(std::dynamic_pointer_cast<uvc_sensor>(shared_from_this())));
_source.init(_metadata_parsers);
_source.set_sensor(_source_owner->shared_from_this());
std::vector<platform::stream_profile> commited;
for (auto&& req_profile : requests)
{
auto&& req_profile_base = std::dynamic_pointer_cast<stream_profile_base>(req_profile);
try
{
unsigned long long last_frame_number = 0;
rs2_time_t last_timestamp = 0;
_device->probe_and_commit(req_profile_base->get_backend_profile(),
[this, req_profile_base, req_profile, last_frame_number, last_timestamp](platform::stream_profile p, platform::frame_object f, std::function<void()> continuation) mutable
{
const auto&& system_time = environment::get_instance().get_time_service()->get_time();
const auto&& fr = generate_frame_from_data(f, _timestamp_reader.get(), last_timestamp, last_frame_number, req_profile_base);
const auto&& requires_processing = true; // TODO - Ariel add option
const auto&& timestamp_domain = _timestamp_reader->get_frame_timestamp_domain(fr);
const auto&& bpp = get_image_bpp(req_profile_base->get_format());
auto&& frame_counter = fr->additional_data.frame_number;
auto&& timestamp = fr->additional_data.timestamp;
if (!this->is_streaming())
{
LOG_WARNING("Frame received with streaming inactive,"
<< librealsense::get_string(req_profile_base->get_stream_type())
<< req_profile_base->get_stream_index()
<< ", Arrived," << std::fixed << f.backend_time << " " << system_time);
return;
}
frame_continuation release_and_enqueue(continuation, f.pixels);
LOG_DEBUG("FrameAccepted," << librealsense::get_string(req_profile_base->get_stream_type())
<< ",Counter," << std::dec << fr->additional_data.frame_number
<< ",Index," << req_profile_base->get_stream_index()
<< ",BackEndTS," << std::fixed << f.backend_time
<< ",SystemTime," << std::fixed << system_time
<< " ,diff_ts[Sys-BE]," << system_time - f.backend_time
<< ",TS," << std::fixed << timestamp << ",TS_Domain," << rs2_timestamp_domain_to_string(timestamp_domain)
<< ",last_frame_number," << last_frame_number << ",last_timestamp," << last_timestamp);
last_frame_number = frame_counter;
last_timestamp = timestamp;
const auto&& vsp = As<video_stream_profile, stream_profile_interface>(req_profile);
int width = vsp ? vsp->get_width() : 0;
int height = vsp ? vsp->get_height() : 0;
frame_holder fh = _source.alloc_frame(stream_to_frame_types(req_profile_base->get_stream_type()), width * height * bpp / 8, fr->additional_data, requires_processing);
if (fh.frame)
{
memcpy((void*)fh->get_frame_data(), fr->data.data(), sizeof(byte)*fr->data.size());
auto&& video = (video_frame*)fh.frame;
video->assign(width, height, width * bpp / 8, bpp);
video->set_timestamp_domain(timestamp_domain);
fh->set_stream(req_profile_base);
}
else
{
LOG_INFO("Dropped frame. alloc_frame(...) returned nullptr");
return;
}
if (!requires_processing)
{
fh->attach_continuation(std::move(release_and_enqueue));
}
if (fh->get_stream().get())
{
_source.invoke_callback(std::move(fh));
}
});
}
catch (...)
{
for (auto&& commited_profile : commited)
{
_device->close(commited_profile);
}
throw;
}
commited.push_back(req_profile_base->get_backend_profile());
}
_internal_config = commited;
if (_on_open)
_on_open(_internal_config);
_power = move(on);
_is_opened = true;
try {
_device->stream_on([&](const notification& n)
{
_notifications_processor->raise_notification(n);
});
}
catch (...)
{
std::stringstream error_msg;
error_msg << "\tFormats: \n";
for (auto&& profile : _internal_config)
{
rs2_format fmt = fourcc_to_rs2_format(profile.format);
error_msg << "\t " << std::string(rs2_format_to_string(fmt)) << std::endl;
try {
_device->close(profile);
}
catch (...) {}
}
error_msg << std::endl;
reset_streaming();
_power.reset();
_is_opened = false;
throw std::runtime_error(error_msg.str());
}
if (Is<librealsense::global_time_interface>(_owner))
{
As<librealsense::global_time_interface>(_owner)->enable_time_diff_keeper(true);
}
set_active_streams(requests);
}
void uvc_sensor::close()
{
std::lock_guard<std::mutex> lock(_configure_lock);
if (_is_streaming)
throw wrong_api_call_sequence_exception("close() failed. UVC device is streaming!");
else if (!_is_opened)
throw wrong_api_call_sequence_exception("close() failed. UVC device was not opened!");
for (auto&& profile : _internal_config)
{
try // Handle disconnect event
{
_device->close(profile);
}
catch (...) {}
}
reset_streaming();
if (Is<librealsense::global_time_interface>(_owner))
{
As<librealsense::global_time_interface>(_owner)->enable_time_diff_keeper(false);
}
_power.reset();
_is_opened = false;
set_active_streams({});
}
void uvc_sensor::register_xu(platform::extension_unit xu)
{
_xus.push_back(std::move(xu));
}
void uvc_sensor::start(frame_callback_ptr callback)
{
std::lock_guard<std::mutex> lock(_configure_lock);
if (_is_streaming)
throw wrong_api_call_sequence_exception("start_streaming(...) failed. UVC device is already streaming!");
else if (!_is_opened)
throw wrong_api_call_sequence_exception("start_streaming(...) failed. UVC device was not opened!");
raise_on_before_streaming_changes(true); //Required to be just before actual start allow recording to work
_source.set_callback(callback);
_is_streaming = true;
_device->start_callbacks();
}
void uvc_sensor::stop()
{
std::lock_guard<std::mutex> lock(_configure_lock);
if (!_is_streaming)
throw wrong_api_call_sequence_exception("stop_streaming() failed. UVC device is not streaming!");
_is_streaming = false;
_device->stop_callbacks();
raise_on_before_streaming_changes(false);
}
void uvc_sensor::reset_streaming()
{
_source.flush();
_source.reset();
_timestamp_reader->reset();
}
void uvc_sensor::acquire_power()
{
std::lock_guard<std::mutex> lock(_power_lock);
if (_user_count.fetch_add(1) == 0)
{
_device->set_power_state(platform::D0);
for (auto&& xu : _xus) _device->init_xu(xu);
}
}
void uvc_sensor::release_power()
{
std::lock_guard<std::mutex> lock(_power_lock);
if (_user_count.fetch_add(-1) == 1)
{
_device->set_power_state(platform::D3);
}
}
stream_profiles uvc_sensor::init_stream_profiles()
{
std::unordered_set<std::shared_ptr<video_stream_profile>> profiles;
power on(std::dynamic_pointer_cast<uvc_sensor>(shared_from_this()));
if (_uvc_profiles.empty()) {}
_uvc_profiles = _device->get_profiles();
for (auto&& p : _uvc_profiles)
{
const auto&& rs2_fmt = fourcc_to_rs2_format(p.format);
if (rs2_fmt == RS2_FORMAT_ANY)
continue;
auto&& profile = std::make_shared<video_stream_profile>(p);
profile->set_dims(p.width, p.height);
profile->set_stream_type(fourcc_to_rs2_stream(p.format));
profile->set_stream_index(0);
profile->set_format(rs2_fmt);
profile->set_framerate(p.fps);
profiles.insert(profile);
}
stream_profiles result{ profiles.begin(), profiles.end() };
return result;
}
rs2_extension uvc_sensor::stream_to_frame_types(rs2_stream stream) const
{
// TODO: explicitly return video_frame for relevant streams and default to an error?
switch (stream)
{
case RS2_STREAM_DEPTH: return RS2_EXTENSION_DEPTH_FRAME;
default: return RS2_EXTENSION_VIDEO_FRAME;
}
}
bool info_container::supports_info(rs2_camera_info info) const
{
auto it = _camera_info.find(info);
return it != _camera_info.end();
}
void info_container::register_info(rs2_camera_info info, const std::string& val)
{
if (info_container::supports_info(info) && (info_container::get_info(info) != val)) // Append existing infos
{
_camera_info[info] += "\n" + val;
}
else
{
_camera_info[info] = val;
}
}
void info_container::update_info(rs2_camera_info info, const std::string& val)
{
if (info_container::supports_info(info))
{
_camera_info[info] = val;
}
}
const std::string& info_container::get_info(rs2_camera_info info) const
{
auto it = _camera_info.find(info);
if (it == _camera_info.end())
throw invalid_value_exception("Selected camera info is not supported for this camera!");
return it->second;
}
void info_container::create_snapshot(std::shared_ptr<info_interface>& snapshot) const
{
snapshot = std::make_shared<info_container>(*this);
}
void info_container::enable_recording(std::function<void(const info_interface&)> record_action)
{
//info container is a read only class, nothing to record
}
void info_container::update(std::shared_ptr<extension_snapshot> ext)
{
if (auto&& info_api = As<info_interface>(ext))
{
for (int i = 0; i < RS2_CAMERA_INFO_COUNT; ++i)
{
rs2_camera_info info = static_cast<rs2_camera_info>(i);
if (info_api->supports_info(info))
{
register_info(info, info_api->get_info(info));
}
}
}
}
void uvc_sensor::register_pu(rs2_option id)
{
register_option(id, std::make_shared<uvc_pu_option>(*this, id));
}
void uvc_sensor::try_register_pu(rs2_option id)
{
auto opt = std::make_shared<uvc_pu_option>(*this, id);
try
{
auto range = opt->get_range();
if (range.max <= range.min || range.step <= 0 || range.def < range.min || range.def > range.max) return;
auto val = opt->query();
if (val < range.min || val > range.max) return;
opt->set(val);
register_option(id, opt);
}
catch (...)
{
LOG_WARNING("Exception was thrown when inspecting " << this->get_info(RS2_CAMERA_INFO_NAME) << " property " << opt->get_description());
}
}
//////////////////////////////////////////////////////
/////////////////// HID Sensor ///////////////////////
//////////////////////////////////////////////////////
hid_sensor::hid_sensor(std::shared_ptr<platform::hid_device> hid_device, std::unique_ptr<frame_timestamp_reader> hid_iio_timestamp_reader,
std::unique_ptr<frame_timestamp_reader> custom_hid_timestamp_reader,
const std::map<rs2_stream, std::map<unsigned, unsigned>>& fps_and_sampling_frequency_per_rs2_stream,
const std::vector<std::pair<std::string, stream_profile>>& sensor_name_and_hid_profiles,
device* dev)
: sensor_base("Raw Motion Module", dev, (recommended_proccesing_blocks_interface*)this), _sensor_name_and_hid_profiles(sensor_name_and_hid_profiles),
_fps_and_sampling_frequency_per_rs2_stream(fps_and_sampling_frequency_per_rs2_stream),
_hid_device(hid_device),
_is_configured_stream(RS2_STREAM_COUNT),
_hid_iio_timestamp_reader(move(hid_iio_timestamp_reader)),
_custom_hid_timestamp_reader(move(custom_hid_timestamp_reader))
{
register_metadata(RS2_FRAME_METADATA_BACKEND_TIMESTAMP, make_additional_data_parser(&frame_additional_data::backend_timestamp));
std::map<std::string, uint32_t> frequency_per_sensor;
for (auto&& elem : sensor_name_and_hid_profiles)
frequency_per_sensor.insert(make_pair(elem.first, elem.second.fps));
std::vector<platform::hid_profile> profiles_vector;
for (auto&& elem : frequency_per_sensor)
profiles_vector.push_back(platform::hid_profile{ elem.first, elem.second });
_hid_device->register_profiles(profiles_vector);
for (auto&& elem : _hid_device->get_sensors())
_hid_sensors.push_back(elem);
}
hid_sensor::~hid_sensor()
{
try
{
if (_is_streaming)
stop();
if (_is_opened)
close();
}
catch (...)
{
LOG_ERROR("An error has occurred while stop_streaming()!");
}
}
stream_profiles hid_sensor::get_sensor_profiles(std::string sensor_name) const
{
stream_profiles profiles{};
for (auto&& elem : _sensor_name_and_hid_profiles)
{
if (!elem.first.compare(sensor_name))
{
auto&& p = elem.second;
platform::stream_profile sp{ 1, 1, p.fps, stream_to_fourcc(p.stream) };
auto profile = std::make_shared<motion_stream_profile>(sp);
profile->set_stream_index(p.index);
profile->set_stream_type(p.stream);
profile->set_format(p.format);
profile->set_framerate(p.fps);
profiles.push_back(profile);
}
}
return profiles;
}
void hid_sensor::open(const stream_profiles& requests)
{
std::lock_guard<std::mutex> lock(_configure_lock);
if (_is_streaming)
throw wrong_api_call_sequence_exception("open(...) failed. Hid device is streaming!");
else if (_is_opened)
throw wrong_api_call_sequence_exception("Hid device is already opened!");
std::vector<platform::hid_profile> configured_hid_profiles;
for (auto&& request : requests)
{
auto&& sensor_name = rs2_stream_to_sensor_name(request->get_stream_type());
_configured_profiles.insert(std::make_pair(sensor_name, request));
_is_configured_stream[request->get_stream_type()] = true;
configured_hid_profiles.push_back(platform::hid_profile{ sensor_name,
fps_to_sampling_frequency(request->get_stream_type(), request->get_framerate()) });
}
_hid_device->open(configured_hid_profiles);
if (Is<librealsense::global_time_interface>(_owner))
{
As<librealsense::global_time_interface>(_owner)->enable_time_diff_keeper(true);
}
_is_opened = true;
set_active_streams(requests);
}
void hid_sensor::close()
{
std::lock_guard<std::mutex> lock(_configure_lock);
if (_is_streaming)
throw wrong_api_call_sequence_exception("close() failed. Hid device is streaming!");
else if (!_is_opened)
throw wrong_api_call_sequence_exception("close() failed. Hid device was not opened!");
_hid_device->close();
_configured_profiles.clear();
_is_configured_stream.clear();
_is_configured_stream.resize(RS2_STREAM_COUNT);
_is_opened = false;
if (Is<librealsense::global_time_interface>(_owner))
{
As<librealsense::global_time_interface>(_owner)->enable_time_diff_keeper(false);
}
set_active_streams({});
}
// TODO:
static rs2_stream custom_gpio_to_stream_type(uint32_t custom_gpio)
{
if (custom_gpio < 4)
{
return static_cast<rs2_stream>(RS2_STREAM_GPIO);
}
LOG_ERROR("custom_gpio " << std::to_string(custom_gpio) << " is incorrect!");
return RS2_STREAM_ANY;
}
void hid_sensor::start(frame_callback_ptr callback)
{
std::lock_guard<std::mutex> lock(_configure_lock);
if (_is_streaming)
throw wrong_api_call_sequence_exception("start_streaming(...) failed. Hid device is already streaming!");
else if (!_is_opened)
throw wrong_api_call_sequence_exception("start_streaming(...) failed. Hid device was not opened!");
_source.set_callback(callback);
_source.init(_metadata_parsers);
_source.set_sensor(_source_owner->shared_from_this());
unsigned long long last_frame_number = 0;
rs2_time_t last_timestamp = 0;
raise_on_before_streaming_changes(true); //Required to be just before actual start allow recording to work
_hid_device->start_capture([this, last_frame_number, last_timestamp](const platform::sensor_data& sensor_data) mutable
{
const auto&& system_time = environment::get_instance().get_time_service()->get_time();
auto timestamp_reader = _hid_iio_timestamp_reader.get();
static const std::string custom_sensor_name = "custom";
auto&& sensor_name = sensor_data.sensor.name;
auto&& request = _configured_profiles[sensor_name];
bool is_custom_sensor = false;
static const uint32_t custom_source_id_offset = 16;
uint8_t custom_gpio = 0;
auto custom_stream_type = RS2_STREAM_ANY;
if (sensor_name == custom_sensor_name)
{
custom_gpio = *(reinterpret_cast<uint8_t*>((uint8_t*)(sensor_data.fo.pixels) + custom_source_id_offset));
custom_stream_type = custom_gpio_to_stream_type(custom_gpio);
if (!_is_configured_stream[custom_stream_type])
{
LOG_DEBUG("Unrequested " << rs2_stream_to_string(custom_stream_type) << " frame was dropped.");
return;
}
is_custom_sensor = true;
timestamp_reader = _custom_hid_timestamp_reader.get();
}
if (!this->is_streaming())
{
auto stream_type = request->get_stream_type();
LOG_INFO("HID Frame received when Streaming is not active,"
<< get_string(stream_type)
<< ",Arrived," << std::fixed << system_time);
return;
}
const auto&& fr = generate_frame_from_data(sensor_data.fo, timestamp_reader, last_timestamp, last_frame_number, request);
auto&& frame_counter = fr->additional_data.frame_number;
const auto&& timestamp_domain = timestamp_reader->get_frame_timestamp_domain(fr);
auto&& timestamp = fr->additional_data.timestamp;
const auto&& bpp = get_image_bpp(request->get_format());
auto&& data_size = sensor_data.fo.frame_size;
LOG_DEBUG("FrameAccepted," << get_string(request->get_stream_type())
<< ",Counter," << std::dec << frame_counter << ",Index,0"
<< ",BackEndTS," << std::fixed << sensor_data.fo.backend_time
<< ",SystemTime," << std::fixed << system_time
<< " ,diff_ts[Sys-BE]," << system_time - sensor_data.fo.backend_time
<< ",TS," << std::fixed << timestamp << ",TS_Domain," << rs2_timestamp_domain_to_string(timestamp_domain)
<< ",last_frame_number," << last_frame_number << ",last_timestamp," << last_timestamp);
last_frame_number = frame_counter;
last_timestamp = timestamp;
frame_holder frame = _source.alloc_frame(RS2_EXTENSION_MOTION_FRAME, data_size, fr->additional_data, true);
memcpy((void*)frame->get_frame_data(), fr->data.data(), sizeof(byte)*fr->data.size());
if (!frame)
{
LOG_INFO("Dropped frame. alloc_frame(...) returned nullptr");
return;
}
frame->set_stream(request);
frame->set_timestamp_domain(timestamp_domain);
_source.invoke_callback(std::move(frame));
});
_is_streaming = true;
}
void hid_sensor::stop()
{
std::lock_guard<std::mutex> lock(_configure_lock);
if (!_is_streaming)
throw wrong_api_call_sequence_exception("stop_streaming() failed. Hid device is not streaming!");
_hid_device->stop_capture();
_is_streaming = false;
_source.flush();
_source.reset();
_hid_iio_timestamp_reader->reset();
_custom_hid_timestamp_reader->reset();
raise_on_before_streaming_changes(false);
}
std::vector<uint8_t> hid_sensor::get_custom_report_data(const std::string& custom_sensor_name,
const std::string& report_name, platform::custom_sensor_report_field report_field) const
{
return _hid_device->get_custom_report_data(custom_sensor_name, report_name, report_field);
}
stream_profiles hid_sensor::init_stream_profiles()
{
stream_profiles stream_requests;
for (auto&& it = _hid_sensors.rbegin(); it != _hid_sensors.rend(); ++it)
{
auto profiles = get_sensor_profiles(it->name);
stream_requests.insert(stream_requests.end(), profiles.begin(), profiles.end());
}
return stream_requests;
}
const std::string& hid_sensor::rs2_stream_to_sensor_name(rs2_stream stream) const
{
for (auto&& elem : _sensor_name_and_hid_profiles)
{
if (stream == elem.second.stream)
return elem.first;
}
throw invalid_value_exception("rs2_stream not found!");
}
uint32_t hid_sensor::stream_to_fourcc(rs2_stream stream) const
{
uint32_t fourcc;
try {
fourcc = stream_and_fourcc.at(stream);
}
catch (std::out_of_range)
{
throw invalid_value_exception(to_string() << "fourcc of stream " << rs2_stream_to_string(stream) << " not found!");
}
return fourcc;
}
uint32_t hid_sensor::fps_to_sampling_frequency(rs2_stream stream, uint32_t fps) const
{
// TODO: Add log prints
auto it = _fps_and_sampling_frequency_per_rs2_stream.find(stream);
if (it == _fps_and_sampling_frequency_per_rs2_stream.end())
return fps;
auto fps_mapping = it->second.find(fps);
if (fps_mapping != it->second.end())
return fps_mapping->second;
else
return fps;
}
uvc_sensor::uvc_sensor(std::string name,
std::shared_ptr<platform::uvc_device> uvc_device,
std::unique_ptr<frame_timestamp_reader> timestamp_reader,
device* dev)
: sensor_base(name, dev, (recommended_proccesing_blocks_interface*)this),
_device(move(uvc_device)),
_user_count(0),
_timestamp_reader(std::move(timestamp_reader))
{
register_metadata(RS2_FRAME_METADATA_BACKEND_TIMESTAMP, make_additional_data_parser(&frame_additional_data::backend_timestamp));
register_metadata(RS2_FRAME_METADATA_RAW_FRAME_SIZE, make_additional_data_parser(&frame_additional_data::raw_size));
}
iio_hid_timestamp_reader::iio_hid_timestamp_reader()
{
counter.resize(sensors);
reset();
}
void iio_hid_timestamp_reader::reset()
{
std::lock_guard<std::recursive_mutex> lock(_mtx);
started = false;
for (auto i = 0; i < sensors; ++i)
{
counter[i] = 0;
}
}
rs2_time_t iio_hid_timestamp_reader::get_frame_timestamp(const std::shared_ptr<frame_interface>& frame)
{
std::lock_guard<std::recursive_mutex> lock(_mtx);
auto f = std::dynamic_pointer_cast<librealsense::frame>(frame);
if (has_metadata(frame))
{
// The timestamps conversions path comprise of:
// FW TS (32bit) -> USB Phy Layer (no changes) -> Host Driver TS (Extend to 64bit) -> LRS read as 64 bit
// The flow introduces discrepancy with UVC stream which timestamps are not extended to 64 bit by host driver both for Win and v4l backends.
// In order to allow for hw timestamp-based synchronization of Depth and IMU streams the latter will be trimmed to 32 bit.
// To revert to the extended 64 bit TS uncomment the next line instead
//auto timestamp = *((uint64_t*)((const uint8_t*)fo.metadata));
// The ternary operator is replaced by explicit assignment due to an issue with GCC for RaspberryPi that causes segfauls in optimized build.
auto timestamp = *(reinterpret_cast<uint32_t*>(f->additional_data.metadata_blob.data()));
if (f->additional_data.metadata_size >= platform::hid_header_size)
timestamp = static_cast<uint32_t>(reinterpret_cast<const platform::hid_header*>(f->additional_data.metadata_blob.data())->timestamp);
// HID timestamps are aligned to FW Default - usec units
return static_cast<rs2_time_t>(timestamp * TIMESTAMP_USEC_TO_MSEC);
}
if (!started)
{
LOG_WARNING("HID timestamp not found, switching to Host timestamps.");
started = true;
}
return std::chrono::duration<rs2_time_t, std::milli>(std::chrono::system_clock::now().time_since_epoch()).count();
}
bool iio_hid_timestamp_reader::has_metadata(const std::shared_ptr<frame_interface>& frame) const
{
auto f = std::dynamic_pointer_cast<librealsense::frame>(frame);
if (f->additional_data.metadata_size > 0)
{
return true;
}
return false;
}
unsigned long long iio_hid_timestamp_reader::get_frame_counter(const std::shared_ptr<frame_interface>& frame) const
{
std::lock_guard<std::recursive_mutex> lock(_mtx);
int index = 0;
if (frame->get_stream()->get_stream_type() == RS2_STREAM_GYRO)
index = 1;
return ++counter[index];
}
rs2_timestamp_domain iio_hid_timestamp_reader::get_frame_timestamp_domain(const std::shared_ptr<frame_interface>& frame) const
{