ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
If you're following the tutorial then you'll be using:
roslaunch vslam_system stereo_vslam.launch
If you look at the stereo_vslam.launch
file, it has:
<node name="stereo_vslam_node"...
This is launching the binary compiled from the source vslam_system/src/nodes/stereo_vslam_node.cpp
. If you check that file, you'll see that it only subscribes to these topics:
// Synchronize inputs
l_image_sub_.subscribe(it_, "left/image_rect", 1);
l_info_sub_ .subscribe(nh_, "left/camera_info", 1);
r_image_sub_.subscribe(it_, "right/image_rect", 1);
r_info_sub_ .subscribe(nh_, "right/camera_info", 1);
sync_.connectInput(l_image_sub_, l_info_sub_, r_image_sub_, r_info_sub_);
So to answer your question, there's no tf inputs needed. It does however broadcast odometry data as tf's in a fixed frame called pgraph
.
2 | No.2 Revision |
If you're following the tutorial then you'll be using:
roslaunch vslam_system stereo_vslam.launch
If you look at the stereo_vslam.launch
file, it has:
<node name="stereo_vslam_node"...
This is launching the binary compiled from the source vslam_system/src/nodes/stereo_vslam_node.cpp
. If you check that file, you'll see that it only subscribes to these topics:
// Synchronize inputs
l_image_sub_.subscribe(it_, "left/image_rect", 1);
l_info_sub_ .subscribe(nh_, "left/camera_info", 1);
r_image_sub_.subscribe(it_, "right/image_rect", 1);
r_info_sub_ .subscribe(nh_, "right/camera_info", 1);
sync_.connectInput(l_image_sub_, l_info_sub_, r_image_sub_, r_info_sub_);
So to answer your question, there's no tf inputs needed. It does however You may be able to get it to broadcast odometry data as tf's in a fixed frame called if you provide the
transform. However that code (in the latest svn) is disabled with an pgraphbase_footprintif (0)
.