## page was copied from duo3d-driver ## page was renamed from duo3d-ros-driver ## keywords = stereo, duo, imu, point cloud, depth, computer vision, camera, visual odometry <> ''DUO3D™ ROS Software Maintainer: [[https://duo3d.com/|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/all-duos-1.6.png||width="100%"}} {{https://duo3d.com/public/media/products/duo_m_mlx_feb10-136.png||width="100%"}} 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: * Factory Calibrated Stereo Camera * Industrial Grade Monochrome/Global Shutter Sensors * Integrated Accelerometer/Gyroscope/Temperature (6 DoF IMU) * Fully Programmable Active LED Array (3xIR 850nm High Power LEDs) * DUO SDK License * DUO Dense3D License * USB Mini-B Cable 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 [[https://duo3d.com|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. * To download the DUO SDK visit the [[https://duo3d.com/docs/downloads|Download page]] * To install the DUO SDK follow the [[https://duo3d.com/docs/articles/install-all|Install guide]] * To download DUO ROS driver visit [[https://github.com/duo3d/duo3d_driver|DUO ROS Driver]] === 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 }}} {{{ #!clearsilver CS/NodeAPI node.0 { name = duo3d_driver desc = The `duo3d_driver` node interfaces with DUO SDK and publishes stereo images, disparity, point cloud, and IMU data from the DUO3D sensor. pub{ 0.name= duo3d_driver/left/image_rect 0.type= sensor_msgs/Image 0.desc= Left camera rectified image 1.name= duo3d_driver/left/camera_info 1.type= sensor_msgs/CameraInfo 1.desc= Left camera info 2.name= duo3d_driver/right/image_rect 2.type= sensor_msgs/Image 2.desc= Right camera rectified image 3.name= duo3d_driver/right/camera_info 3.type= sensor_msgs/CameraInfo 3.desc= Right camera info 4.name= duo3d_driver/rgb/image_rect 4.type= sensor_msgs/Image 4.desc= Left camera RGB rectified image 5.name= duo3d_driver/rgb/camera_info 5.type= sensor_msgs/CameraInfo 5.desc= Left camera info 6.name= duo3d_driver/depth/image_raw 6.type= sensor_msgs/Image 6.desc= Colored disparity image 7.name= duo3d_driver/depth/camera_info 7.type= sensor_msgs/CameraInfo 7.desc= Disparity info 8.name= duo3d_driver/point_cloud/image_raw 8.type= sensor_msgs/PointCloud2 8.desc= DUO 3D point cloud data 9.name= duo3d_driver/imu/data_raw 9.type= sensor_msgs/Imu 9.desc= DUO IMU data } param{ 0.name= ~frame_rate 0.type= double 0.default= 30 0.desc= DUO image capture frame rate 1.name= ~image_size 1.type= vector 1.default= {640,480} 1.desc= DUO image frame size 2.name= ~dense3d_license 2.type= string 2.desc= Dense3D license string 3.name= ~gain 3.type= double 3.default= 0% 3.desc= Image gain value [0, 100] 4.name= ~exposure 4.type= double 4.default= 50% 4.desc= Image exposure value [0, 100] 5.name= ~auto_exposure 5.type= bool 5.default= False 5.desc= Image auto exposure value [False, True] 6.name= ~camera_swap 6.type= bool 6.default= False 6.desc= Image swap [False, True] 7.name= ~horizontal_flip 7.type= bool 7.default= False 7.desc= Horizontal image flip [False, True] 8.name= ~vertical_flip 8.type= bool 8.default= False 8.desc= Vertical image flip [False, True] 9.name= ~led 9.type= double 9.default= 10% 9.desc= LED brightness value [0, 100] 10.name= ~accel_range 10.type= int 10.default= +/-2g (0) 10.desc= Accelerometer Range [+/-2g (0), +/-4g (1), +/-8g (2), +/-16g (3)] 11.name= ~gyro_range 11.type= int 11.default= 250deg/s 11.desc= Gyroscope Range [250deg/s (0), 500deg/s (1), 1000deg/s (2), 2000deg/s (3)] 12.name= ~imu_rate 12.type= double 12.default= 100Hz 12.desc= IMU Data Sampling Rate [25, 500] 13.name= ~processing_mode 13.type= int 13.default= BM (0) 13.desc= Dense3D Processing Mode [BM (0), SGBM(1)] 14.name= ~image_scale 14.type= int 14.default= ScaleXY (3) 14.desc= Dense3D Image Scaling Mode [ScaleNone (0), ScaleX (1), ScaleY (2), ScaleXY (3)] 15.name= ~pre_filter_cap 15.type= int 15.default= 28 15.desc= Dense3D Pre-filter cap [1, 63] 16.name= ~num_disparities 16.type= int 16.default= 4 16.desc= Dense3D Number of disparities [2, 16] 17.name= ~sad_window_size 17.type= int 17.default= 6 17.desc= Dense3D SAD Window Size [2, 10] 18.name= ~uniqueness_ratio 18.type= int 18.default= 27 18.desc= Dense3D Uniqueness Ratio [1, 100] 19.name= ~speckle_window_size 19.type= int 19.default= 52 19.desc= Dense3D Speckle Window Size [0, 256] 20.name= ~speckle_range 20.type= int 20.default= 14 20.desc= Dense3D Speckle Range [0, 32] } } }}} === 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||width="100%"}} ==== 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||width="100%"}} ==== 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||width="100%"}} == Getting Help == * For general help regarding DUO, you can visit the official [[https://duo3d.com/forums|DUO forum]] * For more information about DUO API please visit [[https://duo3d.com/docs/articles/sdk|DUO SDK]] * For ROS specific issues, please open a [[https://github.com/duo3d/duo3d_driver/issues|ticket]]