ON THIS PAGE

  • DepthAI ROS Driver
  • Quickstart
  • Parameters
  • Launch files
  • Publishing TFs from extrinsics
  • List of node wrappers and their parameters
  • Driver
  • Parameters
  • Pipeline generation
  • Parameters
  • Image sensors
  • Initial parameters
  • Runtime parameters
  • Stereo parameters
  • Depth alignment
  • Stereo socket order
  • Custom Sensor sockets
  • Parameters
  • Feature Tracker
  • Parameters
  • IMU
  • Parameters:
  • Neural networks
  • Parameters
  • Sync
  • Parameters
  • ToF
  • Parameters
  • Thermal
  • Parameters
  • RGBD
  • Parameters
  • Specific camera configurations
  • ToF Cameras
  • Stopping/starting camera for power saving/reconfiguration
  • RealSense compatibility
  • Example
  • RTABMap example with RealSense compatibility
  • Before
  • After
  • Recalibration
  • Example scenarios
  • Developers guide

DepthAI ROS Driver

Quickstart

To get the latest driver, please install ROS2 Kilted by following the instructions here. After installation of ROS, you should be able to install DepthAI packages as follows:
Command Line
1sudo apt install ros-kilted-depthai-ros
After installation you should be able to run the driver by one of the launch files, for example:
Command Line
1ros2 launch depthai_ros_driver driver.launch.py
Note, this launch file is targeted towards OAK-D lineup, for devices with different configurations such as OAK-D-PoE-SR or OAK-FFC you might need to use a different launch file or different parameter combination.Each file launches ROS driver as a composable node inside its own composable node container, for running the driver as a separate node you can run.
Command Line
1ros2 run depthai_ros_driver driver

Parameters

The driver can be configured by a large number of parameters. Description of all parameters for each node can be found below, most of them mirror DepthAI C++/Python API. 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

  • driver.launch.py launches camera in RGBD, and NN in spatial mode (using Yolo V6).
  • 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 (currently only for RVC2)
  • 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. Note, pointcloud here is published on a different topic.
  • 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.

Publishing TFs from extrinsics

Frame default names:
  • parent_frame: "oak_parent_frame"
  • base_frame: "oak" (or node name)
In driver, all frames are prepended with node name to allow easier distinguishing when using multiple cameras, for example oak_imu_frameBy default, camera transforms are published from based on Device's camera calibration data. To change this behavior in depthai_ros_driver, you can use following parameters:
  • driver.i_publish_tf_from_calibration - setting this to true launches TFPublisher
Then you can set following arguments:
  • driver.i_tf_device_name - if not set, defaults to the node name
  • driver.i_tf_device_model - if not set, it will be automatically detected. If the node is unable to detect STL file for the device it is set to OAK-D. To explicitly set it in driver.launch.py, set override_cam_model:=true
  • driver.i_tf_base_frame - Frame that is used as an the root for camera frames, usually in the same place as CAM_A (center sensor for OAK-D lineup), by default equal to node name
  • driver.i_tf_parent_frame - Set to the frame that you want to connect the camera to (for example robot end effector)
  • driver.i_tf_cam_pos_x - Position of base frame w.r.t parent frame
  • driver.i_tf_cam_pos_y - Position of base frame w.r.t parent frame
  • driver.i_tf_cam_pos_z - Position of base frame w.r.t parent frame
  • driver.i_tf_cam_roll - Orientation of base frame w.r.t parent frame
  • driver.i_tf_cam_pitch - Orientation of base frame w.r.t parent frame
  • driver.i_tf_cam_yaw - Orientation of base frame w.r.t parent frame
When using driver.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 driver.launch.py pass_tf_args_as_params:=true parent_frame:=map cam_pos_x:=1.0 imu_from_descr:=trueIt 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.

List of node wrappers and their parameters

Driver

Driver class is responsible for resetting camera, loading pipelines and (optionally) monitoring device status.

Parameters

