OrSens camera

Overview

This package is a ROS wrapper of SDK for OrSens 3D-camera.

Usage

launch folder contains several files for different purposes:

Nodes

orsens_node

Main node that publishes camera's data, as well as some results of SDK's integrated CV functions.

Published Topics

disp (sensor_msgs/Image)
  • Disparity image, mono8, values in range 0-255, brighter is closer.
depth (sensor_msgs/Image)
  • Depth image, 16UC1, values in millimetres.
left/image_raw (sensor_msgs/Image)
  • Left RGB image, bgr8.
left/camera_info (sensor_msgs/CameraInfo)
  • Left camera info.
right/image_raw (sensor_msgs/Image)
  • Right RGB image, bgr8.
right/camera_info (sensor_msgs/CameraInfo)
  • Right camera info.
cloud (pcl/PCLPointCloud2)
  • Point cloud.
nearest_obstacle (orsens/NearestObstacle)
  • information about nearest obstacle: centre, width, height, direction from camera etc.
segmentation_mask (sensor_msgs/CameraInfo)
  • Image mask which represents scene regions (currently floor only)

Parameters

~capture_mode (string, default: "depth_only")
  • Determines which data to capture from the camera. Possible values are "depth_only"- capture just depth stream, "depth_left" - capture both streams, "left_only" and "left_right".
~data_path (string, default: "data")
  • Path to the data folder.
~left_camera_info_url (string, default: "data_path/calibration/caminfo_left.yml")
  • An url to the left camera calibration file that will be published as left/camera_info.
~right_camera_info_url (string, default: "data_path/calibration/caminfo_right.yml")
  • An url to the right camera calibration file that will be published as right/camera_info.
~frame_id (string, default: "orsens_camera")
  • The camera's tf frame.
~depth_width (int, default: 640)
  • Same for depth stream.
~color_rate (int, default: 15)
  • Request RGB stream framerate.
~depth_rate (int, default: 15)
  • Request depth stream framerate.
~compress_color (bool, default: false)
  • Request compressed RGB stream (may solve USB bandwidth problems).
~compress_depth (bool, default: false)
  • Same for depth stream, but for future use, not working now.
~publish_depth (bool, default: true)
  • Publish depth image.
~publish_cloud (bool, default: false)
  • Publish pointcloud.
~publish_left_camera_info (bool, default: false)
  • Publish left camera metadata.
~publish_right_camera_info (bool, default: false)
  • Publish right camera metadata.
~publish_nearest_obstacle (bool, default: false)
  • Publish information about nearest obstacle.
~publish_segmentation_mask (bool, default: false)
  • Publish mask with scene regions.

Demos

Stereo visual odometry and mapping

Running samples and ROS nodes

OrSens vs. two web-cameras with stereo-matching

Calibration

1. Camera's depth engine is precalibrated, but if you need to recalibrate it for some reason, please contact us at support@oriense-tech.com for instructions and software.

2. To get ROS CameraInfo use camera calibration tool via this launch file.

Wiki: orsens_ros (last edited 2018-06-06 20:59:32 by EnriqueFernandez)