Overview
TaraXL is a UVC compliant 3D Stereo camera based on MT9V024 stereo sensor from ON Semiconductor which supports WVGA ((2*752) x 480) at 60 fps over USB 3.0 in uncompressed format. This Stereo camera provides two synchronized sensor frame data interleaved side by side to the host machine over USB 3.0 interface.
TaraXL can be used by customers who want to develop their Stereo camera algorithms and to integrate Stereo camera in their product design. TaraXL is provided with accelerated SDK for NVIDIA Jetson TX2, Xavier and Ubuntu 16.04 x64 which is ideal for depth application product designs.
Click Here For More Information for TaraXL camera
STEEReoCAM™ is a 2MP 3D MIPI Stereo camera for NVIDIA® Jetson AGX Xavier™/TX2/Nano developer kit with improved accuracy and depth range. This MIPI Stereo camera is based on 1/2.9" OV2311 global shutter CMOS sensor from OmniVision. STEEReoCAM™ is bundled with a proprietary CUDA® accelerated Stereo SDK that runs on the GPU of NVIDIA® Tegra processors. It provides 3D depth mapping at ((2*1600) x 1300) resolution at 22 fps.
STEEReoCAM™ is ideal for applications such as depth sensing, robotics and autonomous guided vehicles, face recognition, gesture recognition, drones, 3D video recording, 3D measurements, embedded vision, surgical robotics, and so on.
Click Here For More Information for STEEReoCAM camera
This package provides ROS Nodes for TaraXL and STEEReoCAM camera.
Installation
Prerequisites
This package requires TaraXL SDK in order to use TaraXL/STEEReoCAM Stereo camera with ROS. Before installing the taraxl-ros-package, follow the Install Prerequisites for TaraXL SDK.
You can download the taraxl-ros-package on github: https://github.com/econsystems/taraxl-ros-package
Install Prerequisites
Download the latest version of the TaraXL SDK at https://developer.e-consystems.com
- Install the TaraXL SDK on your Nvidia Tx2/Xavier/Nano device or Linux system(x86).
Install the Ubuntu install of ROS Melodic and make your system ready for ROS.
- Download the package from github and put it in your catkin src folder
- cd ~/catkin/src
- Build the package from your catkin folder
- cd ~/catkin
- catkin_make
- source ./devel/setup.bash
Support
Email: techsupport@e-consystems.com
ROS API
Published Topics
/taraxl/left/image_rect - Rectified left image
/taraxl/right/image_rect - Rectified right image
/taraxl/left/image_raw - Unrectified left image
/taraxl/right/image_raw - Unrectified right image
/taraxl/stereo/disparity/image - Disparity image
/taraxl/depth/image - Depth image
/taraxl/stereo/pointcloud - pointcloud
/taraxl/imu/data_raw - Raw IMU data - linear acceleration and angular velocity
/taraxl/imu/inclination - IMU inclination data w.r.t 3 axes x,y and z
/taraxl/left/calib/raw - Calibration informations for unrectified left image
/taraxl/right/calib/raw - Calibration informations for unrectified right image
/taraxl/left/calib/rect - Calibration informations for rectified left image
/taraxl/right/calib/rect - Calibration informations for rectified right image
Dynamic Reconfiguration Settings
TaraXL Camera
brightness : Controls brightness of the image (1-7)
exposure : Manual exposure value (10-1000000)
accuracy : Accuracy of the disparity image(0 - HIGH FRAME RATE, 1 - HIGH ACCURACY, 2 - ULTRA ACCURACY)
autoExposure : Enable auto exposure
pointcloudQuality : Quality of pointcloud(1 - HIGHEST, 2 - MEDIUM, 3 - STANDARD)
SteereoCam
brightness : Controls brightness of the image (1-10 - Works only when auto exposure is enabled)
exposure : Manual exposure value (1 - 7500)
accuracy : Accuracy of the disparity image(0 - HIGH FRAME RATE, 1 - HIGH ACCURACY, 2 - ULTRA ACCURACY)
autoExposure : Enable auto exposure
gain : Controls the gain of the camera(1-240)
pointcloudQuality : Quality of pointcloud(1 - HIGHEST, 2 - MEDIUM, 3 - STANDARD)
Test Package
Open a terminal and enter the following commands,
To launch taraxl_ros_package
roslaunch taraxl_ros_package taraxl.launch
To visualize TaraXL/STEEReoCAM image topics
rqt_image_view
To visualize TaraXL/STEEReoCAM dispariy image topic
rosrun image_view disparity_view image:=/taraxl/stereo/disparity/image
To visualize TaraXL/STEEReoCAM pointcloud topic
rosrun rviz rviz
To view imu data
rostopic echo /taraxl/imu/data_raw
rostopic echo /taraxl/imu/inclination
To view calibration parameters for unrectified Frames
rostopic echo /taraxl/left/calib/raw
rostopic echo /taraxl/right/calib/raw
To view calibration parameters for rectified Frames
rostopic echo /taraxl/left/calib/rect
rostopic echo /taraxl/right/calib/rect
Dynamic reconfiguration
rosrun rqt_reconfigure rqt_reconfigure