Outside of TF-publishing related parameters driver has additional parameters
  • i_usb_speed: SUPER <string> - USB speed set for using current interface, it is automatically deduced but can be overridden, for example to use SUPER_PLUS explicitly available options:
    • LOW
    • FULL
    • HIGH (USB2)
    • SUPER (USB3)
    • SUPER_PLUS - for connecting with a hight speed interface (like Thunderbolt), can be unstable in certain scenarios
  • i_device_id: "" <string> - Used to connect to a device with a specific ID
  • i_ip "" <string> - Used to connect to a device with specific IP
  • i_usb_port_id: "" <string> - Used to connect to devices on specific USB port
  • i_pipeline_dump: false <bool> - Whether to dump created pipeline to a JSON file (used for debugging)
  • i_calibration_dump: false <bool> - Whether to dump calibration to a JSON file
  • i_external_calibration_path: "" <string> - Used to override device calibration
  • i_enable_ir : true <bool> - Whether to enable IR projector
  • i_restart_on_diagnostics_error: false <bool> - If diagnostics publishing is enabled in the pipeline and it reports an error, driver will be restarted
  • i_rs_compat: false <bool> - Turn on Realsense compatibility. Topic, frame names and param names will be changed to reflect RS cameras.
  • r_laser_dot_intensity: 0.6 <float> <0.0-1.0> - Sets laser dot projector intensity. Additional power might be required via Y-adapter in USB cameras
  • r_floodlight_intensity: 0.6 <float> <0.0-1.0> - Sets floodlight projector intensity. Additional power might be required via Y-adapter in USB cameras

Pipeline generation

Parameters

