# DepthAI ROS Driver

> **Version Note**
> This page covers the
> **ROS v3 driver**
> .
> - **Humble / Jazzy:**
> the ROS package names use the
> `_v3`
> suffix, for example
> `depthai_ros_driver_v3`
> and Debian package
> `ros-$ROS_DISTRO-depthai-ros-v3`
> .
> - **Kilted and newer:**
> v3 is the default driver, so the package names are unsuffixed, for example
> `depthai_ros_driver`
> and Debian package
> `ros-$ROS_DISTRO-depthai-ros`
> .
> If you want the latest Humble/Jazzy ROS binaries before they sync to the stable ROS apt repository, enable the
> **ROS testing repository**
> .

## Quickstart

### Classic installation

After installing ROS, install the DepthAI ROS packages matching your distro.

#### Humble/Jazzy

```bash
sudo apt install ros2-testing-apt-source
sudo apt update
sudo apt install ros-$ROS_DISTRO-depthai-ros-v3
```

Run the driver with:

```bash
ros2 launch depthai_ros_driver_v3 driver.launch.py
```

To visualize data in RViz:

```bash
ros2 launch depthai_ros_driver_v3 driver.launch.py use_rviz:=true
```

For running the composable driver package as a separate node:

```bash
ros2 run depthai_ros_driver_v3 driver_node
```

#### Kilted and newer

```bash
sudo apt install ros-$ROS_DISTRO-depthai-ros
```

Run the driver with:

```bash
ros2 launch depthai_ros_driver driver.launch.py
```

To visualize data in RViz:

```bash
ros2 launch depthai_ros_driver driver.launch.py use_rviz:=true
```

For running the composable driver package as a separate node:

```bash
ros2 run depthai_ros_driver driver_node
```

use_rviz:=true will work for all launch files that utilize 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 launch file starts the ROS driver as a composable node inside its own composable node container.

### Prebuilt Docker images

You can also use our prebuilt Docker images, while they are mostly intended for testing and debugging they can serve as a point of
reference between different project versions.

They can also be used to publish data between different ROS versions. i.e. data from driver running in Kitled container should be
accessible in host that uses Jazzy distribution (although this functionatlity depends on the difference between distros and might
not work in all cases)

To run driver with Rviz support you first need to run following command so that GUI window is spawned

```bash
xhost +local:docker
```

Then, run the containers similarly as describer in [Build
article](https://docs.luxonis.com/software-v3/depthai/ros/build-from-source.md)

```bash
docker run -it -v /dev/:/dev/ --privileged -e DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix luxonis/depthai-ros:kilted-latest
```

will run an interactive docker session. You can also try:

```bash
docker run -it -v /dev/:/dev/  --privileged -e DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix luxonis/depthai-ros:kilted-latest [CMD]
```

To run container for a specific version you can use v{VERSION}-kilted , where version is in x.x.x format, so as follows

```bash
docker run -it -v /dev/:/dev/ --privileged -e DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix luxonis/depthai-ros:v3.0.9-kilted
```

We also provide containers for ARM64, they have slightly different names but can be used the same way

```bash
docker run -it -v /dev/:/dev/ --privileged -e DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix luxonis/depthai-ros:kilted-arm64-latest
```

```bash
docker run -it -v /dev/:/dev/ --privileged -e DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix luxonis/depthai-ros:v3.0.9-kilted-arm64
```

You can also pass external YAML file as a configuration for the driver. You can either edit them inside the container itself, or
you can make a .yaml file on your host (let's say /home/YOUR_USERNAME_HERE/params/example_config.yaml) and pass it as an argument
to the executable, as follows:

```bash
docker run -it -v /dev/:/dev/ -v /home/YOUR_USERNAME_HERE/params:/params --network host --privileged -e DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix depthai-ros ros2 launch depthai_ros_driver driver.launch.py params_file:=/params/example_config.yaml
```

## Parameters

Full list of parameters can be found [here.](https://docs.luxonis.com/software-v3/depthai/ros/parameters.md)

## 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.
 * sr_rgbd_pcl.launch.py - Should be used as a baseline for SR cameras due to only having two sensors.
 * sr_poe_rgbd_pcl.launch.py - Should be used as a baseline for SR PoE cameras
 * oak_t.launch.py - A launch file specific to OAK-T lineup
 * calibration.launch.py - Used to launch ROS calibration tool, this is mostly for testing, if you find that your camera has
   invalid calibration, either use our internal calibration tool or contact us directly.
 * vio.launch.py - Launches camera with VIO pipeline enabled by default

## 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_frame

By default, camera transforms are published from based on Device's camera calibration data.

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:=true

It is also possible to set custom URDF path (for now only absolute path works) and custom xacro arguments using
driver.i_tf_custom_urdf_path and driver.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
> `driver.i_tf_imu_from_descr: true`
> . This will publish default IMU extrinsics from URDF based on camera model.

## Custom pipelines

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 dai_ros_plugins), create an executable in that package
(dai_ros_plugins.cpp). Inside that file, define a custom plugin that inherits from depthai_ros_driver::pipeline_gen::BasePipeline
and overrides createPipeline method.

For example

```cpp
std::vector<std::unique_ptr<depthai_ros_driver::dai_nodes::BaseNode>> DaiRosPlugins::createPipeline(
    std::shared_ptr<rclcpp::Node> node,
    std::shared_ptr<dai::Device> device,
    std::shared_ptr<dai::Pipeline> pipeline,
    std::shared_ptr<depthai_ros_driver::param_handlers::PipelineGenParamHandler> ph,
    const std::string& deviceName,
    bool rsCompat,
    const std::string& /*nnType*/) {
    namespace dai_nodes = depthai_ros_driver::dai_nodes;
    std::vector<std::unique_ptr<dai_nodes::BaseNode>> daiNodes;
    auto left = std::make_unique<dai_nodes::SensorWrapper>("left", node, pipeline, deviceName, rsCompat, dai::CameraBoardSocket::CAM_B);
    auto right = std::make_unique<dai_nodes::SensorWrapper>("right", node, pipeline, deviceName, rsCompat, dai::CameraBoardSocket::CAM_C);
    daiNodes.push_back(std::move(left));
    daiNodes.push_back(std::move(right));
    return daiNodes;
}
```

After that export plugin, for example:

```cpp
#include <pluginlib/class_list_macros.hpp>

PLUGINLIB_EXPORT_CLASS(dai_ros_plugins::DaiRosPlugins, depthai_ros_driver::pipeline_gen::BasePipeline)
```

Add plugin definition to your plugins.xml file inside your package:

```xml
<library path="dai_ros_plugins">
  <class type="dai_ros_plugins::DaiRosPlugins" base_class_type="depthai_ros_driver::pipeline_gen::BasePipeline">
    <description>This is a square plugin.</description>
  </class>
</library>
```

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

You can see how the final package with plugin looks like in [our app
examples](https://github.com/luxonis/oak-examples/tree/main/apps/ros/ros-driver-custom-workspace/src/dai_ros_plugins).

## 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 pipeline_gen.i_enable_diagnostics:
true driver.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
# 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_driver_launch_include = IncludeLaunchDescription(
  PythonLaunchDescriptionSource([
      PathJoinSubstitution([
          FindPackageShare('depthai_ros_driver'),
          'launch',
          'driver.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 the 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 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
- 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
```

## 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
