Parameters
Parameters
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.
Driver
driver.i_publish_tf_from_calibration: true<bool> - setting this to true launches TFPublisherdriver.i_tf_device_name: [NODE_NAME]<string> - if not set, defaults to the node namedriver.i_tf_device_model: ''<string> - if not set, it will be automatically detected. If the node is unable to detect STL file for the device it is set toOAK-D-S2. To explicitly set it indriver.launch.py, setoverride_cam_model:=truedriver.i_tf_base_frame: oak<string> - 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)driver.i_tf_parent_frame: oak_parent_frame<string> - Set to the frame that you want to connect the camera to (for example robot end effector)driver.i_tf_cam_pos_x: '0.0'<string> - Position of base frame w.r.t parent framedriver.i_tf_cam_pos_y: '0.0'<string> - Position of base frame w.r.t parent framedriver.i_tf_cam_pos_z: '0.0'<string> - Position of base frame w.r.t parent framedriver.i_tf_cam_roll: '0.0'<string> - Orientation of base frame w.r.t parent framedriver.i_tf_cam_pitch: '0.0'<string> - Orientation of base frame w.r.t parent framedriver.i_tf_cam_yaw: '0.0'<string> - Orientation of base frame w.r.t parent frame Outside of TF-publishing related parametersdriverhas 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 IDi_ip ""<string> - Used to connect to a device with specific IPi_usb_port_id: ""<string> - Used to connect to devices on specific USB porti_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 filei_external_calibration_path: ""<string> - Used to override device calibrationi_enable_ir : true<bool> - Whether to enable IR projectori_restart_on_diagnostics_error: false<bool> - If diagnostics publishing is enabled in the pipeline and it reports an error, driver will be restartedi_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 camerasr_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
pipeline_geni_pipeline_typecan be eitherRGB- only publishes RGB stream , NN availableRGBD- Publishes RGB + Depth streams (seti_publish_topicfor left and right cameras to enable them), NN & Spatial NN availableStereo- Publishes streams from left and right sensors, NN can be set for each sensor separatelyRGBStereo- Publishes RGB + Left + Right streams, NN can be set for each sensor separatelyDepth- Publishes only depth stream, NN can be set on stereo node via parameterCamArray- Publishes streams for all detected sensors, NN can be set for each sensor separatelyTof- Publishes only TOF stream, no NN availableDepthTof- Publishes Depth + TOF streams, specific to OAK-D-SR-POE, NN can be set on stereo node via parameterStereoToF- Publishes Stereo + TOF streams, specific to OAK-D-SR-POE, NN can be set on stereo node via parameterRGBToF- Publishes RGB + TOF streams, specific to OAK-D-SR-POE, NN can be set on stereo node via parameterThermal- Targeted towards OAK-T cameras, publishes RGB + Thermal stream.
i_nn_type: spatial<string> - Type of NN to be created with pipelinesi_enable_imu: true<bool> - Whether to enable IMU node in certain pipelinesi_enable_diagnostics: false<bool> - Whether to enable diagnostics nodei_enable_rgbd: false<bool> - Whether to enable RGBD node in certain pipelines
Image sensors
sensor_name.[PARAMETER_NAME], for example rgb.i_widthInitial parameters
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 overrideni_enable_feature_tracker: false<bool> - Enables FeatureTracker node for this particular sensori_enable_nn: false<bool> - Enables NeuralNetwork for this particular sensori_max_q_size: 8<int> - Sets DAI queue sizei_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 enablei_publish_compressedparameter) 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 typesi_low_bandwidth_bitrate: 0<int> - Bitrate of the Encoder, used in H26X typesi_low_bandwidth_quality: 50<int> - Quality of the MJPEG Encoderi_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 calibrationi_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 controlledi_enable_lazy_publisher: true<bool> - Whether to publish data only in the case where a subscription is detected on an image/camera_info topici_add_exposure_offset: false<bool> - Whether to add exposure offset to ROS timestampi_exposure_offset: 0<int> - Exposure offset type:- START
- MIDDLE
- END
i_reverse_stereo_socket_order: false<bool> - SeeStereo socket ordersection below for more informationi_synced: :false<bool> - Whether to add the output to the synced outputs group, all publishers synced will publish images with the same timestampsi_publish_topic: true/false<bool> - Whether to publish on ROS topic, by default true on sensors on CAM_A socket, false otherwisei_publish_full_resolution: false<bool> - Whether to publish full resolution imagei_use_max_resolution_possible: false<bool> - Whether to use maximum resolution possiblei_width: 640<int> - Width of the imagei_height: 400<int> - Height of the imagei_fps: 30.0<float> - Sensor FPSi_undistorted: true<bool> - Whether to undistort the imagei_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_modeparameter is used for the modei_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 capturingi_num_frames_burst: 1<int> - How many frames in triggered bursti_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, setr_set_man_exposureto user_exposure: 1000<int> <1-33000> - Exposure setting when setting manual exposure, setr_set_man_exposureto user_set_man_exposure: false<bool> - Whether to set manual exposurer_set_autoexposure_limit: false<bool> - Whether to limit the auto exposurer_auto_exposure_limit: 1000<int> - Auto exposure limitr_set_man_focus: false<bool> - Whether to set manual focusr_focus: 1<int> <1-255> - Focus valuer_set_man_whitebalance: false<bool> - Whether to set manual whitebalancer_whitebalance: 3000<int> <1000-12000> - Manual whitebalancer_set_sharpness: false<bool> - Whether to set sharpness manuallyr_sharpness: 1<int> <1-4> - Sharpness levelr_set_chroma_denoise: false- Whether to set chroma denoise manuallyr_chroma_denoise: 1<int> <1-4> - Chroma denoise levelr_set_luma_denoise: false- Whether to set luma denoise manuallyr_luma_denoise: 1<int> <1-4> - Luma denoise levelr_set_auto_exp_region: false<bool> - Whether to use part of image for controlling exposurer_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 regionr_auto_exp_region_height: 0<int> - Height of the autoexposure region
Stereo parameters