Parameters start with name pipeline_gen
  • 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
    • Thermal - Targeted towards OAK-T cameras, publishes RGB + Thermal stream.
  • i_nn_type: spatial <string> - Type of NN to be created with pipelines
  • i_enable_imu: true <bool> - Whether to enable IMU node in certain pipelines
  • i_enable_diagnostics: false <bool> - Whether to enable diagnostics node
  • i_enable_rgbd: false <bool> - Whether to enable RGBD node in certain pipelines 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 (for example 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.For example
C++
1std::vector<std::unique_ptr<dai_nodes::BaseNode>> StereoToF::createPipeline(std::shared_ptr<rclcpp::Node> node,
2                                                                            std::shared_ptr<dai::Device> device,
3                                                                            std::shared_ptr<dai::Pipeline> pipeline,
4                                                                            std::shared_ptr<param_handlers::PipelineGenParamHandler> ph,
5                                                                            const std::string& deviceName,
6                                                                            bool rsCompat,
7                                                                            const std::string& /*nnType*/) {
8    std::vector<std::unique_ptr<dai_nodes::BaseNode>> daiNodes;
9    auto tof = std::make_unique<dai_nodes::ToF>("tof", node, pipeline, deviceName, rsCompat);
10    auto left = std::make_unique<dai_nodes::SensorWrapper>("left", node, pipeline, deviceName, rsCompat, dai::CameraBoardSocket::CAM_B);
11    auto right = std::make_unique<dai_nodes::SensorWrapper>("right", node, pipeline, deviceName, rsCompat, dai::CameraBoardSocket::CAM_C);
12    if(tof->isAligned() && tof->getSocketID() == right->getSocketID()) {
13        auto in = tof->getInput();
14        right->getDefaultOut()->link(in);
15    } else if(tof->isAligned() && tof->getSocketID() == left->getSocketID()) {
16        auto in = tof->getInput();
17        left->getDefaultOut()->link(in);
18    }
19    daiNodes.push_back(std::move(left));
20    daiNodes.push_back(std::move(right));
21    daiNodes.push_back(std::move(tof));
22    return daiNodes;
23}
After that export plugin, for example:
C
1#include <pluginlib /class_list_macros.hpp>
2  PLUGINLIB_EXPORT_CLASS(test_plugins::Test, depthai_ros_driver::pipeline_gen::BasePipeline)
Add plugin definition:
Xml
1<library path="test_plugins">
2    <class type="test_plugins::Test" base_class_type="depthai_ros_driver::pipeline_gen::BasePipeline">
3      <description>Test Pipeline.</description>
4    </class>
5  </library>
Now you can use created plugin as pipeline, just set camera.i_pipeline_type to test_plugins::Test.

Image sensors

Sensor parameters begin with sensor_name.[PARAMETER_NAME], for example rgb.i_width

Initial parameters

  • i_enable_default_output: true <bool>- For now, sensor node creates one default output that is used for image publishing and/or Stereo alignment. The output can be disabled to save some bandwidth if publishing on image topic is not required, for example in the case where we have RGBD pointcloud publishing (as RGBD node requests a separate output internally) and explicit Stereo alignment is not needed.
  • i_board_socket_id <int> - Socket ID of the sensor, used mostly for alignment, calibration and deducing frame names, automatically detected for each sensor but can be overriden
  • i_enable_feature_tracker: false <bool> - Enables FeatureTracker node for this particular sensor
  • i_enable_nn: false <bool> - Enables NeuralNetwork for this particular sensor
  • i_max_q_size: 8 <int> - Sets DAI queue size
  • i_low_bandwidth: false <bool> - When set to true, enables VideoEncoder for this particular sensor to improve latency between camera and host. By default DAI Encoded frames (only in case of MJPEG Encoder, for H264 enable i_publish_compressed parameter) are decoded to ROS Image messages on host.
  • i_low_bandwidth_profile: 4 <int> - Type of encoder used. Following types are available:
    • H264_BASELINE,
    • H264_HIGH,
    • H264_MAIN,
    • H265_MAIN,
    • MJPEG (default)
  • i_low_bandwidth_frame_freq: 30 <int> - Frame frequency of the Encoder, used in H26X types
  • i_low_bandwidth_bitrate: 0 <int> - Bitrate of the Encoder, used in H26X types
  • i_low_bandwidth_quality: 50 <int> - Quality of the MJPEG Encoder
  • i_publish_compressed: false <bool> - Instead of converting DAI Encoded frames to ROS Image messages publish them in respective compressed image formats (CompressedImage for MJPEG and FFMPEGMsgs::FFMPPEGPacket for H26X types)
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)
  • i_calibration_file: "" <string> - Used to override DAI calibration with ROS calibration
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_enable_lazy_publisher: true <bool> - Whether to publish data only in the case where a subscription is detected on an image/camera_info topic
  • i_add_exposure_offset: false <bool> - Whether to add exposure offset to ROS timestamp
  • i_exposure_offset: 0 <int> - Exposure offset type:
    • START
    • MIDDLE
    • END
  • i_reverse_stereo_socket_order: false <bool> - See Stereo socket order section below for more information
  • i_synced: :false <bool> - Whether to add the output to the synced outputs group, all publishers synced will publish images with the same timestamps
  • i_publish_topic: true/false <bool> - Whether to publish on ROS topic, by default true on sensors on CAM_A socket, false otherwise
  • i_width: 640 <int> - Width of the image
  • i_height: 400 <int> - Height of the image
  • i_fps: 30.0 <float> - Sensor FPS
  • i_undistorted: true <bool> - Whether to undistort the image
  • i_resize_mode: "CROP" <string> - Type of resize used when undistorting the image, refer to DAI Camera node for more information, can be:
    • CROP
    • LETTERBOX
    • STRETCH
  • i_fsync_continuous: false <bool> - Whether to set Frame Sync mode. If enabled, i_fsync_mode parameter is used for the mode
  • i_fsync_mode: "INPUT <string> - Type of FSync mode, can be:
    • OFF
    • OUTPUT
    • INPUT
  • i_fsync_trigger: false <bool> - Whether to use external trigger for image capturing
  • i_num_frames_burst: 1 <int> - How many frames in triggered burst
  • i_num_frames_discard: 0 <int> - How many frames to discard in an initial burst (they may have worse quality)

Runtime parameters

  • r_iso: 800 <int> <100-1600> - ISO setting when setting manual exposure, set r_set_man_exposure to use
  • r_exposure: 1000 <int> <1-33000> - Exposure setting when setting manual exposure, set r_set_man_exposure to use
  • r_set_man_exposure: false <bool> - Whether to set manual exposure
  • r_set_autoexposure_limit: false <bool> - Whether to limit the auto exposure
  • r_auto_exposure_limit: 1000 <int> - Auto exposure limit
  • r_set_man_focus: false <bool> - Whether to set manual focus
  • r_focus: 1 <int> <1-255> - Focus value
  • r_set_man_whitebalance: false <bool> - Whether to set manual whitebalance
  • r_whitebalance: 3000 <int> <1000-12000> - Manual whitebalance
  • r_set_sharpness: false <bool> - Whether to set sharpness manually
  • r_sharpness: 1 <int> <1-4> - Sharpness level
  • r_set_chroma_denoise: false - Whether to set chroma denoise manually
  • r_chroma_denoise: 1 <int> <1-4> - Chroma denoise level
  • r_set_luma_denoise: false - Whether to set luma denoise manually
  • r_luma_denoise: 1 <int> <1-4> - Luma denoise level
  • r_set_auto_exp_region: false <bool> - Whether to use part of image for controlling exposure
  • r_auto_exp_region_start_x: 0 <int> - Start point for rectangle used for autoexposure (in image coordinates, i.e X right, Y down)
  • r_auto_exp_region_start_y: 0 <int> - Start point for rectangle used for autoexposure (in image coordinates, i.e X right, Y down)
  • r_auto_exp_region_width: 0 <int> - Width of the autoexposure region
  • r_auto_exp_region_height: 0 <int> - Height of the autoexposure region

