Wiki

Overview

This package provides the functionality of libelas in the form of a ROS node. In addition it provides simple point cloud construction functionality.

St Lucia Point Cloud

This shows an example point cloud that can be constructed. This uses the St Lucia dataset, which is available at https://wiki.qut.edu.au/display/cyphy/UQ+St+Lucia. The visualisation uses rviz.

Relevant Publications

LATEX BIBTEX CITATION ENTRY:
@INPROCEEDINGS{Geiger10,
 author = {Andreas Geiger and Martin Roser and Raquel Urtasun},
 title = {Efficient Large-Scale Stereo Matching},
 booktitle = {Asian Conference on Computer Vision},
 year = {2010},
 month = {November},
 address = {Queenstown, New Zealand}
}

Nodes

elas_ros

This node performs the disparity matching, and generates point clouds in the camera's local reference frame.

Subscribed Topics

<stereo>/left/<image> (sensor_msgs/Image) <stereo>/right/<image> (sensor_msgs/Image) <stereo>/left/camera_info (sensor_msgs/CameraInfo) <stereo>/right/camera_info (sensor_msgs/CameraInfo)

Published Topics

disparity (sensor_msgs/Image) point_cloud (sensor_msgs/PointCloud2) frame_data (elas_ros/ElasFrameData)

Parameters

~queue_size (int, default: 5) ~approximate_sync (bool, default: false)

pc_construction

This node concatenates the point clouds generated by the elas_ros node.

Subscribed Topics

<frame_data> (elas_ros/ElasFrameData) <pose> (geometry_msgs/PoseStamped)

Published Topics

point_cloud (sensor_msgs/PointCloud2)

Parameters

~queue_size (int, default: 5) ~approximate_sync (bool, default: false) base_frame_id (string) pose_frame_id (string)

Usage

This code should be used in conjunction with visual odometry to concatenate point clouds. Testing so far has used the ROS wrapper for libviso, but any visual odometry node that publishes a sensor_msgs/PoseStamped message is suitable.

Usage steps:

  1. Publish transforms from the pose frame to the camera frame
  2. Publish left/right images and camera info
  3. Run libviso or similar on the images, which generates pose topic used by the pc_construction node

  4. Run elas_ros on the images, which generates elas frame data used by the pc_construction node

  5. Run pc_construction to generate reconstructed 3D point clouds

A sample launch file, given that images are published on /stereo/left/image_rect and /stereo/right/image_rect and camera info is published on /stereo/left/camera_info and /stereo/right/camera_info is supplied below.

The relevant frames are: odom_combinedbase_footprintbase_linkcamera_0

libviso publishes the transform from odom_combinedbase_footprint, and in this example the other two transforms were static (and published using static_transform_publisher).

The current frame's point cloud is published to /elas/point_cloud, the concatenated point cloud is published to /elas_pc/point_cloud

<launch>

  <!-- This can be replaced with your favourite visual odometry node. -->
  <node pkg="viso2_ros" type="stereo_odometer" name="vo2"
      args="stereo:=stereo image:=image_rect _odom_frame_id:=/odom_combined _base_link_frame_id:=/base_footprint _publish_tf:=true">
    <param name="approximate_sync" value="true" />
  </node>

  <node pkg="elas_ros" type="elas_ros" name="elas" args="stereo:=stereo image:=image_rect_color" respawn="true">
    <param name="approximate_sync" value="true" />
  </node>
  <node pkg="elas_ros" type="pc_construction" name="elas_pc"
    args="frame_data:=/elas/frame_data pose:=/vo2/pose base_frame_id:=/odom_combined pose_frame_id:=/base_footprint" />

</launch>

Contacts

Patrick Ross: patrick.ross@connect.qut.edu.au (Code maintainer)

Andreas Geiger: geiger@kit.edu (libelas author)

Ben Upcroft: ben.upcroft@qut.edu.au

David Ball: david.ball@qut.edu.au

Wiki: elas_ros (last edited 2017-05-10 20:05:02 by IsaacSaito)