/realsense-ros

Intel(R) RealSense(TM) ROS Wrapper for D400 series, SR300 Camera and T265 Tracking Module

Primary LanguageC++Apache License 2.0Apache-2.0

ROS Wrapper for Intel® RealSense™ Devices

These are packages for using Intel RealSense cameras (D400 series SR300 camera and T265 Tracking Module) with ROS.

Installation Instructions

The following instructions support ROS Indigo, on Ubuntu 14.04, and ROS Kinetic, on Ubuntu 16.04.

The simplest way to install on a clean machine is to follow the instructions on the .travis.yml file. It basically summerize the elaborate instructions in the following 3 steps:

Step 1: Install the latest Intel® RealSense™ SDK 2.0

  • Install from Debian Package - In that case treat yourself as a developer. Make sure you follow the instructions to also install librealsense2-dev and librealsense-dkms packages.

OR

Step 2: Install the ROS distribution

Step 3: Install Intel® RealSense™ ROS from Sources

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src/
  • Clone the latest Intel® RealSense™ ROS from here into 'catkin_ws/src/'
  • Make sure all dependent packages are installed. You can check .travis.yml file for reference.
  • Specifically, make sure that the ros package ddynamic_reconfigure is installed. If ddynamic_reconfigure cannot be installed using APT, you may clone it into your workspace 'catkin_ws/src/' from here (Version 0.2.0)
catkin_init_workspace
cd ..
catkin_make clean
catkin_make -DCATKIN_ENABLE_TESTING=False -DCMAKE_BUILD_TYPE=Release
catkin_make install
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

Usage Instructions

Start the camera node

To start the camera node in ROS:

roslaunch realsense2_camera rs_camera.launch

This will stream all camera sensors and publish on the appropriate ROS topics.

Other stream resolutions and frame rates can optionally be provided as parameters to the 'rs_camera.launch' file.

Published Topics

The published topics differ according to the device and parameters. After running the above command with D435i attached, the following list of topics will be available (This is a partial list. For full one type rostopic list):

  • /camera/color/camera_info
  • /camera/color/image_raw
  • /camera/depth/camera_info
  • /camera/depth/image_rect_raw
  • /camera/extrinsics/depth_to_color
  • /camera/extrinsics/depth_to_infra1
  • /camera/extrinsics/depth_to_infra2
  • /camera/infra1/camera_info
  • /camera/infra1/image_rect_raw
  • /camera/infra2/camera_info
  • /camera/infra2/image_rect_raw
  • /camera/gyro/imu_info
  • /camera/gyro/sample
  • /camera/accel/imu_info
  • /camera/accel/sample

The "/camera" prefix is the default and can be changed. Check the rs_multiple_devices.launch file for an example. If using D435 or D415, the gyro and accel topics wont be available. Likewise, other topics will be available when using T265 (see below).

Launch parameters

The following parameters are available by the wrapper:

  • serial_no: will attach to the device with the given serial number. Default, attach to available RealSense device in random.

  • rosbag_filename: Will publish topics from rosbag file.

  • initial_reset: On occasions the device was not closed properly and due to firmware issues needs to reset. If set to true, the device will reset prior to usage.

  • align_depth: If set to true, will publish additional topics with the all the images aligned to the depth image.
    The topics are of the form: /camera/aligned_depth_to_color/image_raw etc.

  • filters: any of the following options, separated by commas:

  • colorizer: will color the depth image. On the depth topic an RGB image will be published, instead of the 16bit depth values .

  • pointcloud: will add a pointcloud topic /camera/depth/color/points. The texture of the pointcloud can be modified in rqt_reconfigure (see below) or using the parameters: pointcloud_texture_stream and pointcloud_texture_index. Run rqt_reconfigure to see available values for these parameters.
    The depth FOV and the texture FOV are not similar. By default, pointcloud is limited to the section of depth containing the texture. You can have a full depth to pointcloud, coloring the regions beyond the texture with zeros, by setting allow_no_texture_points to true.

  • The following filters have detailed descriptions in : https://github.com/IntelRealSense/librealsense/blob/master/doc/post-processing-filters.md

    • disparity - convert depth to disparity before applying other filters and back.
    • spatial - filter the depth image spatially.
    • temporal - filter the depth image temporally.
    • hole_filling - apply hole-filling filter.
    • decimation - reduces depth scene complexity.
  • enable_sync: gathers closest frames of different sensors, infra red, color and depth, to be sent with the same timetag. This happens automatically when such filters as pointcloud are enabled.

  • <stream_type>_width, <stream_type>_height, <stream_type>_fps: <stream_type> can be any of infra, color, fisheye, depth, gyro, accel, pose. Sets the required format of the device. If the specified combination of parameters is not available by the device, the stream will not be published. Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined). Note: for gyro accel and pose, only _fps option is meaningful.

  • enable_<stream_name>: Choose whether to enable a specified stream or not. Default is true. <stream_name> can be any of infra1, infra2, color, depth, fisheye, fisheye1, fisheye2, gyro, accel, pose.

  • tf_prefix: By default all frame's ids have the same prefix - camera_. This allows changing it per camera.

  • base_frame_id: defines the frame_id all static transformations refers to.

  • odom_frame_id: defines the origin coordinate system in ROS convention (X-Forward, Y-Left, Z-Up). pose topic defines the pose relative to that system.

  • All the rest of the frame_ids can be found in the template launch file: nodelet.launch.xml

  • unite_imu_method: The D435i and T265 cameras have built in IMU components which produce 2 unrelated streams: gyro - which shows angular velocity and accel which shows linear acceleration. Each with it's own frequency. By default, 2 corresponding topics are available, each with only the relevant fields of the message sensor_msgs::Imu are filled out. Setting unite_imu_method creates a new topic, imu, that replaces the default gyro and accel topics. Under the new topic, all the fields in the Imu message are filled out.

  • linear_interpolation: Each message contains the last original value of item A interpolated with the previous value of item A, combined with the last original value of item B on last item B's timestamp. Items A and B are accel and gyro interchangeably, according to which type recently arrived from the sensor. The idea is to give the most recent information, united and without repetitions.

  • copy: For each new message, accel or gyro, the relevant fields and timestamp are filled out while the others maintain the previous data.

  • clip_distance: remove from the depth image all values above a given value (meters). Disable by giving negative value (default)

  • linear_accel_cov, angular_velocity_cov: sets the variance given to the Imu readings. For the T265, these values are being modified by the inner confidence value.

  • hold_back_imu_for_frames: Images processing takes time. Therefor there is a time gap between the moment the image arrives at the wrapper and the moment the image is published to the ROS environment. During this time, Imu messages keep on arriving and a situation is created where an image with earlier timestamp is published after Imu message with later timestamp. If that is a problem, setting hold_back_imu_for_frames to true will hold the Imu messages back while processing the images and then publish them all in a burst, thus keeping the order of publication as the order of arrival. Note that in either case, the timestamp in each message's header reflects the time of it's origin.

  • topic_odom_in: For T265, add wheel odometry information through this topic. The code refers only to the twist.linear field in the message.

  • calib_odom_file: For the T265 to include odometry input, it must be given a configuration file. Explanations can be found here. The calibration is done in ROS coordinates system.

  • publish_odom_tf: If True (default) publish TF from odom_frame to pose_frame.