Stereo parameters

Depth alignment

When setting stereo.aligned: 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.

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.

Parameters

For more information on filters, visit Configuring Stereo Depth
  • i_max_q_size: 30 <int> - Sets DAI queue size
  • i_low_bandwidth: false <bool> - Refer to the parameter description in Sensor node. NOTE This parameter is incompatible with i_subpixel parameter.
  • i_low_bandwidth_profile: 4 <int> - Type of encoder used. Following types are available:
    • H264_BASELINE,
    • H264_HIGH,
    • H264_MAIN,
    • H265_MAIN,
    • MJPEG (default)
  • i_low_bandwidth_frame_freq: 30 <int> - Frame frequency of the Encoder, used in H26X types
  • i_low_bandwidth_bitrate: 0 <int> - Bitrate of the Encoder, used in H26X types
  • i_low_bandwidth_quality: 50 <int> - Quality of the MJPEG Encoder
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)
  • i_calibration_file: "" <string> - Used to override DAI calibration with ROS calibration
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_enable_lazy_publisher: true <bool> - Whether to publish data only in the case where a subscription is detected on an image/camera_info topic
  • i_add_exposure_offset: false <bool> - Whether to add exposure offset to ROS timestamp
  • i_exposure_offset: 0 <int> - Exposure offset type:
    • START
    • MIDDLE
    • END
  • i_reverse_stereo_socket_order: false <bool> - See Stereo socket order section below for more information
  • i_synced: :false <bool> - Whether to add the output to the synced outputs group, all publishers synced will publish images with the same timestamps
  • i_publish_topic: true/false <bool> - Whether to publish on ROS topic, by default true on sensors on CAM_A socket, false otherwise
  • i_output_disparity: false <bool> - Whether to output disparity instead of depth
  • i_enable_left_spatial_nn: false <bool> - Whether to create spatial NN with left sensor as RGB source
  • i_enable_right_spatial_nn: false <bool> - Whether to create spatial NN with right sensor as RGB source
  • i_enable_left_rgbd: false <bool> - Whether to create RGBD node with left sensor as RGB source
  • i_enable_right_rgbd: false <bool> - Whether to create RGBD node with right sensor as RGB source
  • i_aligned: true <bool> - Whether to align stereo node to i_board_socket_id
  • i_run_align_on_host: true <bool> - Whether to run align node on host (this is only in case of RVC4)
  • i_depth_preset: FAST_ACCURACY <string> - What kind of default depth preset to apply. WARNING In case of types other than FAST_ACCURACY, other stereo filtering parameters might be overriden. Additionally, in some cases decimation filter is applied resulting in lower final image size and increased processing might reduce available resources that are shared with, for example Neural Networks on RVC2 devices. Following settings are exposed:
    • FAST_ACCURACY
    • DEFAULT
    • FACE
    • HIGH_DETAIL
    • ROBOTICS
  • i_enable_distortion_correction: true <bool> - Toggling distortion correction on output stream
  • i_set_disparity_to_depth_use_spec_translation: false <bool> - Whether to use baseline from CAD data, not the calibration data
  • i_bilateral_sigma: 0 <int> <0-65535> - Value for bilateral sigma filter. Large values of this parameter means that farther colors within pixel neighbourhood will be mixed together, resulting in large areas of semi-equal color.
  • i_lrc_threshold: 10 <int> <0-255> - Threshold for left-right, right-left disparity map combine.
  • i_stereo_conf_threshold: 15 <int> <0-255> - Confidence threshold for disparity calculation. High value means more depth values are discarded
  • i_subpixel: true <bool> - Compute disparity with sub-pixel interpolation (3 fractional bits by default. Suitable for long range. Currently incompatible with extended disparity and low_bandwidth mode. Setting subpixel results in more depth values being output (less visible "steps" in pointclouds at the cost of more bandwidth and resources being used. Automatically enabled on some depth presets.
  • i_subpixel_fractional_bits: 3 <int> <3-5> - Defines the number of fractional disparities: 2^x
  • i_rectify_edge_fill_color: 0 <int> <-1-255> - Fill color for missing data at the edges. 0-255 for grayscale or -1 to replicate pixels
  • i_enable_alpha_scaling: false <bool> - Enable alpha scaling.
  • i_alpha_scaling: 0.0 <float> - Alpha scaling parameter. It is a free scaling parameter between 0, (where all pixels in the undistorted image are valid) and 1 (where all the source image pixels are retained in the undistorted image). On some high distortion lenses, and/or due to rectification (image rotated) invalid areas may appear even with alpha=0, in these cases alpha < 0.0 helps removing invalid areas.
  • i_disparity_width: DISPARITY_96 <string> - Disparity search range. Values:
    • DISPARITY_64
    • DISPARITY_96
  • i_extended_disp: false <bool> - Disparity range increased from 0-95 to 0-190, combined with full resolution and downscaled images. Suitable for short range objects. Currently incompatible with sub-pixel disparity.
  • i_enable_companding: false <bool> - Enable disparity companding using sparse matching. Matching pixel by pixel for N disparities. Matching every 2nd pixel for M disparities. Matching every 4th pixel for T disparities. In case of 96 disparities: N=48, M=32, T=16. This way the search range is extended to 176 disparities, by sparse matching. Note, when enabling this flag only depth map will be affected, disparity map will not
  • i_enable_temporal_filter: false <bool> - Enable temporal filter.
  • i_temporal_filter_alpha: 0.4 <float> <0.0-1.0> - The alpha factor in an exponential moving average with Alpha=1 - no filter. Alpha=0 - infinite filter. Determines the extent of the temporal history that should be averaged.
  • i_temporal_filter_delta: 20 <int> - Step-size boundary. Establishes the threshold used to preserve "edges". If the disparity value between neighboring pixels exceed the disparity threshold set by this delta parameter, then filtering will be temporarily disabled. Default value 0 means auto: 3 disparity integer levels. In case of subpixel mode it's 3*number of subpixel levels.
  • i_temporal_filter_persistency: VALID_2_IN_LAST_4 <string> - Persistency mode. If the current disparity/depth value is invalid, it will be replaced by an older value, based on persistency mode. Valid values:
    • PERSISTENCY_OFF
    • VALID_8_OUT_OF_8
    • VALID_2_IN_LAST_3
    • VALID_2_IN_LAST_4
    • VALID_2_OUT_OF_8
    • VALID_1_IN_LAST_2
    • VALID_1_IN_LAST_5
    • VALID_1_IN_LAST_8
    • PERSISTENCY_INDEFINITELY
  • i_enable_speckle_filter: false <bool> - Enable speckle filter.
  • i_speckle_filter_speckle_range: 50 <int> - Speckle search range.
  • i_enable_disparity_shift: false <bool> - Shift input frame by a number of pixels to increase minimum depth. For example shifting by 48 will change effective disparity search range from (0,95] to [48,143]. An alternative approach to reducing the minZ. We normally only recommend doing this when it is known that there will be no objects farther away than MaxZ, such as having a depth camera mounted above a table pointing down at the table surface.
  • i_disparity_shift: 0 <int> - Disparity shift value.
  • i_enable_spatial_filter: false <bool> - Enable spatial filter.
  • i_spatial_filter_hole_filling_radius: 2 <int> - An in-place heuristic symmetric hole-filling mode applied horizontally during the filter passes. Intended to rectify minor artefacts with minimal performance impact. Search radius for hole filling.
  • i_spatial_filter_alpha: 0.5 <float> - The Alpha factor in an exponential moving average with Alpha=1 - no filter. Alpha = 0 - infinite filter. Determines the amount of smoothing.
  • i_spatial_filter_delta: 20 <int> - Similar to delta in temporal filter.
  • i_spatial_filter_num_iterations: 1 <int> - Number of iterations over the image in both horizontal and vertical direction.
  • i_enable_threshold_filter: false <bool> - Enable threshold filter
  • i_threshold_filter_min_range: 400 <int> - Minimum range in depth units(mm). Depth values under this value are invalidated.
  • i_threshold_filter_max_range: 15000 <int> - Maximum range in depth units. Depth values over this value are invalidated.
  • i_enable_brightness_filter: false <bool> - Enable brightness filter
  • i_brightness_filter_min_brightness: 0 <int> - Minimum pixel brightness. If input pixel is less or equal than this value the depth value is invalidated.
  • i_brightness_filter_max_brightness: 255 <int> - Maximum pixel brightness. If input pixel is more or equal than this value the depth value is invalidated.
  • i_enable_decimation_filter: false <bool> - Enable decimation filter. Affects final image size.
  • i_decimation_filter_decimation_mode: PIXEL_SKIPPING <string> - Decimation algorithm type. Available values:
    • PIXEL_SKIPPING
    • NON_ZERO_MEDIAN
    • NON_ZERO_MEAN
  • i_decimation_filter_decimation_factor: 1 <int> <1-4> - Valid values are 1,2,3,4. Disparity/depth map x/y resolution will be decimated with this value.
  • Following parameters are for the same for left and right rectified streams, below are parameters for left for the sake of brevity
    • i_publish_left_rect: false <bool> - Whether to publish rectified left stream
    • i_left_rect_low_bandwidth: false <bool> - Left rect low bandwidth provile
    • i_left_rect_low_bandwidth_profile: 4 <int> - Left Rect LB profile
    • i_left_rect_low_bandwidth_frame_freq: 30 <int> - Left Rect LB frame frequency
    • i_left_rect_low_bandwidth_bitrate: 0 <int> - Left Rect LB bitrate
    • i_left_rect_low_bandwidth_quality: 50 <int> - Left Rect LB quality
    • i_left_rect_publish_compressed: false <bool> - Whether to publish compressed images for left rect
    • i_left_rect_add_exposure_offset: false <bool> - Left Rect add exposure offset
    • i_left_rect_exposure_offset: 0 <int> - Left Rect exposure offset setting
    • i_left_rect_enable_feature_tracker: false <bool> - Whether to add feature tracker for rectified left
    • i_left_rect_synced: false <bool> - Whether to sync left rect with other streams

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

Parameters

  • i_motion_estimation_type: LUKAS_KANADE_OPTICAL_FLOW <string> - Motion estimator type, can be:
    • LUKAS_KANADE_OPTICAL_FLOW
    • HW_MOTION_ESTIMATION
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)

IMU

Parameters:

  • i_max_q_size: 8 <int> - Sets DAI queue size
  • i_acc_freq: 480 <int> - Accelerometer sensor frequency
  • i_acc_cov: 0.0 <float> - Accelerometer covariance
  • i_batch_report_threshold: 5 <int> - Batch report size
  • i_enable_rotation: false <bool> - Whether to enable rotation vector & magnetometer data (available when using IMU_WITH_MAGN/ IMU_WITH_MAGN_SPLIT message type and BNO086 sensor)
  • i_gyro_cov: 0.0 <float> - Gyroscope covariance
  • i_gyro_freq: 400 <int> - Gyroscope frequency
  • i_mag_cov: 0.0 <float> - Magnetometer covariance
  • i_mag_freq: 100 <int> - Magnetometer frequency
  • i_max_batch_reports: 10 <int> - Max reports per batch
  • i_message_type: IMU <string> - 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 <float> - Rotation covariance
  • i_rot_freq: 400 <int> - Rotation frequency
  • i_sync_method: COPY <string> - sync method. Available options (WARNING RVC4 Devices only support COPY for now):
    • COPY
    • LINEAR_INTERPOLATE_GYRO
    • LINEAR_INTERPOLATE_ACCEL
  • i_rotation_vector_type <string> - type of rotation vector, for more information, refer to this link. Available options:
    • ROTATION_VECTOR
    • GAME_ROTATION_VECTOR
    • GEOMAGNETIC_ROTATION_VECTOR
    • ARVR_STABILIZED_ROTATION_VECTOR
    • ARVR_STABILIZED_GAME_ROTATION_VECTOR
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)

