# DepthAI ROS Driver

Currently, recommended way to launch cameras is to use executables from depthai_ros_driver package.

This runs your camera as a ROS2 Component/ROS Nodelet and gives you the ability to customize your camera using ROS parameters.

Main API difference between ROS2 and ROS1 is that parameter names use different convention - parameters in ROS2 are namespaced
using . and parameters in ROS1 are namespaced using _, for example in ROS2: camera.i_pipeline_type, ROS1 camera_i_pipeline_type.
For sake of simplicity, this Readme uses ROS2 convention. List of all available parameters with their default values can be found
at the bottom of Readme.

Parameters that begin with r_ can be freely modified during runtime, for example with rqt.

Parameters that begin with i_ are set when camera is initializing, to change them you have to call stop and start services. This
can be used to hot swap NNs during runtime, changing resolutions, etc.

## Launch files

We provide few examples for [depthai-ros-driver](https://github.com/luxonis/depthai-ros/tree/humble/depthai_ros_driver) package:

 * camera.launch.py launches camera in RGBD, and NN in spatial (Mobilenet) mode.
 * rgbd_pcl.launch.py launches camera in basic RGBD configuration, doesn't load any NNs. Also loads ROS depth processing nodes for
   RGBD pointcloud.
 * example_multicam.launch.py launches several cameras at once, each one in different container. Edit the multicam_example.yaml
   config file in config directory to change parameters
 * example_segmentation.launch.py launches camera in RGBD + semantic segmentation (pipeline type=RGBD, nn_type=rgb)
 * pointcloud.launch.py - similar to rgbd_pcl.launch.py, but doesn't use RGB component for pointcloud
 * example_marker_publish.launch.py launches camera.launch.py + small python node that publishes detected objects as markers/tfs
 * rtabmap.launch.py launches camera and RTAB-MAP RGBD SLAM (you need to install it first - sudo apt install
   ros-$ROS_DISTRO-rtabmap-ros). You might need to set manual focus via parameters here.

To launch them, you can run:

 * ros2 launch depthai_ros_driver camera.launch.py (ROS2)
 * roslaunch depthai_ros_driver camera.launch (ROS1)

## Publishing TFs from extrinsics

By default, camera transforms are published from default URDF descriptions based on CAD models. This can be overridden by using
TFPublisher class from depthai_bridge, which based on Device's camera calibration data republishes the description with updated
information. To enable this behavior in depthai_ros_driver, you can use following parameters:

 * camera.i_publish_tf_from_calibration - setting this to true launches TFPublisher

Then you can set following arguments:

 * camera.i_tf_camera_name - if not set, defaults to the node name
 * camera.i_tf_camera_model - if not set, it will be automatically detected. If the node is unable to detect STL file for the
   camera it is set to OAK-D. To explicitly set it in camera.launch.py, set override_cam_model:=true
 * camera.i_tf_base_frame
 * camera.i_tf_parent_frame
 * camera.i_tf_cam_pos_x
 * camera.i_tf_cam_pos_y
 * camera.i_tf_cam_pos_z
 * camera.i_tf_cam_roll
 * camera.i_tf_cam_pitch
 * camera.i_tf_cam_yaw

When using camera.launch.py, you can set pass_tf_args_as_params:=true so that TF arguments are used to fill those parameters. For
example ros2 launch depthai_ros_driver camera.launch.py pass_tf_args_as_params:=true parent_frame:=map cam_pos_x:=1.0
imu_from_descr:=true

It is also possible to set custom URDF path (for now only absolute path works) and custom xacro arguments using
camera.i_tf_custom_urdf_path and camera.i_tf_custom_xacro_args. Please note that robot_state_publisher must be running.

> **Note on Extrinsics**
> If your camera has uncalibrated IMU, a warning will be shown, and IMU will be published with zero rotation and translation. You
can override this behavior by setting
> `camera.i_tf_imu_from_descr: true`
> . This will publish default IMU extrinsics from URDF based on camera model.

## Available sensors and their resolutions:

 * IMX378 - {"12MP", "4K", "1080P"}, default 1080P
 * OV9282 - {"800P", "720P", "400P"}, default 800P
 * OV9782 - {"800P", "720P", "400P"}, default 800P
 * OV9281 - {"800P", "720P", "400P"}, default 800P
 * IMX214 - {"13MP", "12MP", "4K", "1080P"}, default 1080P
 * IMX412 - {"13MP", "12MP", "4K", "1080P"}, default 1080P
 * OV7750 - {"480P", "400P"}, default 480P
 * OV7251 - {"480P", "400P"}, default 480P
 * IMX477 - {"12MP", "4K", "1080P"}, default 1080P
 * IMX577 - {"12MP", "4K", "1080P"}, default 1080P
 * AR0234 - {"1200P"}, default 1200P
 * IMX582 - {"48MP", "12MP", "4K"}, default 4K
 * LCM48 - {"48MP", "12MP", "4K"}, default 4K

## Setting RGB parameters

By default RGB camera outputs ISP frame. To set custom width and height of output image, you can set i_isp_num and i_isp_den which
scale image dimensions (2 and 3 by default, so from 1920x1080 to 1280x720), note for RGBD alignment to work resulting width and
height must be divisible by 16.

Additionally you can set i.output_isp: false to use video output and set custom size using i_width and i_height parameters.

## Setting Stereo parameters

### Depth alignment

When setting stereo.i_align_depth: true, stereo output is aligned to board socket specified by stereo.i_board_socket_id parameter
(by default 0/CAM_A)

You can enable rectified Stereo streams by setting, for example in the case of right stream i_publish_right_rect: true. You can
also set i_publish_synced_rect_pair: true to get both images with the same timestamps.

### Stereo socket order

By default, right camera is treated as first when used for stereo computation, which is reflected in CameraInfo messages. If you
want to reverse that logic, set stereo.i_reverse_stereo_socket_order: true (this can be also set for individual sensors).

### Custom Sensor sockets

Configuration of which sensors are used for computing stereo pair can be done either programmatically, by specifying them in a
constructor of a Stereo node (for example when building a custom pipeline), or via parameters -
stereo.i_left_socket_id/stereo.i_right_socket_id. Please note that currently if you want to use rgb/center socket instead of one
of the given pairs you will need to build a custom pipeline for that.

## Feature Tracker

Each sensor node (and rectified streams from Stereo node) has the option to add FeatureTracker node, which publishes
depthai_ros_msgs/msg/TrackedFeatures messages. To enable features on, for example rgb node, set rgb: i_enable_feature_tracker:
true. To enable publishing on rectified streams, set for example stereo: i_left_rect_enable_feature_tracker

## Setting IMU parameters

Parameters:

 * i_acc_freq: 400 - Accelerometer sensor frequency
 * i_acc_cov: 0.0 - Accelerometer covariance
 * i_batch_report_threshold: 1 - Batch report size
 * i_enable_rotation: false - Whether to enable rotation vector & magnetometer data (available when using IMU_WITH_MAGN/
   IMU_WITH_MAGN_SPLIT message type)
 * i_gyro_cov: 0.0 - Gyroscope covariance
 * i_gyro_freq: 400 - Gyroscope frequency
 * i_mag_cov: 0.0 - Magnetometer covariance
 * i_mag_freq: 100 - Magnetometer frequency
 * i_max_batch_reports: 10 - Max reports per batch
 * i_message_type: IMU - ROS publisher type:
 * IMU - sensor_msgs/Imu
 * IMU_WITH_MAG - depthai_ros_msgs/ImuWithMagneticField
 * IMU_WITH_MAG_SPLIT - two publishers - sensor_msgs/Imu & sensor_msgs/MagneticField
 * i_rot_cov: -1.0 - Rotation covariance
 * i_rot_freq: 400 - Rotation frequency
 * i_sync_method: LINEAR_INTERPOLATE_ACCEL - sync method. Available options:
 * COPY
 * LINEAR_INTERPOLATE_GYRO
 * LINEAR_INTERPOLATE_ACCEL
 * i_rotation_vector_type - type of rotation vector, for more information, refer to [this
   link](https://docs.luxonis.com/software/depthai-components/nodes/imu.md). Available options:
 * ROTATION_VECTOR
 * GAME_ROTATION_VECTOR
 * GEOMAGNETIC_ROTATION_VECTOR
 * ARVR_STABILIZED_ROTATION_VECTOR
 * ARVR_STABILIZED_GAME_ROTATION_VECTOR

## Stopping/starting camera for power saving/reconfiguration

Stopping camera also can be used for power saving, as pipeline is removed from the device. Topics are also removed when camera is
stopped.

There is also an option to enable auto restart if camera encounters an error. To do that, set
camera.i_restart_on_diagnostics_error: true

## Pipeline parameters

As for the parameters themselves, there are a few crucial ones that decide on how camera behaves.

 * camera_i_pipeline_type can be either
 * RGB - only publishes RGB stream , NN available
 * RGBD - Publishes RGB + Depth streams (set i_publish_topic for left and right cameras to enable them), NN & Spatial NN available
 * Stereo - Publishes streams from left and right sensors, NN can be set for each sensor separately
 * RGBStereo - Publishes RGB + Left + Right streams, NN can be set for each sensor separately
 * Depth - Publishes only depth stream, NN can be set on stereo node via parameter
 * CamArray - Publishes streams for all detected sensors, NN can be set for each sensor separately
 * Tof - Publishes only TOF stream, no NN available
 * DepthTof - Publishes Depth + TOF streams, specific to OAK-D-SR-POE, NN can be set on stereo node via parameter
 * StereoToF - Publishes Stereo + TOF streams, specific to OAK-D-SR-POE, NN can be set on stereo node via parameter
 * RGBToF - Publishes RGB + TOF streams, specific to OAK-D-SR-POE, NN can be set on stereo node via parameter This tells the
   camera whether it should load stereo components. Default set to RGBD. It is also possible to create a custom pipeline since all
   types are defined as plugins.

To do that, you can create a custom package (let's say test_plugins), create an executable in that package (test_plugins.cpp).
Inside that file, define a custom plugin that inherits from depthai_ros_driver::pipeline_gen::BasePipeline and overrides
createPipeline method.

After that export plugin, for example:

```c++
#include <pluginlib /class_list_macros.hpp>
  PLUGINLIB_EXPORT_CLASS(test_plugins::Test, depthai_ros_driver::pipeline_gen::BasePipeline)
```

Add plugin definition:

```xml
<library path="test_plugins">
    <class type="test_plugins::Test" base_class_type="depthai_ros_driver::pipeline_gen::BasePipeline">
      <description>Test Pipeline.</description>
    </class>
  </library>
```

Now you can use created plugin as pipeline, just set camera.i_pipeline_type to test_plugins::Test.

## Neural networks

Basic configuration options for cameras with 3 sensors can be controlled by 3 camera parameters:

 * camera.i_nn_type can be either none, rgb or spatial. This is responsible for whether the NN that we load should also take depth
   information (and for example provide detections in 3D format). Default set to spatial
 * camera.i_mx_id/camera.i_ip/camera.i_usb_port_id are for connecting to a specific camera. If not set, it automatically connects
   to the next available device. You can get those parameters from logs by running the default launch file.
 * nn.i_nn_config_path represents path to JSON that contains information on what type of NN to load, and what parameters to use.
   Currently we provide options to load MobileNet, Yolo and Segmentation (not in spatial) models. To see their example configs,
   navigate to depthai_ros_driver/config/nn. Defaults to mobilenet.json from depthai_ros_driver

To use provided example NN's, you can set the path to:

 * depthai_ros_driver/segmentation
 * depthai_ros_driver/mobilenet
 * depthai_ros_driver/yolo

You can also choose to run NN on a specific sensor by setting sensor_name.i_enable_nn to true. After that, you can similarly set
sensor_name_nn.i_nn_config_path to a path to a config file. You can also set up spatial NN for Stereo node and use one of its
left/right streams as rgb input. This can be enabled in cameras with RGB side sensors such as OAK-D-SR and OAK-D-LR. Setting up is
also similar:

 * stereo.i_enable_spatial_nn - set to true to enable spatial NN
 * stereo.i_spatial_nn_source - set to either left or right to choose which sensor to use as rgb input for NN
 * stereo_nn.i_nn_config_path - path to config file for spatial NN

All available camera-specific parameters and their default values can be seen in depthai_ros_driver/config/camera.yaml.

## Syncing

Currently you can sync any number of image topics with a sync node wrapper. To create a sync node, set pipeline_gen:
i_enable_sync: true, and, for example rgb.i_synced: true and stereo.i_synced: true. This example configuration is applied when
running camera.launch.py with pointcloud.enable:=true argument.

## Specific camera configurations

### PoE Cameras

Since PoE cameras use protocol that has lower throughput than USB, running default camera launch can result in lags depending on
chosen resolution/fps. To combat this issue, you can use encoded frames, which let you keep desired resolution/fps at the cost of
image quality reduction due to compression. One additional difference is that subpixel depth filtering is disabled in this mode.
To enable low_bandwidth, for example for rgb camera, change parameters:

 * rgb.i_low_bandwidth - true to enable
 * rgb.i_low_bandwidth_quality - desired quality % (default-50) See low_bandwidth.yaml file for example parameters for all streams

### ToF Cameras

OAK-D-SR-PoE due to it's specific configuration requires a separate launch file - sr_poe_rgbd_pcl.launch.py. This also utilizes
pipeline configuration specific to OAK-D-SR, you can find more information about the pipeline types above. Please note that
currently ToF cameras publish images in rgb frame due to sensor socket naming convention.

## RealSense compatibility

For quick integration test, you can use camera.launch.py with rs_compat:=true argument to miminc Realsense camera behavior. This
will set up camera with RGBD pipeline, and publish topics with names compatible with Realsense camera. TF frames will be also
available in Realsense format. Similarly to how RS node works, you can enable pointcloud publishing with pointcloud.enable:=true
argument. Please note that the driver will spawn with different name and namespace, as well as different DAI node names so you
might need to adjust your config files accordingly. Naming convention is as follows:

 * Namespace: '' -> camera
 * Node name: oak -> camera
 * rgb -> color
 * stereo -> depth
 * 'left' -> infra_2
 * 'right' -> infra_1
 * Frame oak -> camera_link

### Example

Let's take look at what changes would be needed for a launch file:

```python
# Example inclusion of RealSense driver
rs_camera_launch_include = IncludeLaunchDescription(
  PythonLaunchDescriptionSource([
      PathJoinSubstitution([
          FindPackageShare('realsense2_camera'),
          'launch',
          'rs_launch.py',
      ])
  ]),
  launch_arguments={
      'pointcloud.enable': true,
  }.items()
)
```

Following launch description will run the camera driver in RGBD mode with pointcloud enabled. Now to adjust to use OAK camera, you
would need to change the following:

```python
# Example inclusion of OAK driver
oak_camera_launch_include = IncludeLaunchDescription(
  PythonLaunchDescriptionSource([
      PathJoinSubstitution([
          FindPackageShare('depthai_ros_driver'),
          'launch',
          'camera.launch.py',
      ])
  ]),
  launch_arguments={
      'rs_compat': true,
      'pointcloud.enable': true,
  }.items()
)
```

This launches the camera with the same topics, the only change is that the default profile for depth is 1280x720x30 instead of
848x480x30.

### RTABMap example with RealSense compatibility

Let's take a look at one of the examples in rtabmap_ros package, realsense_d435i_color.launch.py. Note This example as of this
moment (2024-08-27) needs to be adjusted for RS topic names as follows:

#### Before

```python
remappings=[
('imu', '/imu/data'),
('rgb/image', '/camera/color/image_raw'),
('rgb/camera_info', '/camera/color/camera_info'),
('depth/image', '/camera/realigned_depth_to_color/image_raw')]
```

#### After

```python
remappings=[
('imu', '/imu/data'),
('rgb/image', '/camera/camera/color/image_raw'),
('rgb/camera_info', '/camera/camera/color/camera_info'),
('depth/image', '/camera/camera/depth/image_rect_raw')]
```

Now to launch the example with RS camera, per instruction you need to run following command:

```bash
ros2 launch realsense2_camera rs_launch.py enable_gyro:=true enable_accel:=true unite_imu_method:=1 enable_sync:=true
```

To launch the same example with OAK camera, you would need to run following command:

```bash
ros2 launch depthai_ros_driver camera.launch.py rs_compat:=true
```

Note that recommended approach for ROS2 nodes is to use components to improve performance and reduce latency. RS camera driver
does not provide a dedicated launch file for running camera node in component container (except intra_process_demo), so you would
need to create a custom container for that. DepthAI ROS driver's default launch file runs in composition mode by default, so you
can add more nodes in runtime to the same container. You can also refer to rtabmap.launch.py example in depthai_ros_driver package
for running RTABMap with OAK camera. You can also add slight modifications to also enable RS mode for this example.

## Recalibration

If you want to use other calibration values than the ones provided by the device, you can do it in following ways:

 * Use set_camera_info services available for each of the image streams
 * Use i_calibration_file parameter available to point to the calibration file. Note camera name must start with /, so for example
   /rgb. See depthai_ros_driver/config/calibration for example calibration files. calibration.launch file is provided to start up
   a ROS camera calibrator node in both monocular and stereo configurations. Calibration file syntax (from camera_info_manager):

```yaml
- file:///full/path/to/local/file.yaml
- file:///full/path/to/videre/file.ini
- package://camera_info_manager/tests/test_calibration.yaml
- package://ros_package_name/calibrations/camera3.yaml
```

## Using external sources for NN inference or Stereo Depth

There is a possibility of using external image topics as input for NNs or Depth calculation.

## Example scenarios

 1. We want to get segmentation or 2D detection output based on images published by usb camera node. This can be achieved by
    setting rgb.i_simulate_from_topic parameter to true. This creates sensor_msgs/Image subscriber listening by default on
    /<node_name>/rgb/input topic that passes data into the pipeline on each callback. Topic names can be changed either by classic
    ROS topic remapping or setting rgb.i_simulated_topic_name to a desired name. By default, original sensor node still runs and
    publishes data. Setting rgb.i_disable_node to true will prevent it from spawning. Check det2d_usb_cam_overlay.launch.py in
    `depthai_filters to see it in action.

 2. Calculating depth - both left and right sensor nodes can be setup as in the example above to calculate calculate
    depth/disparity from external topics. Note that for this to work properly you need specify:

 * left.i_board_socket_id: 1
 * right.i_board_socket_id: 2
 * Default stereo input size is set to 1280x720, in case of different image size, To set custom ones, set stereo.i_set_input_size:
   true and adjust stereo.i_input_width and stereo.i_input_height accordingly.
 * external calibration file path using camera.i_external_calibration_path parameter. To get calibration from the device you can
   either set camera.i_calibration_dump to true or call save_calibration service. Calibration will be saved to
   /tmp/<mx_id>_calibration.json. An example can be seen in stereo_from_rosbag.launch.py in depthai_ros_driver

## Developers guide

For easier development inside isolated workspace, one can use Visual Studio Code with DevContainers plugin, to do that:

 * Create separate workspace
 * Clone repository into src
 * Copy .devcontainer directory into main workspace directory
 * Open workspace directory in VSCode

## List of parameters

```yaml
/oak:
ros__parameters:
  camera:
    i_calibration_dump: false
    i_enable_diagnostics: true
    i_enable_ir: true
    i_enable_sync: false
    i_external_calibration_path: ""
    i_floodlight_brightness: 0
    i_ip: ""
    i_laser_dot_brightness: 800
    i_mx_id: ""
    i_nn_type: none
    i_pipeline_dump: false
    i_pipeline_type: RGBD
    i_publish_tf_from_calibration: false
    i_restart_on_diagnostics_error: false
    i_rs_compat: false
    i_tf_base_frame: oak
    i_tf_cam_pitch: "0.0"
    i_tf_cam_pos_x: "0.0"
    i_tf_cam_pos_y: "0.0"
    i_tf_cam_pos_z: "0.0"
    i_tf_cam_roll: "0.0"
    i_tf_cam_yaw: "0.0"
    i_tf_camera_model: ""
    i_tf_camera_name: oak
    i_tf_custom_urdf_location: ""
    i_tf_custom_xacro_args: ""
    i_tf_imu_from_descr: "false"
    i_tf_parent_frame: oak-d-base-frame
    i_usb_port_id: ""
    i_usb_speed: SUPER_PLUS
    diagnostic_updater:
    period: 1.0
  pipeline_gen:
    i_enable_diagnostics: true
    i_enable_imu: true
    i_enable_sync: false
  imu:
    i_acc_cov: 0.0
    i_acc_freq: 400
    i_batch_report_threshold: 5
    i_enable_rotation: false
    i_get_base_device_timestamp: false
    i_gyro_cov: 0.0
    i_gyro_freq: 400
    i_mag_cov: 0.0
    i_max_batch_reports: 10
    i_message_type: IMU
    i_rot_cov: -1.0
    i_sync_method: LINEAR_INTERPOLATE_ACCEL
    i_update_ros_base_time_on_ros_msg: false
  left:
    i_add_exposure_offset: false
    i_board_socket_id: 1
    i_calibration_file: ""
    i_disable_node: false
    i_enable_feature_tracker: false
    i_enable_lazy_publisher: true
    i_enable_nn: false
    i_exposure_offset: 0
    i_fps: 30.0
    i_fsync_continuous: false
    i_fsync_trigger: false
    i_get_base_device_timestamp: false
    i_height: 720
    i_low_bandiwdth_frame_freq: 30
    i_low_bandwidth: false
    i_low_bandwidth_bitrate: 0
    i_low_bandwidth_ffmpeg_encoder: libx264
    i_low_bandwidth_profile: 4
    i_low_bandwidth_quality: 50
    i_max_q_size: 30
    i_publish_compressed: false
    i_publish_topic: false
    i_resolution: 720P
    i_reverse_stereo_socket_order: false
    i_sensor_img_orientation: AUTO
    i_set_isp3a_fps: false
    i_simulate_from_topic: false
    i_simulated_topic_name: ""
    i_synced: false
    i_update_ros_base_time_on_ros_msg: false
    i_width: 1280
    r_exposure: 1000
    r_iso: 800
    r_set_man_exposure: false
  nn:
    i_board_socket_id: 0
    i_disable_resize: false
    i_enable_passthrough: false
    i_enable_passthrough_depth: false
    i_get_base_device_timestamp: false
    i_num_inference_threads: 2
    i_num_pool_frames: 4
    i_update_ros_base_time_on_ros_msg: false
  rgb:
    i_add_exposure_offset: false
    i_board_socket_id: 0
    i_calibration_file: ""
    i_disable_node: false
    i_enable_feature_tracker: false
    i_enable_lazy_publisher: true
    i_enable_nn: false
    i_enable_preview: false
    i_exposure_offset: 0
    i_fps: 30.0
    i_fsync_continuous: false
    i_fsync_trigger: false
    i_get_base_device_timestamp: false
    i_height: 720
    i_interleaved: false
    i_isp_den: 3
    i_isp_num: 2
    i_keep_preview_aspect_ratio: true
    i_low_bandiwdth_frame_freq: 30
    i_low_bandwidth: true
    i_low_bandwidth_bitrate: 0
    i_low_bandwidth_ffmpeg_encoder: libx264
    i_low_bandwidth_profile: 4
    i_low_bandwidth_quality: 50
    i_max_q_size: 30
    i_output_isp: true
    i_preview_height: 300
    i_preview_size: 300
    i_preview_width: 300
    i_publish_compressed: false
    i_publish_topic: true
    i_resolution: 1080P
    i_reverse_stereo_socket_order: false
    i_sensor_img_orientation: AUTO
    i_set_isp3a_fps: false
    i_set_isp_scale: true
    i_simulate_from_topic: false
    i_simulated_topic_name: ""
    i_synced: false
    i_update_ros_base_time_on_ros_msg: false
    i_width: 1280
    r_exposure: 20000
    r_focus: 1
    r_iso: 800
    r_set_man_exposure: false
    r_set_man_focus: false
    r_set_man_whitebalance: false
    r_whitebalance: 3300
  right:
    i_add_exposure_offset: false
    i_board_socket_id: 2
    i_calibration_file: ""
    i_disable_node: false
    i_enable_feature_tracker: false
    i_enable_lazy_publisher: true
    i_enable_nn: false
    i_exposure_offset: 0
    i_fps: 30.0
    i_fsync_continuous: false
    i_fsync_trigger: false
    i_get_base_device_timestamp: false
    i_height: 720
    i_low_bandiwdth_frame_freq: 30
    i_low_bandwidth: false
    i_low_bandwidth_bitrate: 0
    i_low_bandwidth_ffmpeg_encoder: libx264
    i_low_bandwidth_profile: 4
    i_low_bandwidth_quality: 50
    i_max_q_size: 30
    i_publish_compressed: false
    i_publish_topic: false
    i_resolution: 720P
    i_reverse_stereo_socket_order: false
    i_sensor_img_orientation: AUTO
    i_set_isp3a_fps: false
    i_simulate_from_topic: false
    i_simulated_topic_name: ""
    i_synced: false
    i_update_ros_base_time_on_ros_msg: false
    i_width: 1280
    r_exposure: 1000
    r_iso: 800
    r_set_man_exposure: false

  stereo:
    i_add_exposure_offset: false
    i_align_depth: true
    i_bilateral_sigma: 0
    i_board_socket_id: 0
    i_depth_filter_size: 5
    i_depth_preset: HIGH_ACCURACY
    i_disparity_width: DISPARITY_96
    i_enable_alpha_scaling: false
    i_alpha_scaling: 0.0
    i_enable_brightness_filter: false
    i_brightness_filter_min_brightness: 0
    i_brightness_filter_max_brightness: 256
    i_enable_companding: false
    i_enable_decimation_filter: false
    i_decimation_filter_decimation_mode: PIXEL_SKIPPING
    i_decimation_filter_decimation_factor: 1
    i_enable_disparity_shift: false
    i_disparity_shift: 0
    i_enable_distortion_correction: false
    i_enable_lazy_publisher: true
    i_enable_spatial_filter: false
    i_spatial_filter_hole_filling_radius: 2
    i_spatial_filter_alpha: 0.5
    i_spatial_filter_delta: 20
    i_spatial_filter_iterations: 1
    i_enable_spatial_nn: false
    i_enable_speckle_filter: false
    i_speckle_filter_speckle_range: 50
    i_enable_temporal_filter: false
    i_temporal_filter_alpha: 0.4
    i_temporal_filter_delta: 20
    i_temporal_filter_persistency: VALID_2_IN_LAST_4
    i_enable_threshold_filter: false
    i_threshold_filter_min_range: 400
    i_threshold_filter_max_range: 15000
    i_exposure_offset: 0
    i_extended_disp: false
    i_get_base_device_timestamp: false
    i_height: 720
    i_left_rect_add_exposure_offset: false
    i_left_rect_enable_feature_tracker: false
    i_left_rect_exposure_offset: 0
    i_left_rect_low_bandwidth: false
    i_left_rect_low_bandwidth_bitrate: 0
    i_left_rect_low_bandwidth_ffmpeg_encoder: libx264
    i_left_rect_low_bandwidth_frame_freq: 30
    i_left_rect_low_bandwidth_profile: 4
    i_left_rect_low_bandwidth_quality: 50
    i_left_rect_publish_compressed: false
    i_left_rect_synced: true
    i_left_socket_id: 1
    i_low_bandwidth: false
    i_low_bandwidth_bitrate: 0
    i_low_bandwidth_ffmpeg_encoder: libx264
    i_low_bandwidth_profile: 4
    i_low_bandwidth_quality: 50
    i_lr_check: true
    i_lrc_threshold: 10
    i_max_q_size: 30
    i_output_disparity: false
    i_publish_left_rect: false
    i_publish_right_rect: false
    i_publish_synced_rect_pair: false
    i_publish_topic: true
    i_rectify_edge_fill_color: 0
    i_reverse_stereo_socket_order: false
    i_right_rect_add_exposure_offset: false
    i_right_rect_enable_feature_tracker: false
    i_right_rect_exposure_offset: 0
    i_right_rect_low_bandwidth: false
    i_right_rect_low_bandwidth_bitrate: 0
    i_right_rect_low_bandwidth_ffmpeg_encoder: libx264
    i_right_rect_low_bandwidth_frame_freq: 30
    i_right_rect_low_bandwidth_profile: 4
    i_right_rect_low_bandwidth_quality: 50
    i_right_rect_publish_compressed: false
    i_right_rect_synced: true
    i_right_socket_id: 2
    i_set_disparity_to_depth_use_spec_translation: false
    i_set_input_size: false
    i_socket_name: rgb
    i_spatial_nn_source: right
    i_stereo_conf_threshold: 240
    i_subpixel: true
    i_subpixel_fractional_bits: 3
    i_synced: false
    i_update_ros_base_time_on_ros_msg: false
    i_width: 1280
    use_sim_time: false
  tof:
    i_publish_topic: true
    i_synced: true
    i_calibration_file: ""
    i_low_bandwidth: false # enabling low bandwidth mode might currently not work properly
    i_low_bandwidth_bitrate: 0
    i_low_bandwidth_ffmpeg_encoder: libx264
    i_low_bandwidth_profile: 4
    i_low_bandwidth_quality: 80
    i_get_base_device_timestamp: false
    i_update_ros_base_time_on_ros_msg: false
    i_enable_lazy_publisher: false
    i_add_exposure_offset: false
    i_exposure_offset: 0
    i_reverse_stereo_socket_order: false
    i_board_socket_id: 0
    i_max_q_size: 8
    i_width: 640
    i_height: 480
    i_fps: 30.0
    i_enable_optical_correction: false
    i_enable_fppn_correction: false
    i_enable_temperature_correction: false
    i_enable_wiggle_correction: false
    i_enable_phase_unwrapping: false
    i_enable_phase_shuffle_temporal_filter: true
    i_phase_unwrapping_level: 4
    i_phase_unwrap_error_threshold: 100
    i_median_filter: MEDIAN_OFF
```
