(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Running VSLAM on Stereo Data

Description: A tutorial that explains how to use the stereo_vslam_node to get point and odometry information from stereo images.

Tutorial Level: INTERMEDIATE

In this tutorial we will cover the basics of using VSLAM on stereo images in ROS.

Please note that vslam_system is under active development and will be changing significantly in the near future, as will this tutorial.

Getting vslam_system

To check out the latest vslam_system and dependencies on top of an existing cturtle installation, follow the instructions at http://www.ros.org/wiki/vslam .

Necessary Data

In order to use Stereo VSLAM, you need the following ROS Topics:

  • left/image_rect
  • left/camera_info
  • right/image_rect
  • right/camera_info

And they must all be synchronized; that is, there should be a set of all 4 messages published with identical timestamps.

Testing on Bag Data

In order to test that everything is working correctly, or to simply look at what the output of the system looks like, it's useful to run the algorithm on some test data.

Setup

First, download a sample bag (446 MB):

$ wget http://pr.willowgarage.com/data/vslam_system/vslam_tutorial.bag

Note: This bag is in cturtle format. If you are running diamondback or newer you will need to migrate the bag forward.

Then, start the VSLAM node using a launch file:

$ roslaunch vslam_system stereo_vslam.launch

In a new terminal, type

$ roscd vslam_system
$ rosrun rviz rviz -d simple_vslam.vcg

Then open another new terminal, and type:

$ rosbag play --clock /path/to/your/bag/vslam_tutorial.bag

Results

You should see something like the following in Rviz as the bag plays:

vslam_tutorial_bag.png

Teal represents the camera pose at each keyframe, and red points represent all 3D points in the system.

In the image_view that the launchfile spawns, you should see something like this:

vslam_tutorial_vo.png

Here, red is all the keypoints found in the image, and blue lines represent tracks through several frames.

Running on Your Own Data

If you publish all the topics described in Necessary Data, then to use your own messages, simply change the namespace or remap topics in stereo_vslam.launch to the correct topics.

For example, if your stereo camera publishes on /mycam/left/image_rect, /mycam/left/camera_info, etc., change lines 5-8 in stereo_vslam.launch to say:

  <!-- Run stereo VSLAM on wide stereo data -->
  <group ns="mycam">
    <node name="stereo_vslam_node" pkg="vslam_system" type="stereo_vslam_node" args="$(find vocabulary_tree)/holidays.tree $(find vocabulary_tree)/holidays.weights $(find calonder_descriptor)/current.rtc" output="screen" cwd="node" />
  </group>

If, on the other hand, your cameras publish their images on /myrandomleftimage, /myrandomleftcamerainfo, etc., use roslaunch remapping commands instead:

  <!-- Run stereo VSLAM on wide stereo data -->
    <node name="stereo_vslam_node" pkg="vslam_system" type="stereo_vslam_node" args="$(find vocabulary_tree)/holidays.tree $(find vocabulary_tree)/holidays.weights $(find calonder_descriptor)/current.rtc" output="screen" cwd="node" >
      <remap from="left/image_rect" to="/myrandomleftimage" />
      <remap from="left/camera_info" to="/myrandomleftcamerainfo" />
      <!-- repeat for right camera topics -->
    </node>

Again, remember that all 4 of these topics must publish synchronously.

Note: If Error encountered while running vslam_tutorial.bag, following modifications are required:

$ rosbag check vslam_tutorial.bag
#The following migrations need to occur:
# * From: sensor_msgs/CameraInfo [1b5cf7f984c229b6141ceb3a955aa18f]
#   To:   sensor_msgs/CameraInfo [c9a58c1b0b154e0e6da7578cb991d214]
To fix:
$ rosbag fix vslam_tutorial.bag vslam_tutorial_new.bag
To play the modified bag:
$ rosbag play --clock vslam_tutorial_new.bag
All other steps remain the same.

Wiki: vslam_system/Tutorials/RunningVslamOnStereoData (last edited 2011-06-28 16:38:03 by TullyFoote)