Neural networks

In most of the pipeline types there is an option to easily turn enable Neural Networks.
  • camera.i_nn_type can be either none (no NN), 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

Parameters

  • i_nn_family: detection <string> - sets what kind of NN we want to have. Currently available options are: *detection
    • segmentation (for now only on RVC2)
  • i_nn_model: yolov6-nano <string> - Which model we want to load, models are downloaded from the web automatically when the driver is started, similarly to DepthAI C++/Python examples.
  • i_nn_confidence_threshold: 0.5 <float> - Confidence threshold for NN
  • i_nn_depth_lower_threshold: 100 <int> - (Spatial only) lower depth threshold for detections (in mm)
  • i_nn_depth_upper_threshold: 10000 <int> - (Spatial only) upper depth threshold for detections (in mm)
  • i_enable_passthrough: false <bool> - Whether to publish RGB passthrough image
  • i_enable_passthrough_depth: false <bool> - Whether to publish depth passthrough image
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)
  • i_bounding_box_scale_factor: 0.5 <float> <0.0-1.0> - Bounding box scale factor for detections
  • i_max_q_size: 8 <int> - Sets DAI queue size
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_model 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_left_spatial_nn - set to true to enable spatial NN with left sensor as input

Sync

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 driver.launch.py with pointcloud.enable:=true argument.

