0
# Sensors & Streaming
1
2
Low-level sensor control for advanced applications requiring precise stream configuration, custom frame processing, or multi-device synchronization. Provides direct access to individual sensors and their capabilities.
3
4
## Capabilities
5
6
### Base Sensor
7
8
Core sensor interface with streaming and configuration capabilities.
9
10
```python { .api }
11
class sensor:
12
def get_stream_profiles() -> list[stream_profile]:
13
"""
14
Get all available stream profiles for this sensor.
15
16
Returns:
17
list[stream_profile]: Available stream configurations
18
"""
19
20
@property
21
def profiles(self) -> list[stream_profile]:
22
"""All available stream profiles."""
23
24
def open(profile):
25
"""
26
Open sensor with single stream profile.
27
28
Args:
29
profile (stream_profile): Stream configuration to open
30
"""
31
32
def open(profiles):
33
"""
34
Open sensor with multiple stream profiles.
35
36
Args:
37
profiles (list[stream_profile]): Stream configurations to open
38
"""
39
40
def close():
41
"""Close sensor and stop streaming."""
42
43
def get_active_streams() -> list[stream_profile]:
44
"""
45
Get currently active stream profiles.
46
47
Returns:
48
list[stream_profile]: Active stream configurations
49
"""
50
51
def start(callback_function):
52
"""
53
Start streaming with frame callback.
54
55
Args:
56
callback_function: Function called for each frame
57
"""
58
59
def start(syncer):
60
"""
61
Start streaming into frame synchronizer.
62
63
Args:
64
syncer (syncer): Frame synchronizer
65
"""
66
67
def start(frame_queue):
68
"""
69
Start streaming into frame queue.
70
71
Args:
72
frame_queue (frame_queue): Frame buffer queue
73
"""
74
75
def stop():
76
"""Stop streaming."""
77
78
@property
79
def name(self) -> str:
80
"""Sensor name if available."""
81
82
def supports(camera_info) -> bool:
83
"""
84
Check if sensor supports information field.
85
86
Args:
87
camera_info (camera_info): Information field to check
88
89
Returns:
90
bool: True if supported
91
"""
92
93
def get_info(camera_info) -> str:
94
"""
95
Get sensor information.
96
97
Args:
98
camera_info (camera_info): Information field to retrieve
99
100
Returns:
101
str: Information value
102
"""
103
104
def get_recommended_filters() -> list[filter]:
105
"""
106
Get recommended processing filters for this sensor.
107
108
Returns:
109
list[filter]: Recommended filters
110
"""
111
112
def set_notifications_callback(callback):
113
"""
114
Set callback for sensor notifications.
115
116
Args:
117
callback: Function called with notification events
118
"""
119
120
# Type checking methods
121
def is_depth_sensor() -> bool:
122
"""Check if sensor is a depth sensor."""
123
124
def is_color_sensor() -> bool:
125
"""Check if sensor is a color sensor."""
126
127
def is_motion_sensor() -> bool:
128
"""Check if sensor is a motion sensor."""
129
130
def is_fisheye_sensor() -> bool:
131
"""Check if sensor is a fisheye sensor."""
132
133
def is_pose_sensor() -> bool:
134
"""Check if sensor is a pose sensor."""
135
136
def is_roi_sensor() -> bool:
137
"""Check if sensor supports region of interest."""
138
139
# Type casting methods
140
def as_depth_sensor() -> depth_sensor:
141
"""Cast to depth sensor."""
142
143
def as_color_sensor() -> color_sensor:
144
"""Cast to color sensor."""
145
146
def as_motion_sensor() -> motion_sensor:
147
"""Cast to motion sensor."""
148
149
def as_fisheye_sensor() -> fisheye_sensor:
150
"""Cast to fisheye sensor."""
151
152
def as_pose_sensor() -> pose_sensor:
153
"""Cast to pose sensor."""
154
155
def as_roi_sensor() -> roi_sensor:
156
"""Cast to ROI sensor."""
157
158
@staticmethod
159
def from_frame(frame) -> sensor:
160
"""
161
Get sensor that produced a frame.
162
163
Args:
164
frame (frame): Frame to trace back to sensor
165
166
Returns:
167
sensor: Originating sensor
168
"""
169
```
170
171
### Specialized Sensor Types
172
173
#### Depth Sensor
174
175
```python { .api }
176
class depth_sensor(sensor):
177
def get_depth_scale() -> float:
178
"""
179
Get depth scale factor (meters per depth unit).
180
181
Returns:
182
float: Depth scale in meters per unit
183
"""
184
```
185
186
#### Depth Stereo Sensor
187
188
```python { .api }
189
class depth_stereo_sensor(depth_sensor):
190
def get_stereo_baseline() -> float:
191
"""
192
Get stereo baseline distance.
193
194
Returns:
195
float: Baseline distance in millimeters
196
"""
197
```
198
199
#### ROI Sensor
200
201
```python { .api }
202
class roi_sensor(sensor):
203
def set_region_of_interest(roi):
204
"""
205
Set region of interest for processing.
206
207
Args:
208
roi (region_of_interest): ROI bounds
209
"""
210
211
def get_region_of_interest() -> region_of_interest:
212
"""
213
Get current region of interest.
214
215
Returns:
216
region_of_interest: Current ROI bounds
217
"""
218
```
219
220
#### Pose Sensor
221
222
```python { .api }
223
class pose_sensor(sensor):
224
def import_localization_map(map_data):
225
"""
226
Import localization map data.
227
228
Args:
229
map_data (bytes): Map data to import
230
"""
231
232
def export_localization_map() -> bytes:
233
"""
234
Export current localization map.
235
236
Returns:
237
bytes: Map data
238
"""
239
240
def set_static_node(guid, position, orientation):
241
"""
242
Set static node in map.
243
244
Args:
245
guid (str): Node unique identifier
246
position (list[float]): 3D position [x, y, z]
247
orientation (list[float]): Quaternion [x, y, z, w]
248
"""
249
250
def get_static_node(guid) -> tuple[bool, list[float], list[float]]:
251
"""
252
Get static node from map.
253
254
Args:
255
guid (str): Node unique identifier
256
257
Returns:
258
tuple: (success, position, orientation)
259
"""
260
261
def remove_static_node(guid):
262
"""
263
Remove static node from map.
264
265
Args:
266
guid (str): Node unique identifier
267
"""
268
```
269
270
#### Motion & Other Sensors
271
272
```python { .api }
273
class color_sensor(sensor):
274
"""Color camera sensor - inherits base sensor functionality."""
275
276
class motion_sensor(sensor):
277
"""IMU/motion sensor - inherits base sensor functionality."""
278
279
class fisheye_sensor(sensor):
280
"""Fisheye camera sensor - inherits base sensor functionality."""
281
282
class wheel_odometer(sensor):
283
def load_wheel_odometery_config(config_data):
284
"""
285
Load wheel odometry configuration.
286
287
Args:
288
config_data (bytes): Configuration data
289
"""
290
291
def send_wheel_odometry(sensor_id, frame_num, translational_velocity):
292
"""
293
Send wheel odometry data.
294
295
Args:
296
sensor_id (int): Sensor identifier
297
frame_num (int): Frame number
298
translational_velocity (list[float]): Velocity vector [x, y, z]
299
"""
300
301
class max_usable_range_sensor(sensor):
302
def get_max_usable_depth_range() -> float:
303
"""
304
Get maximum usable depth range.
305
306
Returns:
307
float: Maximum range in meters
308
"""
309
310
class debug_stream_sensor(sensor):
311
def get_debug_stream_profiles() -> list[stream_profile]:
312
"""
313
Get debug stream profiles.
314
315
Returns:
316
list[stream_profile]: Debug stream configurations
317
"""
318
```
319
320
### Stream Profiles
321
322
Stream configuration and parameter definitions.
323
324
```python { .api }
325
class stream_profile:
326
def stream_index() -> int:
327
"""
328
Get stream index for multi-instance streams.
329
330
Returns:
331
int: Stream index
332
"""
333
334
def stream_type() -> stream:
335
"""
336
Get stream type.
337
338
Returns:
339
stream: Stream type enum
340
"""
341
342
def format() -> format:
343
"""
344
Get data format.
345
346
Returns:
347
format: Data format enum
348
"""
349
350
def fps() -> int:
351
"""
352
Get framerate.
353
354
Returns:
355
int: Frames per second
356
"""
357
358
def unique_id() -> int:
359
"""
360
Get unique stream identifier.
361
362
Returns:
363
int: Unique ID
364
"""
365
366
def stream_name() -> str:
367
"""
368
Get stream name.
369
370
Returns:
371
str: Human-readable stream name
372
"""
373
374
def is_default() -> bool:
375
"""
376
Check if this is the default profile for the stream.
377
378
Returns:
379
bool: True if default profile
380
"""
381
382
def bytes_per_pixel() -> int:
383
"""
384
Get bytes per pixel for this format.
385
386
Returns:
387
int: Bytes per pixel
388
"""
389
390
def get_extrinsics_to(other_profile) -> extrinsics:
391
"""
392
Get extrinsic transformation to another stream.
393
394
Args:
395
other_profile (stream_profile): Target stream profile
396
397
Returns:
398
extrinsics: Transformation parameters
399
"""
400
401
def register_extrinsics_to(other_profile, extrinsics):
402
"""
403
Register extrinsic transformation to another stream.
404
405
Args:
406
other_profile (stream_profile): Target stream profile
407
extrinsics (extrinsics): Transformation parameters
408
"""
409
410
def clone(stream_type, stream_index, format) -> stream_profile:
411
"""
412
Clone profile with different parameters.
413
414
Args:
415
stream_type (stream): New stream type
416
stream_index (int): New stream index
417
format (format): New format
418
419
Returns:
420
stream_profile: Cloned profile
421
"""
422
423
# Type checking and casting
424
def is_video_stream_profile() -> bool:
425
"""Check if profile is for video stream."""
426
427
def is_motion_stream_profile() -> bool:
428
"""Check if profile is for motion stream."""
429
430
def is_pose_stream_profile() -> bool:
431
"""Check if profile is for pose stream."""
432
433
def as_video_stream_profile() -> video_stream_profile:
434
"""Cast to video stream profile."""
435
436
def as_motion_stream_profile() -> motion_stream_profile:
437
"""Cast to motion stream profile."""
438
439
def as_pose_stream_profile() -> pose_stream_profile:
440
"""Cast to pose stream profile."""
441
```
442
443
#### Video Stream Profile
444
445
```python { .api }
446
class video_stream_profile(stream_profile):
447
def width() -> int:
448
"""
449
Get frame width.
450
451
Returns:
452
int: Width in pixels
453
"""
454
455
def height() -> int:
456
"""
457
Get frame height.
458
459
Returns:
460
int: Height in pixels
461
"""
462
463
def get_intrinsics() -> intrinsics:
464
"""
465
Get camera intrinsic parameters.
466
467
Returns:
468
intrinsics: Camera calibration parameters
469
"""
470
471
@property
472
def intrinsics(self) -> intrinsics:
473
"""Camera intrinsic parameters."""
474
```
475
476
#### Motion Stream Profile
477
478
```python { .api }
479
class motion_stream_profile(stream_profile):
480
def get_motion_intrinsics() -> motion_device_intrinsic:
481
"""
482
Get motion sensor intrinsic parameters.
483
484
Returns:
485
motion_device_intrinsic: IMU calibration parameters
486
"""
487
```
488
489
#### Pose Stream Profile
490
491
```python { .api }
492
class pose_stream_profile(stream_profile):
493
"""Pose stream profile - inherits base functionality."""
494
```
495
496
### Notifications
497
498
Sensor notification system for device events and status changes.
499
500
```python { .api }
501
class notification:
502
def get_category() -> notification_category:
503
"""
504
Get notification category.
505
506
Returns:
507
notification_category: Notification type
508
"""
509
510
def get_description() -> str:
511
"""
512
Get human-readable description.
513
514
Returns:
515
str: Notification description
516
"""
517
518
def get_timestamp() -> float:
519
"""
520
Get notification timestamp.
521
522
Returns:
523
float: Timestamp in milliseconds
524
"""
525
526
def get_severity() -> log_severity:
527
"""
528
Get notification severity level.
529
530
Returns:
531
log_severity: Severity level
532
"""
533
534
def get_serialized_data() -> str:
535
"""
536
Get serialized notification data.
537
538
Returns:
539
str: Serialized data
540
"""
541
542
# Properties (read-only)
543
@property
544
def category(self) -> notification_category:
545
"""Notification category."""
546
547
@property
548
def description(self) -> str:
549
"""Notification description."""
550
551
@property
552
def timestamp(self) -> float:
553
"""Notification timestamp."""
554
555
@property
556
def severity(self) -> log_severity:
557
"""Notification severity."""
558
559
@property
560
def serialized_data(self) -> str:
561
"""Serialized notification data."""
562
```
563
564
## Usage Examples
565
566
### Low-Level Sensor Control
567
568
```python
569
import pyrealsense2 as rs
570
571
# Get device and sensors
572
ctx = rs.context()
573
device = ctx.query_devices()[0]
574
sensors = device.query_sensors()
575
576
# Find depth sensor
577
depth_sensor = None
578
for sensor in sensors:
579
if sensor.is_depth_sensor():
580
depth_sensor = sensor.as_depth_sensor()
581
break
582
583
if not depth_sensor:
584
print("No depth sensor found")
585
exit()
586
587
# Get available profiles
588
profiles = depth_sensor.get_stream_profiles()
589
print(f"Found {len(profiles)} stream profiles:")
590
591
for i, profile in enumerate(profiles):
592
vp = profile.as_video_stream_profile()
593
print(f" {i}: {vp.stream_type().name} "
594
f"{vp.width()}x{vp.height()} "
595
f"{vp.format().name} @ {vp.fps()}fps")
596
597
# Select 640x480 Z16 profile
598
selected_profile = None
599
for profile in profiles:
600
vp = profile.as_video_stream_profile()
601
if (vp.width() == 640 and vp.height() == 480 and
602
vp.format() == rs.format.z16):
603
selected_profile = profile
604
break
605
606
if selected_profile:
607
print(f"Selected profile: {selected_profile.stream_name()}")
608
609
# Open and start streaming
610
depth_sensor.open(selected_profile)
611
612
# Use frame queue for processing
613
frame_queue = rs.frame_queue(capacity=10)
614
depth_sensor.start(frame_queue)
615
616
try:
617
for i in range(50):
618
frame = frame_queue.wait_for_frame(timeout_ms=1000)
619
depth_frame = frame.as_depth_frame()
620
621
print(f"Frame {depth_frame.get_frame_number()}: "
622
f"{depth_frame.get_width()}x{depth_frame.get_height()}")
623
624
finally:
625
depth_sensor.stop()
626
depth_sensor.close()
627
```
628
629
### Multi-Sensor Streaming
630
631
```python
632
import pyrealsense2 as rs
633
import threading
634
635
class FrameProcessor:
636
def __init__(self):
637
self.frame_count = 0
638
self.lock = threading.Lock()
639
640
def depth_callback(self, frame):
641
with self.lock:
642
self.frame_count += 1
643
depth_frame = frame.as_depth_frame()
644
print(f"Depth frame {depth_frame.get_frame_number()}")
645
646
def color_callback(self, frame):
647
with self.lock:
648
self.frame_count += 1
649
color_frame = frame.as_video_frame()
650
print(f"Color frame {color_frame.get_frame_number()}")
651
652
# Get device and sensors
653
ctx = rs.context()
654
device = ctx.query_devices()[0]
655
656
# Find sensors
657
depth_sensor = device.first_depth_sensor()
658
color_sensor = device.first_color_sensor()
659
660
# Configure sensors
661
depth_profiles = depth_sensor.get_stream_profiles()
662
color_profiles = color_sensor.get_stream_profiles()
663
664
# Select profiles (simplified selection)
665
depth_profile = depth_profiles[0] # Use first available
666
color_profile = color_profiles[0] # Use first available
667
668
processor = FrameProcessor()
669
670
# Start streaming
671
depth_sensor.open(depth_profile)
672
color_sensor.open(color_profile)
673
674
depth_sensor.start(processor.depth_callback)
675
color_sensor.start(processor.color_callback)
676
677
try:
678
import time
679
time.sleep(5) # Stream for 5 seconds
680
finally:
681
depth_sensor.stop()
682
color_sensor.stop()
683
depth_sensor.close()
684
color_sensor.close()
685
686
print(f"Processed {processor.frame_count} frames total")
687
```
688
689
### Sensor Information and Capabilities
690
691
```python
692
import pyrealsense2 as rs
693
694
ctx = rs.context()
695
device = ctx.query_devices()[0]
696
697
for i, sensor in enumerate(device.query_sensors()):
698
print(f"\nSensor {i}:")
699
700
if sensor.supports(rs.camera_info.name):
701
print(f" Name: {sensor.get_info(rs.camera_info.name)}")
702
703
# Check sensor type
704
sensor_types = []
705
if sensor.is_depth_sensor():
706
sensor_types.append("Depth")
707
ds = sensor.as_depth_sensor()
708
print(f" Depth Scale: {ds.get_depth_scale()}")
709
710
if sensor.is_roi_sensor():
711
sensor_types.append("ROI")
712
713
if sensor.is_color_sensor():
714
sensor_types.append("Color")
715
716
if sensor.is_motion_sensor():
717
sensor_types.append("Motion")
718
719
if sensor.is_fisheye_sensor():
720
sensor_types.append("Fisheye")
721
722
if sensor.is_pose_sensor():
723
sensor_types.append("Pose")
724
725
print(f" Types: {', '.join(sensor_types)}")
726
727
# List stream profiles
728
profiles = sensor.get_stream_profiles()
729
print(f" Stream Profiles: {len(profiles)}")
730
731
for j, profile in enumerate(profiles[:5]): # Show first 5
732
if profile.is_video_stream_profile():
733
vp = profile.as_video_stream_profile()
734
print(f" {j}: {vp.stream_type().name} "
735
f"{vp.width()}x{vp.height()} "
736
f"{vp.format().name} @ {vp.fps()}fps")
737
else:
738
print(f" {j}: {profile.stream_type().name} "
739
f"{profile.format().name} @ {profile.fps()}fps")
740
741
# Get recommended filters
742
filters = sensor.get_recommended_filters()
743
if filters:
744
filter_names = [type(f).__name__ for f in filters]
745
print(f" Recommended Filters: {', '.join(filter_names)}")
746
```
747
748
### Notification Handling
749
750
```python
751
import pyrealsense2 as rs
752
import time
753
754
def notification_callback(notification):
755
print(f"Notification: {notification.get_description()}")
756
print(f" Category: {notification.get_category().name}")
757
print(f" Severity: {notification.get_severity().name}")
758
print(f" Timestamp: {notification.get_timestamp()}")
759
760
ctx = rs.context()
761
device = ctx.query_devices()[0]
762
sensor = device.query_sensors()[0]
763
764
# Set notification callback
765
sensor.set_notifications_callback(notification_callback)
766
767
# Start streaming to trigger notifications
768
profiles = sensor.get_stream_profiles()
769
if profiles:
770
sensor.open(profiles[0])
771
772
frame_queue = rs.frame_queue()
773
sensor.start(frame_queue)
774
775
try:
776
time.sleep(5) # Monitor for 5 seconds
777
finally:
778
sensor.stop()
779
sensor.close()
780
```
781
782
### Intrinsics and Extrinsics
783
784
```python
785
import pyrealsense2 as rs
786
787
ctx = rs.context()
788
device = ctx.query_devices()[0]
789
790
# Get depth and color sensors
791
depth_sensor = device.first_depth_sensor()
792
color_sensor = device.first_color_sensor()
793
794
# Get profiles
795
depth_profiles = depth_sensor.get_stream_profiles()
796
color_profiles = color_sensor.get_stream_profiles()
797
798
# Find matching resolution profiles
799
depth_profile = None
800
color_profile = None
801
802
for dp in depth_profiles:
803
if dp.is_video_stream_profile():
804
dvp = dp.as_video_stream_profile()
805
if dvp.width() == 640 and dvp.height() == 480:
806
depth_profile = dp
807
break
808
809
for cp in color_profiles:
810
if cp.is_video_stream_profile():
811
cvp = cp.as_video_stream_profile()
812
if cvp.width() == 640 and cvp.height() == 480:
813
color_profile = cp
814
break
815
816
if depth_profile and color_profile:
817
# Get intrinsics
818
depth_intrinsics = depth_profile.as_video_stream_profile().get_intrinsics()
819
color_intrinsics = color_profile.as_video_stream_profile().get_intrinsics()
820
821
print("Depth Intrinsics:")
822
print(f" Resolution: {depth_intrinsics.width}x{depth_intrinsics.height}")
823
print(f" Principal Point: ({depth_intrinsics.ppx}, {depth_intrinsics.ppy})")
824
print(f" Focal Length: ({depth_intrinsics.fx}, {depth_intrinsics.fy})")
825
print(f" Distortion Model: {depth_intrinsics.model}")
826
827
print("\nColor Intrinsics:")
828
print(f" Resolution: {color_intrinsics.width}x{color_intrinsics.height}")
829
print(f" Principal Point: ({color_intrinsics.ppx}, {color_intrinsics.ppy})")
830
print(f" Focal Length: ({color_intrinsics.fx}, {color_intrinsics.fy})")
831
832
# Get extrinsics between streams
833
extrinsics = depth_profile.get_extrinsics_to(color_profile)
834
print(f"\nDepth to Color Extrinsics:")
835
print(f" Translation: {extrinsics.translation}")
836
print(f" Rotation: {extrinsics.rotation}")
837
```