Depth alignment
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
stereo.i_reverse_stereo_socket_order: true (this can be also set for individual sensors).Custom Sensor sockets
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
i_max_q_size: 30<int> - Sets DAI queue sizei_fps: 30.0<float> - Stereo FPSi_low_bandwidth: false<bool> - Refer to the parameter description inSensornode. NOTE This parameter is incompatible withi_subpixelparameter.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 typesi_low_bandwidth_bitrate: 0<int> - Bitrate of the Encoder, used in H26X typesi_low_bandwidth_quality: 50<int> - Quality of the MJPEG Encoderi_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 calibrationi_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 controlledi_enable_lazy_publisher: true<bool> - Whether to publish data only in the case where a subscription is detected on an image/camera_info topici_add_exposure_offset: false<bool> - Whether to add exposure offset to ROS timestampi_exposure_offset: 0<int> - Exposure offset type:- START
- MIDDLE
- END
i_reverse_stereo_socket_order: false<bool> - SeeStereo socket ordersection below for more informationi_synced: :false<bool> - Whether to add the output to the synced outputs group, all publishers synced will publish images with the same timestampsi_publish_topic: true/false<bool> - Whether to publish on ROS topic, by default true on sensors on CAM_A socket, false otherwisei_output_disparity: false<bool> - Whether to output disparity instead of depthi_enable_left_spatial_nn: false<bool> - Whether to create spatial NN with left sensor as RGB sourcei_enable_right_spatial_nn: false<bool> - Whether to create spatial NN with right sensor as RGB sourcei_enable_left_rgbd: false<bool> - Whether to create RGBD node with left sensor as RGB sourcei_enable_right_rgbd: false<bool> - Whether to create RGBD node with right sensor as RGB sourcei_aligned: true<bool> - Whether to align stereo node toi_board_socket_idi_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 streami_set_disparity_to_depth_use_spec_translation: false<bool> - Whether to use baseline from CAD data, not the calibration datai_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 discardedi_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^xi_rectify_edge_fill_color: 0<int> <-1-255> - Fill color for missing data at the edges. 0-255 for grayscale or -1 to replicate pixelsi_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 noti_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 filteri_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 filteri_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.i_use_neural_depth: false<bool>- Whether to use Neural Depth instead of regular Stereo (available only on RVC4)i_neural_depth_model: NEURAL_DEPTH_SMALL<string> - Type of Neural Depth. Following types are available- NEURAL_DEPTH_LARGE
- NEURAL_DEPTH_MEDIUM
- NEURAL_DEPTH_SMALL
- NEURAL_DEPTH_NANO
r_edge_threshold: 10<int> - Edge threshold for Neural Depthr_confidence_threshold: 125<int> - Confidence threshold for Neural Depth- 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 streami_left_rect_low_bandwidth: false<bool> - Left rect low bandwidth provilei_left_rect_low_bandwidth_profile: 4<int> - Left Rect LB profilei_left_rect_low_bandwidth_frame_freq: 30<int> - Left Rect LB frame frequencyi_left_rect_low_bandwidth_bitrate: 0<int> - Left Rect LB bitratei_left_rect_low_bandwidth_quality: 50<int> - Left Rect LB qualityi_left_rect_publish_compressed: false<bool> - Whether to publish compressed images for left recti_left_rect_add_exposure_offset: false<bool> - Left Rect add exposure offseti_left_rect_exposure_offset: 0<int> - Left Rect exposure offset settingi_left_rect_enable_feature_tracker: false<bool> - Whether to add feature tracker for rectified lefti_left_rect_synced: false<bool> - Whether to sync left rect with other streams
Feature Tracker
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_trackerParameters
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 controlledi_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 sizei_acc_freq: 480<int> - Accelerometer sensor frequencyi_acc_cov: 0.0<float> - Accelerometer covariancei_batch_report_threshold: 5<int> - Batch report sizei_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 covariancei_gyro_freq: 400<int> - Gyroscope frequencyi_mag_cov: 0.0<float> - Magnetometer covariancei_mag_freq: 100<int> - Magnetometer frequencyi_max_batch_reports: 10<int> - Max reports per batchi_message_type: IMU<string> - ROS publisher type:IMU- sensor_msgs/ImuIMU_WITH_MAG- depthai_ros_msgs/ImuWithMagneticFieldIMU_WITH_MAG_SPLIT- two publishers - sensor_msgs/Imu & sensor_msgs/MagneticField
i_rot_cov: -1.0<float> - Rotation covariancei_rot_freq: 400<int> - Rotation frequencyi_sync_method: COPY<string> - sync method. Available options (WARNING RVC4 Devices only support COPY for now):COPYLINEAR_INTERPOLATE_GYROLINEAR_INTERPOLATE_ACCEL
i_rotation_vector_type<string> - type of rotation vector, for more information, refer to this link. Available options:ROTATION_VECTORGAME_ROTATION_VECTORGEOMAGNETIC_ROTATION_VECTORARVR_STABILIZED_ROTATION_VECTORARVR_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 controlledi_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
camera.i_nn_typecan be eithernone(no NN),rgborspatial. 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 tospatial
Parameters
i_nn_family: detection<string> - sets what kind of NN we want to have. Currently available options are: *detectionsegmentation(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 NNi_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 imagei_enable_passthrough_depth: false<bool> - Whether to publish depth passthrough imagei_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 controlledi_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 detectionsi_max_q_size: 8<int> - Sets DAI queue size
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
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
Parameters
i_publish_topic: true<bool> - Whether to publish topici_max_q_size: 8<int> - Sets DAI queue sizei_low_bandwidth: false<bool> - Refer to the parameter description inSensornode. NOTE This parameter is incompatible withi_subpixelparameter.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 typesi_low_bandwidth_bitrate: 0<int> - Bitrate of the Encoder, used in H26X typesi_low_bandwidth_quality: 50<int> - Quality of the MJPEG Encoderi_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 calibrationi_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 controlledi_enable_lazy_publisher: true<bool> - Whether to publish data only in the case where a subscription is detected on an image/camera_info topici_publish_compressed: false<bool> - Whether to publish compressed imagesi_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 controlledi_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 timestampi_exposure_offset: 0<int> - Exposure offset type:- START
- MIDDLE
- END
i_width: 640<int> - Width of the imagei_height: 400<int> - Height of the imagei_fps: 30<int> - FPS of the imagei_aligned :false<bool> - Whether to align the image to the other sensori_aligned_socket_id: ""<string> - Socket to align the image toi_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 timestampsi_preset_mode: TOF_MID_RANGE<string> - Preset mode for image filtering
Thermal
Parameters
i_publish_topic: true<bool> - Whether to publish topici_max_q_size: 8<int> - Sets DAI queue sizei_low_bandwidth: false<bool> - Refer to the parameter description inSensornode. NOTE This parameter is incompatible withi_subpixelparameter.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 typesi_low_bandwidth_bitrate: 0<int> - Bitrate of the Encoder, used in H26X typesi_low_bandwidth_quality: 50<int> - Quality of the MJPEG Encoderi_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 calibrationi_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 controlledi_enable_lazy_publisher: true<bool> - Whether to publish data only in the case where a subscription is detected on an image/camera_info topici_publish_compressed: false<bool> - Whether to publish compressed imagesi_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 controlledi_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 timestampi_exposure_offset: 0<int> - Exposure offset type:- START
- MIDDLE
- END
i_width: 640<int> - Width of the imagei_height: 400<int> - Height of the imagei_fps: 30.0<float> - FPS of the imagei_aligned :false<bool> - Whether to align the image to the other sensori_aligned_socket_id: ""<string> - Socket to align the image toi_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 timestampsi_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
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 topici_max_q_size: 2<int> - Sets DAI queue sizei_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 controlledi_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 nodei_run_sync_on_host: true<bool> - Whether to sync messages on hosti_run_align_on_host: true<bool> - Whether to run align node on host (this is only in case of RVC4)
VIO
pipeline_gen.i_enable_vio parameter.Parameters
i_publish_topic: true<bool> - Whether to publish topici_max_q_size: 2<int> - Sets DAI queue sizei_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 controlledi_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_run_sync_on_host: true<bool> - Whether to sync messages on hosti_imu_update_rate: 400<int> - Rate of updating the imu messagesi_width: 640<int> - Width of the imagesi_height: 400<int> - Height of the imagesi_fps: 60.0<float> - FPS of the imagesi_config_path: 'depthai_ros_driver_default.json'<string> - Full path to config.json used, when default value is used, config from depthai_ros_driver/config/custom is usedi_override_local_transform: false<bool> - Whether to override local transform, when enabled, following parameters can be seti_local_transform_x: 0.0<float> - X positioni_local_transform_y: 0.0<float> - Y positioni_local_transform_z: 0.0<float> - Z positioni_local_transform_qx: 0.0<float> - X component of quaternioni_local_transform_qy: 0.0<float> - Y component of quaternioni_local_transform_qz: 0.0<float> - Z component of quaternioni_local_transform_qw: 0.0<float> - w component of quaternion
i_override_imu_extrinsics: false<bool> - Whether to override IMU extrinsics with other valuesi_imu_extr_x: 0.0<float> - X positioni_imu_extr_y: 0.0<float> - Y positioni_imu_extr_z: 0.0<float> - Z positioni_imu_extr_qx: 0.0<float> - X component of quaternioni_imu_extr_qy: 0.0<float> - Y component of quaternioni_imu_extr_qz: 0.0<float> - Z component of quaternioni_imu_extr_qw: 0.0<float> - w component of quaternion
i_set_acc_bias: false<bool> - Override default accelerometer biasi_accel_bias: 9x0.0<vector<double>> - Accelerometer biasi_set_acc_noise_std: false<bool> - Override standard noise for accelerometeri_acc_noise_std: 3x0.0<vector<double>> - Accelerometer standard noisei_set_gyro_bias: false<bool> - Override default gyroscope biasi_gyro_bias: 9x0.0<vector<double>> - Gyroscope biasi_set_gyro_noise_std: false<bool> - Override standard noise for gyroscopei_gyro_noise_std: 3x0.0<vector<double>> - Gyroscope standard noisei_publish_tf: true<bool> - Whether to publish TF frame as welli_frame_id: odom<string> - Frame ID of the messagesi_child_frame_id: oak_parent_frame<string> - Child frame IDi_covariance: 36x0.0<vector<double>> - Covariance for the messages