Parameters

  • i_sync_threshold: 10 <int> - Set maximal interval between messages in a group in milliseconds.
  • i_sync_attempts: 10 <int> - Number of attemps for syncing

ToF

ToF node is available on ToF, RgbTof, StereoToF and DepthTof pipelines. Its parameters are similar to regular camera node

Parameters

  • i_publish_topic: true <bool> - Whether to publish topic
  • i_max_q_size: 8 <int> - Sets DAI queue size
  • i_low_bandwidth: false <bool> - Refer to the parameter description in Sensor node. NOTE This parameter is incompatible with i_subpixel parameter.
  • i_low_bandwidth_profile: 4 <int> - Type of encoder used. Following types are available:
    • H264_BASELINE,
    • H264_HIGH,
    • H264_MAIN,
    • H265_MAIN,
    • MJPEG (default)
  • i_low_bandwidth_frame_freq: 30 <int> - Frame frequency of the Encoder, used in H26X types
  • i_low_bandwidth_bitrate: 0 <int> - Bitrate of the Encoder, used in H26X types
  • i_low_bandwidth_quality: 50 <int> - Quality of the MJPEG Encoder
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)
  • i_calibration_file: "" <string> - Used to override DAI calibration with ROS calibration
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_enable_lazy_publisher: true <bool> - Whether to publish data only in the case where a subscription is detected on an image/camera_info topic
  • i_publish_compressed: false <bool> - Whether to publish compressed images
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)
  • i_add_exposure_offset: false <bool> - Whether to add exposure offset to ROS timestamp
  • i_exposure_offset: 0 <int> - Exposure offset type:
    • START
    • MIDDLE
    • END
  • i_width: 640 <int> - Width of the image
  • i_height: 400 <int> - Height of the image
  • i_fps: 30 <int> - FPS of the image
  • i_aligned :false <bool> - Whether to align the image to the other sensor
  • i_aligned_socket_id: "" <string> - Socket to align the image to
  • i_run_align_on_host: true <bool> - Whether to run align node on host (this is only in case of RVC4)
  • i_synced: :false <bool> - Whether to add the output to the synced outputs group, all publishers synced will publish images with the same timestamps
  • i_preset_mode: TOF_MID_RANGE <string> - Preset mode for image filtering