RGBD Point Cloud

Here is an example of how to start the camera node and make it publish the RGBD point cloud using aligned depth topic.

roslaunch realsense2_camera rs_camera.launch filters:=pointcloud

Then open rviz to watch the pointcloud:

Aligned Depth Frames

Here is an example of how to start the camera node and make it publish the aligned depth stream to other available streams such as color or infra-red.

roslaunch realsense2_camera rs_camera.launch align_depth:=true

Set Camera Controls Using Dynamic Reconfigure Params

The following command allow to change camera control values using [http://wiki.ros.org/rqt_reconfigure].

rosrun rqt_reconfigure rqt_reconfigure

Work with multiple cameras

Here is an example of how to start the camera node and streaming with two cameras using the rs_multiple_devices.launch.

roslaunch realsense2_camera rs_multiple_devices.launch serial_no_camera1:=<serial number of the first camera> serial_no_camera2:=<serial number of the second camera>

The camera serial number should be provided to serial_no_camera1 and serial_no_camera2 parameters. One way to get the serial number is from the rs-enumerate-devices tool.

rs-enumerate-devices | grep Serial

Another way of obtaining the serial number is connecting the camera alone, running

roslaunch realsense2_camera rs_camera.launch

and looking for the serial number in the log printed to screen under "[INFO][...]Device Serial No:".

Another way to use multiple cameras is running each from a different terminal. Make sure you set a different namespace for each camera using the "camera" argument:

roslaunch realsense2_camera rs_camera.launch camera:=cam_1 serial_no:=<serial number of the first camera>
roslaunch realsense2_camera rs_camera.launch camera:=cam_2 serial_no:=<serial number of the second camera>
...

Using T265

Important Notice: For wheeled robots, odometer input is a requirement for robust and accurate tracking. The relevant APIs will be added to librealsense and ROS/realsense in upcoming releases. Currently, the API is available in the underlying device driver.

Start the camera node

To start the camera node in ROS:

roslaunch realsense2_camera rs_t265.launch

This will stream all camera sensors and publish on the appropriate ROS topics.

The T265 sets its usb unique ID during initialization and without this parameter it wont be found. Once running it will publish, among others, the following topics:

  • /camera/odom/sample
  • /camera/accel/sample
  • /camera/gyro/sample
  • /camera/fisheye1/image_raw
  • /camera/fisheye2/image_raw

To visualize the pose output and frames in RViz, start:

roslaunch realsense2_camera demo_t265.launch

About Frame ID

The wrapper publishes static transformations(TFs). The Frame Ids are divided into 3 groups:

  • ROS convention frames: follow the format of <tf_prefix>_<_stream>"_frame" for example: camera_depth_frame, camera_infra1_frame, etc.
  • Original frame coordinate system: with the suffix of <_optical_frame>. For example: camera_infra1_optical_frame. Check the device documentation for specific coordinate system for each stream.
  • base_link: For example: camera_link. A reference frame for the device. In D400 series and SR300 it is the depth frame. In T265, the pose frame.

realsense2_description package:

For viewing included models, a separate package is included. For example:

roslaunch realsense2_description view_d415_model.launch

Unit tests:

Unit-tests are based on bag files saved on S3 server. These can be downloaded using the following commands:

cd catkin_ws
wget "http://realsense-hw-public.s3.amazonaws.com/rs-tests/TestData/outdoors.bag" -P "records/"
wget "http://realsense-hw-public.s3-eu-west-1.amazonaws.com/rs-tests/D435i_Depth_and_IMU_Stands_still.bag" -P "records/"

Then, unit-tests can be run using the following command:

python src/realsense/realsense2_camera/scripts/rs2_test.py --all

Packages using RealSense ROS Camera

Title Links
ROS Object Analytics github / ROS Wiki

Known Issues

  • This ROS node does not currently support ROS Lunar Loggerhead.
  • This ROS node does not currently work with ROS 2.
  • This ROS node currently does not provide the unit-tests which ensure the proper operation of the camera. Future versions of the node will provide ROS compatible unit-tests.

License

Copyright 2018 Intel Corporation

Licensed under the Apache License, Version 2.0 (the "License"); you may not use this project except in compliance with the License. You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

*Other names and brands may be claimed as the property of others