forked from IntelRealSense/librealsense
-
Notifications
You must be signed in to change notification settings - Fork 0
/
index.js
6666 lines (6316 loc) · 224 KB
/
index.js
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
// Copyright (c) 2017 Intel Corporation. All rights reserved.
// Use of this source code is governed by an Apache 2.0 license
// that can be found in the LICENSE file.
'use strict';
const RS2 = require('bindings')('node_librealsense');
const EventEmitter = require('events');
const PNG = require('pngjs').PNG;
const fs = require('fs');
/**
* UnrecoverableError is the type of error that jeopardized the modue that restart
* is needed.
*/
class UnrecoverableError extends Error {
constructor(message) {
super('Unrecoverable! '+ message);
}
}
// TODO(tingshao): resolve the potential disabled eslint errors
/* eslint-disable prefer-rest-params, valid-jsdoc, no-unused-vars, camelcase */
/**
* A RealSense camera
*/
class Device {
constructor(cxxDev, autoDelete = true) {
this.cxxDev = cxxDev;
if (autoDelete) {
internal.addObject(this);
}
}
/**
* Check if everything is OK, e.g. if the device object is connected to underlying hardware
* @return {Boolean}
*/
get isValid() {
return (this.cxxDev !== null);
}
/**
* get an array of adjacent sensors, sharing the same physical parent composite device
* @return {Sensor[]}
*/
querySensors() {
let sensors = this.cxxDev.querySensors();
if (!sensors) return undefined;
const array = [];
sensors.forEach((s) => {
if (s.is(RS2.RS2_EXTENSION_DEPTH_SENSOR)) {
array.push(new DepthSensor(s));
} else if (s.is(RS2.RS2_EXTENSION_COLOR_SENSOR)) {
array.push(new ColorSensor(s));
} else if (s.is(RS2.RS2_EXTENSION_MOTION_SENSOR)) {
array.push(new MotionSensor(s));
} else if (s.is(RS2.RS2_EXTENSION_FISHEYE_SENSOR)) {
array.push(new FisheyeSensor(s));
} else {
array.push(new Sensor(s));
}
});
return array;
}
/**
* Get the first sensor
* @return {Sensor|undefined}
*/
get first() {
let sensors = this.querySensors();
if (sensors && sensors.length > 0) {
return sensors[0];
}
return undefined;
}
/**
* Information that can be queried from the device.
* Not all information attributes are available on all camera types.
* This information is mainly available for camera debug and troubleshooting and should not be
* used in applications.
* @typedef {Object} CameraInfoObject
* @property {String|undefined} name - Device friendly name. <br> undefined is not
* supported.
* @property {String|undefined} serialNumber - Device serial number. <br> undefined is not
* supported.
* @property {String|undefined} firmwareVersion - Primary firmware version.
* <br> undefined is not supported.
* @property {String|undefined} physicalPort - Unique identifier of the port the device is
* connected to (platform specific). <br> undefined is not supported.
* @property {String|undefined} debugOpCode - If device supports firmware logging, this is the
* command to send to get logs from firmware. <br> undefined is not supported.
* @property {String|undefined} advancedMode - True if the device is in advanced mode.
* <br> undefined is not supported.
* @property {String|undefined} productId - Product ID as reported in the USB descriptor.
* <br> undefined is not supported.
* @property {Boolean|undefined} cameraLocked - True if EEPROM is locked. <br> undefined is not
* supported.
* @property {String|undefined} usbTypeDescriptor - Designated USB specification: USB2/USB3.
* <br> undefined is not supported.
* @property {String|undefined} recommendedFirmwareVersion - Latest firmware version.
* <br> undefined is not supported.
* @see [Device.getCameraInfo()]{@link Device#getCameraInfo}
*/
/**
* Get camera information
* There are 2 acceptable forms of syntax:
* <pre><code>
* Syntax 1. getCameraInfo()
* Syntax 2. getCameraInfo(info)
* </code></pre>
*
* @param {String|Integer} [info] - the camera_info type, see {@link camera_info} for available
* values
* @return {CameraInfoObject|String|undefined} if no argument is provided, {CameraInfoObject} is
* returned. If a camera_info is provided, the specific camera info value string is returned.
*/
getCameraInfo(info) {
const funcName = 'Device.getCameraInfo()';
checkArgumentLength(0, 1, arguments.length, funcName);
if (arguments.length === 0) {
let result = {};
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_NAME)) {
result.name = this.cxxDev.getCameraInfo(camera_info.CAMERA_INFO_NAME);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_SERIAL_NUMBER)) {
result.serialNumber = this.cxxDev.getCameraInfo(camera_info.CAMERA_INFO_SERIAL_NUMBER);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_FIRMWARE_VERSION)) {
result.firmwareVersion = this.cxxDev.getCameraInfo(
camera_info.CAMERA_INFO_FIRMWARE_VERSION);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_PHYSICAL_PORT)) {
result.physicalPort = this.cxxDev.getCameraInfo(camera_info.CAMERA_INFO_PHYSICAL_PORT);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_DEBUG_OP_CODE)) {
result.debugOpCode = this.cxxDev.getCameraInfo(camera_info.CAMERA_INFO_DEBUG_OP_CODE);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_ADVANCED_MODE)) {
result.advancedMode = this.cxxDev.getCameraInfo(camera_info.CAMERA_INFO_ADVANCED_MODE);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_PRODUCT_ID)) {
result.productId = this.cxxDev.getCameraInfo(camera_info.CAMERA_INFO_PRODUCT_ID);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_CAMERA_LOCKED)) {
result.cameraLocked = this.cxxDev.getCameraInfo(camera_info.CAMERA_INFO_CAMERA_LOCKED);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_USB_TYPE_DESCRIPTOR)) {
result.usbTypeDescriptor = this.cxxDev.getCameraInfo(
camera_info.CAMERA_INFO_USB_TYPE_DESCRIPTOR);
}
if (this.cxxDev.supportsCameraInfo(camera_info.CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION)) {
result.recommendedFirmwareVersion = this.cxxDev.getCameraInfo(
camera_info.CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION);
}
return result;
} else {
const val = checkArgumentType(arguments, constants.camera_info, 0, funcName);
return (this.cxxDev.supportsCameraInfo(val) ? this.cxxDev.getCameraInfo(val) : undefined);
}
}
get cameraInfo() {
return this.getCameraInfo();
}
/**
* Check if specific camera info is supported.
* @param {String|Integer} info - info type to query. See {@link camera_info} for available values
* @return {Boolean|undefined} Returns undefined if an invalid info type was specified.
* @see enum {@link camera_info}
* @example <caption>Example of 3 equivalent calls of the same query</caption>
* device.supportsCameraInfo('name');
* device.supportsCameraInfo(realsense2.camera_info.camera_info_name);
* device.supportsCameraInfo(realsense2.camera_info.CAMERA_INFO_NAME);
*/
supportsCameraInfo(info) {
const funcName = 'Device.supportsCameraInfo()';
checkArgumentLength(1, 1, arguments.length, funcName);
const i = checkArgumentType(arguments, constants.camera_info, 0, funcName);
return this.cxxDev.supportsCameraInfo(i);
}
/**
* Send hardware reset request to the device.
* @return {undefined}
*/
reset() {
this.cxxDev.reset();
}
/**
* Release resources associated with the object
*/
destroy() {
if (this.cxxDev) {
this.cxxDev.destroy();
this.cxxDev = undefined;
}
this._events = undefined;
}
static _internalCreateDevice(cxxDevice) {
return cxxDevice.isTm2() ? new Tm2(cxxDevice) : new Device(cxxDevice);
}
}
/**
* This class represents the tm2 device
*/
class Tm2 extends Device {
constructor(dev) {
super(dev);
}
/**
* Enter the given device into loopback operation mode that uses the given file as input for
* raw data
* @param {String} file Path to bag file with raw data for loopback
* @return {undefined}
*/
enableLoopback(file) {
const funcName = 'Tm2.enableLoopback()';
checkArgumentLength(1, 1, arguments.length, funcName);
checkArgumentType(arguments, 'string', 0, funcName);
checkFileExistence(file);
this.cxxDev.enableLoopback(file);
}
/**
* Restores the given device into normal operation mode
* @return {undefined}
*/
disableLoopback() {
this.cxxDev.disableLoopback();
}
/**
* Checks if the device is in loopback mode or not
* @return {Boolean}
*/
get loopbackEnabled() {
return this.cxxDev.isLoopbackEnabled();
}
}
/**
* Class represents a stream configuration
*/
class StreamProfile {
constructor(cxxProfile) {
this.cxxProfile = cxxProfile;
this.streamValue = this.cxxProfile.stream();
this.formatValue = this.cxxProfile.format();
this.fpsValue = this.cxxProfile.fps();
this.indexValue = this.cxxProfile.index();
this.uidValue = this.cxxProfile.uniqueID();
this.isDefaultValue = this.cxxProfile.isDefault();
}
/**
* Get stream index the input profile in case there are multiple streams of the same type
*
* @return {Integer}
*/
get streamIndex() {
return this.indexValue;
}
/**
* Get stream type
*
* @return {Integer}
*/
get streamType() {
return this.streamValue;
}
/**
* Get binary data format
*
* @return {Integer}
*/
get format() {
return this.formatValue;
}
/**
* Expected rate for data frames to arrive, meaning expected number of frames per second
*
* @return {Integer}
*/
get fps() {
return this.fpsValue;
}
/**
* Get the identifier for the stream profile, unique within the application
*
* @return {Integer}
*/
get uniqueID() {
return this.uidValue;
}
/**
* Returns non-zero if selected profile is recommended for the sensor
* This is an optional hint we offer to suggest profiles with best performance-quality tradeof
*
* @return {Boolean}
*/
get isDefault() {
return this.isDefaultValue;
}
/**
* Extrinsics:
* @typedef {Object} ExtrinsicsObject
* @property {Float32[]} rotation - Array(9), Column-major 3x3 rotation matrix
* @property {Float32[]} translation - Array(3), Three-element translation vector, in meters
* @see [StreamProfile.getExtrinsicsTo()]{@link StreamProfile#getExtrinsicsTo}
*/
/**
* Get extrinsics from a this stream to the target stream
*
* @param {StreamProfile} toProfile the target stream profile
* @return {ExtrinsicsObject}
*/
getExtrinsicsTo(toProfile) {
const funcName = 'StreamProfile.getExtrinsicsTo()';
checkArgumentLength(1, 1, arguments.length, funcName);
checkArgumentType(arguments, StreamProfile, 0, funcName);
return this.cxxProfile.getExtrinsicsTo(toProfile.cxxProfile);
}
destroy() {
if (this.cxxProfile) {
this.cxxProfile.destroy();
this.cxxProfile = undefined;
}
}
static _internalCreateStreamProfile(cxxProfile) {
if (cxxProfile.isMotionProfile()) {
return new MotionStreamProfile(cxxProfile);
} else if (cxxProfile.isVideoProfile()) {
return new VideoStreamProfile(cxxProfile);
} else {
return new StreamProfile(cxxProfile);
}
}
}
/**
* Motion intrinsics: scale, bias, and variances.
* @typedef {Object} MotionIntrinsics
* @property {Float32[]} data - Array(12), Interpret data array values. Indices are:
* <br>[0 - Scale X, 1 - cross axis, 2 - cross axis, 3 - Bias X,
* <br> 4 - cross axis, 5 - Scale Y, 6 - cross axis, 7 - Bias Y,
* <br> 8 - cross axis, 9 - cross axis, 10 - Scale Z, 11 - Bias Z]
* @property {Float32[]} noiseVariances - Array(3), Variance of noise for X, Y, and Z axis
* @property {Float32[]} biasVariances - Array(3), Variance of bias for X, Y, and Z axis
* @see [MotionStreamProfile.getMotionIntrinsics()]{@link MotionStreamProfile#getMotionIntrinsics}
*/
/**
* This represent the stream profile of motion stream
*/
class MotionStreamProfile extends StreamProfile {
constructor(cxxProfile) {
super(cxxProfile);
}
/**
* Returns scale and bias of a motion stream.
* @return {MotionIntrinsics} {@link MotionIntrinsics}
*/
getMotionIntrinsics() {
return this.cxxProfile.getMotionIntrinsics();
}
}
/**
* List of devices
*/
class DeviceList {
constructor(cxxList) {
this.cxxList = cxxList;
internal.addObject(this);
}
/**
* Release resources associated with the object
*/
destroy() {
if (this.cxxList) {
this.cxxList.destroy();
this.cxxList = undefined;
}
}
/**
* Checks if a specific device is contained inside a device list.
*
* @param {Device} device the camera to be checked
* @return {Boolean} true if the camera is contained in the list, otherwise false
*/
contains(device) {
const funcName = 'DeviceList.contains()';
checkArgumentLength(1, 1, arguments.length, funcName);
checkArgumentType(arguments, Device, 0, funcName);
return this.cxxList.contains(device.cxxDev);
}
/**
* Creates a device by index. The device object represents a physical camera and provides the
* means to manipulate it.
*
* @param {Integer} index the zero based index of the device in the device list
* @return {Device|undefined}
*/
getDevice(index) {
const funcName = 'DeviceList.getDevice()';
checkArgumentLength(1, 1, arguments.length, funcName);
checkArgumentType(arguments, 'number', 0, funcName, 0, this.size);
let dev = this.cxxList.getDevice(index);
return dev ? Device._internalCreateDevice(dev) : undefined;
}
get devices() {
let len = this.cxxList.size();
if (!len) {
return undefined;
}
let output = [];
for (let i = 0; i < len; i++) {
output[i] = Device._internalCreateDevice(this.cxxList.getDevice(i));
}
return output;
}
/**
* Determines number of devices in a list.
* @return {Integer}
*/
get size() {
return this.cxxList.size();
}
/**
* Get the first device
* @return {Device|undefined}
*/
get front() {
return this.getDevice(0);
}
/**
* Get the last device
* @return {Device|undefined}
*/
get back() {
if (this.size > 0) {
return this.getDevice(this.size - 1);
}
return undefined;
}
}
class VideoStreamProfile extends StreamProfile {
/**
* Construct a device object, representing a RealSense camera
*/
constructor(cxxProfile) {
super(cxxProfile);
// TODO(tinshao): determine right width and height value
this.widthValue = this.cxxProfile.width();
this.heightValue = this.cxxProfile.height();
}
/**
* Width in pixels of the video stream
*
* @return {Integer}
*/
get width() {
return this.widthValue;
}
/**
* height in pixels of the video stream
*
* @return {Integer}
*/
get height() {
return this.heightValue;
}
/**
* Stream intrinsics:
* @typedef {Object} IntrinsicsObject
* @property {Integer} width - Width of the image in pixels
* @property {Integer} height - Height of the image in pixels
* @property {Float32} ppx - Horizontal coordinate of the principal point of the image, as a
* pixel offset from the left edge
* @property {Float32} ppy - Vertical coordinate of the principal point of the image, as a pixel
* offset from the top edge
* @property {Float32} fx - Focal length of the image plane, as a multiple of pixel width
* @property {Float32} fy - Focal length of the image plane, as a multiple of pixel height
* @property {Integer} model - Distortion model of the image, see
* @property {Float32[]} coeffs - Array(5), Distortion coefficients
* @see [StreamProfile.getIntrinsics()]{@link StreamProfile#getIntrinsics}
*/
/**
* When called on a VideoStreamProfile, returns the intrinsics of specific stream configuration
* @return {IntrinsicsObject|undefined}
*/
getIntrinsics() {
return this.cxxProfile.getVideoStreamIntrinsics();
}
}
class Options {
constructor(cxxObj) {
this.cxxObj = cxxObj;
}
setCxxOptionsObject(cxxObj) {
this.cxxObj = cxxObj;
}
/**
* Check if particular option is read-only
* @param {String|Number} option The option to be checked
* @return {Boolean|undefined} true if option is read-only and undefined if not supported
*/
isOptionReadOnly(option) {
const funcName = 'Options.isOptionReadOnly()';
checkArgumentLength(1, 1, arguments.length, funcName);
const o = checkArgumentType(arguments, constants.option, 0, funcName);
if (!this.cxxObj.supportsOption(o)) {
return undefined;
}
return this.cxxObj.isOptionReadonly(o);
}
/**
* Read option value from the sensor.
* @param {String|Number} option The option to be queried
* @return {Float32|undefined} The value of the option, or <code>undefined</code> if invalid
* option
* @see {@link option}
*/
getOption(option) {
const funcName = 'Options.getOption()';
checkArgumentLength(1, 1, arguments.length, funcName);
const o = checkArgumentType(arguments, constants.option, 0, funcName);
if (!this.cxxObj.supportsOption(o)) {
return undefined;
}
return this.cxxObj.getOption(o);
}
/**
* @typedef {Object} OptionRangeObject
* @property {Float32} minValue - the minimum value which will be accepted for this option
* @property {Float32} maxValue - the maximum value which will be accepted for this option
* @property {Float32} defaultValue - the default value of the option
* @property {Float32} step - the granularity of options which accept discrete values, or zero if
* the option accepts continuous values
* @see [Sensor.getOptionRange()]{@link Sensor#getOptionRange}
*/
/**
* Retrieve the available range of values of a supported option.
* @param {String|Integer} option - the option that is being queried. See {@link option} for
* available values
* @return {OptionRangeObject|undefined} Returns undefined if an invalid option was specified
* @see {@link OptionRangeObject}
* @see {@link option}
*
* @example <caption>Example of 3 equivalent calls of the same option range</caption>
* Sensor.getOptionRange('backlight-compensation');
* Sensor.getOptionRange(realsense2.option.option_backlight_compensation);
* Sensor.getOptionRange(realsense2.option.OPTION_BACKLIGHT_COMPENSATION);
*/
getOptionRange(option) {
const funcName = 'Options.getOptionRange()';
checkArgumentLength(1, 1, arguments.length, funcName);
const o = checkArgumentType(arguments, constants.option, 0, funcName);
if (!this.cxxObj.supportsOption(o)) {
return undefined;
}
return this.cxxObj.getOptionRange(o);
}
/**
* Write new value to device option.
* @param {String|Integer} option - the option that is being queried. See {@link option} for
* available values
* @param {Float32} value - the new value to be set
* @see {@link option}
* @return {undefined}
*/
setOption(option, value) {
const funcName = 'Options.setOption()';
checkArgumentLength(2, 2, arguments.length, funcName);
const o = checkArgumentType(arguments, constants.option, 0, funcName);
checkArgumentType(arguments, 'number', 1, funcName);
if (!this.cxxObj.supportsOption(o) || this.cxxObj.isOptionReadonly(o)) {
return undefined;
}
if (!this._internalIsOptionValueInRange(o, value)) {
return undefined;
}
this.cxxObj.setOption(o, value);
}
/**
* Check if particular option is supported by a subdevice.
* @param {String|Integer} option - the option that is being queried. See {@link option} for
* available values
* @return {Boolean|undefined} Returns undefined if an invalid option was specified
* @see {@link option}
*/
supportsOption(option) {
const funcName = 'Options.supportsOption()';
checkArgumentLength(1, 1, arguments.length, funcName);
const o = checkArgumentType(arguments, constants.option, 0, funcName);
return this.cxxObj.supportsOption(o);
}
/**
* Get option description.
* @param {String|Integer} option - the option that is being queried. See {@link option} for
* available values
* @return {String|undefined} the human readable description of the option. Returns undefined if
* an invalid option was specified
* @see {@link option}
*/
getOptionDescription(option) {
const funcName = 'Options.getOptionDescription()';
checkArgumentLength(1, 1, arguments.length, funcName);
const o = checkArgumentType(arguments, constants.option, 0, funcName);
if (!this.cxxObj.supportsOption(o)) {
return undefined;
}
return this.cxxObj.getOptionDescription(o);
}
/**
* Get option value description (in case specific option value hold special meaning).
* @param {String|Integer} option - the option that is being queried. See {@link option} for
* available values
* @return {String|undefined} the human readable description of the option value. Returns
* undefined if an invalid option was specified
* @see {@link option}
*/
getOptionValueDescription(option, value) {
const funcName = 'Options.getOptionValueDescription()';
checkArgumentLength(2, 2, arguments.length, funcName);
const o = checkArgumentType(arguments, constants.option, 0, funcName);
checkArgumentType(arguments, 'number', 1, funcName);
if (!this.cxxObj.supportsOption(o)) {
return undefined;
}
return this.cxxObj.getOptionValueDescription(o, value);
}
_internalIsOptionValueInRange(option, value) {
let range = this.getOptionRange(option);
return (range && value >= range.minValue && value <= range.maxValue);
}
}
/**
* A sensor device in a RealSense camera
*/
class Sensor extends Options {
/**
* Construct a Sensor object, representing a RealSense camera subdevice
* By default, native resources associated with a Sensor object are freed
* automatically during cleanup.
*/
constructor(cxxSensor, autoDelete = true) {
super(cxxSensor);
this.cxxSensor = cxxSensor;
this._events = new EventEmitter();
if (autoDelete === true) {
internal.addObject(this);
}
}
/**
* Check if everything is OK, e.g. if the device object is connected to underlying hardware
* @return {Boolean}
*/
get isValid() {
return (this.cxxSensor !== null);
}
/**
* Open subdevice for exclusive access, by committing to a configuration.
* There are 2 acceptable forms of syntax:
* <pre><code>
* Syntax 1. open(streamProfile)
* Syntax 2. open(profileArray)
* </code></pre>
* Syntax 2 is for opening multiple profiles in one function call and should be used for
* interdependent streams, such as depth and infrared, that have to be configured together.
*
* @param {StreamProfile} streamProfile configuration commited by the device
* @param {StreamProfile[]} profileArray configurations array commited by the device
* @see [Sensor.getStreamProfiles]{@link Sensor#getStreamProfiles} for a list of all supported
* stream profiles
*/
open(streamProfile) {
const funcName = 'Sensor.open()';
checkArgumentLength(1, 1, arguments.length, funcName);
if (Array.isArray(streamProfile) && streamProfile.length > 0) {
let cxxStreamProfiles = [];
for (let i = 0; i < streamProfile.length; i++) {
if (!(streamProfile[i] instanceof StreamProfile)) {
throw new TypeError(
'Sensor.open() expects a streamProfile object or an array of streamProfile objects'); // eslint-disable-line
}
cxxStreamProfiles.push(streamProfile[i].cxxProfile);
}
this.cxxSensor.openMultipleStream(cxxStreamProfiles);
} else {
checkArgumentType(arguments, StreamProfile, 0, funcName);
this.cxxSensor.openStream(streamProfile.cxxProfile);
}
}
/**
* Check if specific camera info is supported
* @param {String|Integer} info - info type to query. See {@link camera_info} for available values
* @return {Boolean|undefined} Returns undefined if an invalid info type was specified.
* @see enum {@link camera_info}
*/
supportsCameraInfo(info) {
const funcName = 'Sensor.supportsCameraInfo()';
checkArgumentLength(1, 1, arguments.length, funcName);
const i = checkArgumentType(arguments, constants.camera_info, 0, funcName);
return this.cxxSensor.supportsCameraInfo(i);
}
/**
* Get camera information of the sensor
*
* @param {String|Integer} info - the camera_info type, see {@link camera_info} for available
* values
* @return {String|undefined}
*/
getCameraInfo(info) {
const funcName = 'Sensor.getCameraInfo()';
checkArgumentLength(1, 1, arguments.length, funcName);
const i = checkArgumentType(arguments, constants.camera_info, 0, funcName);
return (this.cxxSensor.supportsCameraInfo(i) ? this.cxxSensor.getCameraInfo(i) : undefined);
}
/**
* Stops any streaming and close subdevice.
* @return {undefined} No return value
*/
close() {
this.cxxSensor.close();
}
/**
* Delete the resource for accessing the subdevice. The device would not be accessable from
* this object after the operation.
* @return {undefined} No return value
*/
destroy() {
this._events = null;
if (this.cxxSensor) {
this.cxxSensor.destroy();
this.cxxSensor = undefined;
}
}
/**
* This callback is called when a frame is captured
* @callback FrameCallback
* @param {Frame} frame - The captured frame
*
* @see [Sensor.start]{@link Sensor#start}
*/
/**
* Start passing frames into user provided callback
* There are 2 acceptable syntax:
* <pre><code>
* Syntax 1. start(callback)
* Syntax 2. start(Syncer)
* </code></pre>
*
* @param {FrameCallback} callback
* @param {Syncer} syncer, the syncer to synchronize frames
*
* @example <caption>Simply do logging when a frame is captured</caption>
* sensor.start((frame) => {
* console.log(frame.timestamp, frame.frameNumber, frame.data);
* });
*
*/
start(callback) {
const funcName = 'Sensor.start()';
checkArgumentLength(1, 1, arguments.length, funcName);
if (arguments[0] instanceof Syncer) {
this.cxxSensor.startWithSyncer(arguments[0].cxxSyncer, false, 0);
} else {
checkArgumentType(arguments, 'function', 0, funcName);
// create object to hold frames generated from native.
this.frame = new Frame();
this.depthFrame = new DepthFrame();
this.videoFrame = new VideoFrame();
this.disparityFrame = new DisparityFrame();
this.motionFrame = new MotionFrame();
this.poseFrame = new PoseFrame();
let inst = this;
this.cxxSensor.frameCallback = function() {
// When the callback is triggered, the underlying frame bas been saved in the objects
// created above, we need to update it and callback.
if (inst.disparityFrame.isValid) {
inst.disparityFrame.updateProfile();
callback(inst.disparityFrame);
} else if (inst.depthFrame.isValid) {
inst.depthFrame.updateProfile();
callback(inst.depthFrame);
} else if (inst.videoFrame.isValid) {
inst.videoFrame.updateProfile();
callback(inst.videoFrame);
} else if (inst.motionFrame.isValid) {
inst.motionFrame.updateProfile();
callback(inst.motionFrame);
} else if (inst.poseFrame.isValid) {
inst.poseFrame.updateProfile();
callback(inst.poseFrame);
} else {
inst.frame.updateProfile();
callback(inst.frame);
}
};
this.cxxSensor.startWithCallback('frameCallback', this.frame.cxxFrame,
this.depthFrame.cxxFrame, this.videoFrame.cxxFrame, this.disparityFrame.cxxFrame,
this.motionFrame.cxxFrame, this.poseFrame.cxxFrame);
}
}
/**
* stop streaming
* @return {undefined} No return value
*/
stop() {
if (this.cxxSensor) {
this.cxxSensor.stop();
}
if (this.frame) this.frame.release();
if (this.videoFrame) this.videoFrame.release();
if (this.depthFrame) this.depthFrame.release();
}
/**
* @typedef {Object} NotificationEventObject
* @property {String} descr - The human readable literal description of the notification
* @property {Float} timestamp - The timestamp of the notification
* @property {String} severity - The severity of the notification
* @property {String} category - The category of the notification
* @property {String} serializedData - The serialized data of the notification
*/
/**
* This callback is called when there is a device notification
* @callback NotificationCallback
* @param {NotificationEventObject} info
* @param {String} info.descr - See {@link NotificationEventObject} for details
* @param {Float} info.timestamp - See {@link NotificationEventObject} for details
* @param {String} info.severity - See {@link NotificationEventObject} for details
* @param {String} info.category - See {@link NotificationEventObject} for details
* @param {String} info.serializedData - See {@link NotificationEventObject} for details
*
* @see {@link NotificationEventObject}
* @see [Sensor.setNotificationsCallback()]{@link Sensor#setNotificationsCallback}
*/
/**
* @event Sensor#notification
* @param {NotificationEventObject} evt
* @param {String} evt.descr - See {@link NotificationEventObject} for details
* @param {Float} evt.timestamp - See {@link NotificationEventObject} for details
* @param {String} evt.severity - See {@link NotificationEventObject} for details
* @param {String} evt.category - See {@link NotificationEventObject} for details
* @param {String} evt.serializedData - See {@link NotificationEventObject} for details
* @see {@link NotificationEventObject}
* @see [Sensor.setNotificationsCallback()]{@link Sensor#setNotificationsCallback}
*/
/**
* register notifications callback
* @param {NotificationCallback} callback The user-provied notifications callback
* @see {@link NotificationEventObject}
* @see [Sensor 'notification']{@link Sensor#event:notification} event
* @return {undefined}
*/
setNotificationsCallback(callback) {
const funcName = 'Sensor.setNotificationsCallback()';
checkArgumentLength(1, 1, arguments.length, funcName);
checkArgumentType(arguments, 'function', 0, funcName);
this._events.on('notification', (info) => {
callback(info);
});
let inst = this;
if (!this.cxxSensor.notificationCallback) {
this.cxxSensor.notificationCallback = function(info) {
// convert the severity and category properties from numbers to strings to be
// consistent with documentation which are more meaningful to users
info.severity = log_severity.logSeverityToString(info.severity);
info.category = notification_category.notificationCategoryToString(info.category);
inst._events.emit('notification', info);
};
this.cxxSensor.setNotificationCallback('notificationCallback');
}
return undefined;
}
/**
* Get a list of stream profiles that given subdevice can provide. The returned profiles should be
* destroyed by calling its destroy() method.
*
* @return {StreamProfile[]} all of the supported stream profiles
* See {@link StreamProfile}
*/
getStreamProfiles() {
let profiles = this.cxxSensor.getStreamProfiles();
if (profiles) {
const array = [];
profiles.forEach((profile) => {
array.push(StreamProfile._internalCreateStreamProfile(profile));
});
return array;
}
}
}
/**
* Sensor for managing region of interest.
*/
class ROISensor extends Sensor {
/**
* Create a ROISensor out of another sensor
* @param {Sensor} sensor a sensor object
* @return {ROISensor|undefined} return a ROISensor if the sensor can be
* treated as a ROISensor, otherwise return undefined.
*/
static from(sensor) {
if (sensor.cxxSensor.isROISensor()) {
return new ROISensor(sensor.cxxSensor);
}
return undefined;
}
/**
* Construct a ROISensor object, representing a RealSense camera subdevice
* The newly created ROISensor object shares native resources with the sensor
* argument. So the new object shouldn't be freed automatically to make
* sure resources released only once during cleanup.
*/
constructor(cxxSensor) {
super(cxxSensor, false);
}
/**
* @typedef {Object} RegionOfInterestObject
* @property {Float32} minX - lower horizontal bound in pixels
* @property {Float32} minY - lower vertical bound in pixels
* @property {Float32} maxX - upper horizontal bound in pixels
* @property {Float32} maxY - upper vertical bound in pixels
* @see [Device.getRegionOfInterest()]{@link Device#getRegionOfInterest}
*/
/**
* Get the active region of interest to be used by auto-exposure algorithm.
* @return {RegionOfInterestObject|undefined} Returns undefined if failed
* @see {@link RegionOfInterestObject}
*/
getRegionOfInterest() {
return this.cxxSensor.getRegionOfInterest();