Thermal

Thermal camera similarly operates as camera node with the option to set some additional runtime parameters

Parameters

  • i_publish_topic: true <bool> - Whether to publish topic
  • i_max_q_size: 8 <int> - Sets DAI queue size
  • i_low_bandwidth: false <bool> - Refer to the parameter description in Sensor node. NOTE This parameter is incompatible with i_subpixel parameter.
  • i_low_bandwidth_profile: 4 <int> - Type of encoder used. Following types are available:
    • H264_BASELINE,
    • H264_HIGH,
    • H264_MAIN,
    • H265_MAIN,
    • MJPEG (default)
  • i_low_bandwidth_frame_freq: 30 <int> - Frame frequency of the Encoder, used in H26X types
  • i_low_bandwidth_bitrate: 0 <int> - Bitrate of the Encoder, used in H26X types
  • i_low_bandwidth_quality: 50 <int> - Quality of the MJPEG Encoder
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)
  • i_calibration_file: "" <string> - Used to override DAI calibration with ROS calibration
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_enable_lazy_publisher: true <bool> - Whether to publish data only in the case where a subscription is detected on an image/camera_info topic
  • i_publish_compressed: false <bool> - Whether to publish compressed images
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)
  • i_add_exposure_offset: false <bool> - Whether to add exposure offset to ROS timestamp
  • i_exposure_offset: 0 <int> - Exposure offset type:
    • START
    • MIDDLE
    • END
  • i_width: 640 <int> - Width of the image
  • i_height: 400 <int> - Height of the image
  • i_fps: 30 <int> - FPS of the image
  • i_aligned :false <bool> - Whether to align the image to the other sensor
  • i_aligned_socket_id: "" <string> - Socket to align the image to
  • i_run_align_on_host: true <bool> - Whether to run align node on host (this is only in case of RVC4)
  • i_synced: :false <bool> - Whether to add the output to the synced outputs group, all publishers synced will publish images with the same timestamps
  • i_orientation: NORMAL <string> - Orientation of the image. Available options:
    • NORMAL
    • MIRROR
    • FLIP
    • MIRROR_FLIP
  • r_auto_ffc: false <bool> - Auto Flat-Field-Correction. Controls wheather the shutter is controlled by the sensor module automatically or not.
  • r_close_manual_shutter: false <bool> - Set this to True/False to close/open the shutter when autoFFC is disabled.
  • r_brightness_level: 0 <int> <0-255> - Image brightness level.
  • r_time_noise_filter_level: 0 <int> <0-3> - Time noise filter level. Filters out the noise that appears over time.

