Wiki

DUO3D™ ROS Software Maintainer: DUO3D

Introduction

The DUO MLX is an ultra-compact imaging sensor with global shutter and a standard USB interface for ease of use and connectivity. The DUO is intended for use in research, autonomous navigation, robotics and industrial areas. The camera's high speed and small size make it ideal for existing and new use cases for vision based applications.

https://duo3d.com/public/media/products/duo_m_mlx_feb10-136.png

With a programmable illumination board and built-in IR filters and auto-exposure it allows for precise control of lighting environment, delivering configurable and precise stereo imaging for robotics, inspection, microscopy, visual odometry, human computer interaction and beyond.

The DUO MLX solution consists of:

The DUO line of sensors offer a versatile board level solution for 3D sensing, a solution equipped with IMU and IR illumination and a board level sensor with an aluminum enclosure and a complete system for utilizing stereo vision that comes with a DUO MLX sensor and the DUO VPC processor. All DUO sensors are ready to work right out of the box and support a wide range of accessories and configurations.

For more information visit DUO3D Home Page

Installation

DUO SDK

The DUO SDK package is required for DUO device support under your Linux operating system. It consists of kernel module and user mode libraries that expose all of the DUO functionalities with a simple and concise C/C++ API. Included in the package is the Dense3D™, an SIMD/NEON optimized multi-threaded library that performs the disparity and 3D data extraction from DUO stereo image pair.

DUO ROS package

DUO ROS driver package is build on Ubuntu 16.04.1 LTS x64 running ROS Kinetic.

Get the package from github and put it in your catkin workspace src folder:

    $ cd ~/catkin_ws/src
    $ git clone https://github.com/duo3d/duo3d_driver
    $ chmod a+x cfg/Duo3D.cfg

Build the package:

    $ cd ~/catkin_ws
    $ catkin_make duo3d_driver
    $ source ./devel/setup.bash

duo3d_driver

The duo3d_driver node interfaces with DUO SDK and publishes stereo images, disparity, point cloud, and IMU data from the DUO3D sensor.

Published Topics

duo3d_driver/left/image_rect (sensor_msgs/Image) duo3d_driver/left/camera_info (sensor_msgs/CameraInfo) duo3d_driver/right/image_rect (sensor_msgs/Image) duo3d_driver/right/camera_info (sensor_msgs/CameraInfo) duo3d_driver/rgb/image_rect (sensor_msgs/Image) duo3d_driver/rgb/camera_info (sensor_msgs/CameraInfo) duo3d_driver/depth/image_raw (sensor_msgs/Image) duo3d_driver/depth/camera_info (sensor_msgs/CameraInfo) duo3d_driver/point_cloud/image_raw (sensor_msgs/PointCloud2) duo3d_driver/imu/data_raw (sensor_msgs/Imu)

Parameters

~frame_rate (double, default: 30) ~image_size (vector<int>, default: {640,480}) ~dense3d_license (string) ~gain (double, default: 0%) ~exposure (double, default: 50%) ~auto_exposure (bool, default: False) ~camera_swap (bool, default: False) ~horizontal_flip (bool, default: False) ~vertical_flip (bool, default: False) ~led (double, default: 10%) ~accel_range (int, default: +/-2g (0)) ~gyro_range (int, default: 250deg/s) ~imu_rate (double, default: 100Hz) ~processing_mode (int, default: BM (0)) ~image_scale (int, default: ScaleXY (3)) ~pre_filter_cap (int, default: 28) ~num_disparities (int, default: 4) ~sad_window_size (int, default: 6) ~uniqueness_ratio (int, default: 27) ~speckle_window_size (int, default: 52) ~speckle_range (int, default: 14)

Testing the DUO ROS package

Make sure that DUO device is plugged in the USB port and it is operating properly.

DUO ROS Camera Example

This example demonstrates the acquisition of rectified stereo image pair from DUO. To launch DUO Camera ROS example, in a terminal run the following command:

   $ roslaunch duo3d_driver duo3d_camera.launch

You should see the following: https://duo3d.com/public/media/products/ROS-DUO-Camera.jpg

DUO ROS IMU Example

This example demonstrates the DUO's on-board 6DoF sensor fusion using Madgwick algorithm running at 100Hz. To launch DUO IMU ROS example, in a terminal run the following command:

   $ roslaunch duo3d_driver duo3d_imu.launch

You should see the following: https://duo3d.com/public/media/products/ROS-DUO-IMU.jpg

DUO ROS Point Cloud Example

This example demonstrates disparity and point cloud generation using DUO. To launch DUO IMU Point Cloud example, in a terminal run the following command:

   $ roslaunch duo3d_driver duo3d_depth.launch

You should see the following: https://duo3d.com/public/media/products/ROS-DUO-PointCloud.jpg

Getting Help

Wiki: duo3d-ros-driver (last edited 2016-10-19 10:32:56 by AlexanderPopovich)