RGBD

RGBD node can be turned on in some pipelines by turning on pipeline_gen.i_enable_rgbd parameter or by setting i_enable_left/right_rgbd in Stereo node.

Parameters

  • i_publish_topic: true <bool> - Whether to publish topic
  • i_max_q_size: 2 <int> - Sets DAI queue size
  • i_update_ros_base_time_on_ros_msg: false <bool> - Enable if you experience timeshifts in your system (for example in the case where system clock is externally controlled
  • i_get_base_device_timestamp: false <bool> - Controls whether DAI timestamps obtained for data are synchronized to host (Timestamps themselves are still aligned to ROS time)
  • i_num_threads: 1 <int> - Number of threads used for RGBD node
  • i_run_sync_on_host: true <bool> - Whether to sync messages on host
  • i_run_align_on_host: true <bool> - Whether to run align node on host (this is only in case of RVC4)

Specific camera configurations

PoE Cameras

Since PoE cameras use protocol that has lower throughput than USB, running default driver 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.

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

RealSense compatibility

For quick integration test, you can use driver.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
1# Example inclusion of RealSense driver
2rs_camera_launch_include = IncludeLaunchDescription(
3  PythonLaunchDescriptionSource([
4      PathJoinSubstitution([
5          FindPackageShare('realsense2_camera'),
6          'launch',
7          'rs_launch.py',
8      ])
9  ]),
10  launch_arguments={
11      'pointcloud.enable': true,
12  }.items()
13)
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
1# Example inclusion of OAK driver
2oak_driver_launch_include = IncludeLaunchDescription(
3  PythonLaunchDescriptionSource([
4      PathJoinSubstitution([
5          FindPackageShare('depthai_ros_driver'),
6          'launch',
7          'driver.launch.py',
8      ])
9  ]),
10  launch_arguments={
11      'rs_compat': true,
12      'pointcloud.enable': true,
13  }.items()
14)
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
1remappings=[
2('imu', '/imu/data'),
3('rgb/image', '/camera/color/image_raw'),
4('rgb/camera_info', '/camera/color/camera_info'),
5('depth/image', '/camera/realigned_depth_to_color/image_raw')]

After

Python
1remappings=[
2('imu', '/imu/data'),
3('rgb/image', '/camera/camera/color/image_raw'),
4('rgb/camera_info', '/camera/camera/color/camera_info'),
5('depth/image', '/camera/camera/depth/image_rect_raw')]
Now to launch the example with RS camera, per instruction you need to run following command:
Command Line
1ros2 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:
Command Line
1ros2 launch depthai_ros_driver driver.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
1- file:///full/path/to/local/file.yaml
2- file:///full/path/to/videre/file.ini
3- package://camera_info_manager/tests/test_calibration.yaml
4- package://ros_package_name/calibrations/camera3.yaml

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