Analysis of ROS-based Visual and Lidar Odometry for a Teleoperated
Crawler-type Robot in Indoor Environment
Maxim Sokolov, Oleg Bulichev and Ilya Afanasyev
Institute of Robotics, Innopolis University, Universitetskaya str. 1, 420500 Innopolis, Russia
Keywords:
Monocular SLAM, ROS, Visual Odometry, Lidar Odometry, Crawler Robot, ORB-SLAM, LSD-SLAM.
Abstract:
This article presents a comparative analysis of ROS-based monocular visual odometry, lidar odometry and
ground truth-related path estimation for a crawler-type robot in indoor environment. We tested these methods
with the crawler robot ”Engineer”, which was teleoperated in a small-sized indoor workspace with office-
style environment. Since robot’s onboard computer can not work simultaneously with ROS packages of lidar
odometry and visual SLAM, we used online computation of lidar odometry, while video data from onboard
camera was processed offline by ORB-SLAM and LSD-SLAM algorithms. As far as crawler robot motion is
accompanied by significant vibrations, we faced some problems with these visual SLAM, which resulted in
decreasing accuracy of robot trajectory evaluation or even fails in visual odometry, in spite of using a video
stabilization filter. The comparative analysis shown that lidar odometry is close to the ground truth, whereas
visual odometry can demonstrate significant trajectory deviations.
1 INTRODUCTION
Over the last decade visual odometry has become the
valuable tool for estimation of a vehicle’s pose, orien-
tation and trajectory through analysis of correspond-
ing onboard camera images recorded during vehicle
motion. However, visual odometry methods are sen-
sitive to illumination conditions and can fail in case of
insufficiency of visual features since a scene requires
enough texture to let explicit motion be estimated.
It makes essential to combine visual odometry with
other measurements like wheel odometry, lidar odom-
etry, global positioning system (GPS), inertial mea-
surement units (IMUs), etc. (Scaramuzza and Fraun-
dorfer, 2011), (Zhang and Singh, 2015), (Sarvrood
et al., 2016). Nevertheless, the other types of on-
board odometry can have own drawbacks. For in-
stance, lidar odometry at robot motion includes fluc-
tuations in positions of point clouds over time. There-
fore, onboard sensor odometry should be provided
with ground truth
1
.
Since we utilize a single onboard camera, we
are interested in monocular visual odometry, which
is characterized by computing both relative vehi-
cle motion and 3D scene structure from 2D video
1
”Ground truth” is defined as a reference tool or a set
of measurements that are known to be much more accurate
than measurements from a system under investigation
data. Very often, researchers define three cate-
gories of monocular visual odometry: (1) feature-
based, (2) appearance-based (also known as direct),
and hybrid methods (Scaramuzza and Fraundorfer,
2011). Appearance-based methods estimate intensity
of all image pixels with the following direct image-
to-image alignment, whereas feature-based methods
extract appreciable and repeatable features that can
be tracked through the frames. Finally, hybrid meth-
ods apply to a combination of both previous ap-
proaches. We need to emphasize that in our investiga-
tion we exploit visual simultaneous localization and
mapping (V-SLAM) methods, which are originally
focused on calculating a global map and robot path
while tracking onboard camera position and orienta-
tion. However, in our case we study a robot motion
in small indoor workspace, thereby we extend the re-
sults of V-SLAM to visual odometry, neglecting a dif-
ference between these definitions and considering the
workspace map as a global map. In our research we
use both feature-based and appearance-based meth-
ods for robot path recovery by choosing two monoc-
ular V-SLAM: ORB-SLAM (Mur-Artal et al., 2015)
and LSD-SLAM (Engel et al., 2014) recognized as
enhanced and robust methods. Both of these meth-
ods have demonstrated good results in tracking, map-
ping, and camera localization for outdoor applica-
tions, but there are some uncertainties with robust-
316
Sokolov, M., Bulichev, O. and Afanasyev, I.
Analysis of ROS-based Visual and Lidar Odometry for a Teleoperated Crawler-type Robot in Indoor Environment.
DOI: 10.5220/0006420603160321
In Proceedings of the 14th International Conference on Informatics in Control, Automation and Robotics (ICINCO 2017) - Volume 2, pages 316-321
ISBN: Not Available
Copyright © 2017 by SCITEPRESS Science and Technology Publications, Lda. All rights reserved
ness and feasibility to indoor robot navigation in typ-
ical office-style environment with monotone-painted
walls (Buyval et al., 2017). Except V-SLAM we also
provided ROS-based onboard lidar odometry in on-
line mode, getting more accurate information about
robot motion trajectory. Since crawler robot motion
suffers significant shakes, vibrations and sharp turns,
it brings deviations in onboard sensor outputs, de-
creasing accuracy of trajectory evaluation or even fail-
ing visual odometry. Therefore, robot path verifica-
tion is provided by an external camera-based moni-
toring system, which is not affected by vibrations.
Our main goal of this study is to compute a
crawler-type robot trajectory via different odome-
try methods realized in ROS
2
, providing: (1) vi-
sual odometry acquisition for robot motion within
the workspace by using onboard camera and two V-
SLAM packages: feature-based ORB-SLAM and di-
rect LSD-SLAM; (2) comparison of onboard visual
and lidar odometry; (3) a verification of both visual
and lidar odometry with the real robot trajectory mea-
sured by the external camera-based monitoring sys-
tem as the ground truth. To summarize, this pa-
per analyzes and compares different monocular visual
odometry with lidar odometry and the ground truth-
based robot path estimation. Since onboard computer
of our robot did not permit a simultaneous run of ROS
packages for lidar and two visual SLAM, we launched
ROS-based lidar odometry online and recorded on-
board and external cameras’ video in synchronous
mode. Then, we processed onboard video offline with
ORB and LSD-SLAM, comparing visual and lidar
odometry with ground truth-based robot trajectories.
The rest of the paper is organized as following.
Section 2 introduces system setup, Section 3 presents
ROS-based visual and lidar odometry, and Section 4
describes indoor tests and robot trajectories evalua-
tion. In Section 5 we analyze visual and lidar odome-
try estimation. Finally, we conclude in Section 6.
2 SYSTEM SETUP
2.1 Robot System Configuration
The crawler-type robot ”Engineer” (Fig. 1) is de-
signed and manufactured by ”Servosila” company
3
to
overcome complex terrain while navigating in con-
fined spaces and solving a number of challenging
tasks for search and rescue missions. The robot has
2
Robot Operating System (ROS), which is a set of soft-
ware libraries and tools for robot applications, www.ros.org
3
”Servosila” company, www.servosila.com/en/
tracks, flippers, and a robotic arm, that support capa-
bilities for climbing stairs, traversing doorways and
narrow passages, negotiating obstacles, leveling itself
from sideways/upside down positions, etc. Moreover,
the robotic arm is equipped by a head with sensors,
controllers and grippers, that allows to have a flexible
remote control for lifting heavy loads, opening differ-
ent doors, plus grasping, pushing or pulling objects.
The robot sensors pack can contain of a laser scan-
ner, an optical zoom camera, a thermal vision cam-
era, a pair of stereo cameras, IMU and GPS naviga-
tion tools. The detailed information about our set of
robot vision system is presented in Table 1.
Since our robot’ sensor pack does not have a
built-in laser scanner, we mounted the scanning laser
rangefinder Hokuyo URG-04LX-UG01
4
on the robot
head (see, Fig. 2). This laser is often used for au-
tonomous robots, as far as it has light weight (160g),
low-power consumption (2.5W), convenient for in-
door application scanning range from 2 cm to 5.6 m,
wide field of view up to 240
, angular resolution of
0.36
, refresh rate of 10Hz, and accuracy up to 3%
relatively to measured distance.
Figure 1: The Servosila ”Engineer” crawler robot. Courtesy
of Servosila company.
Figure 2: The ”Engineer” robot head’s sensor system.
2.2 Robot Vision System
To validate onboard visual and lidar data, we used ex-
ternal ground truth system based on Basler acA2000-
4
Hokuyo Automatic Co. 2D lidar, www.hokuyo-aut.jp
Analysis of ROS-based Visual and Lidar Odometry for a Teleoperated Crawler-type Robot in Indoor Environment
317
Table 1: The Servosila ”Engineer” robot vision system.
Type Quantity Direction Resolution Palette Night vision Zoom Rate
Mono one front 1280*720 RGB No Yes 60fps
Stereo pair two front 640*480 YUYV Yes No 30fps
Mono one rear 640*480 YUYV No No 30fps
Figure 3: Workspace with the ground truth camera above.
50gc camera
5
(see, characteristics in Table 2), which
was hung up under the workspace on the height of
about 3m and connected to PC (Fig. 3). Before tests
the camera was calibrated against a chessboard with
camera calibration” ROS package
6
.
Table 2: Basler acA2000-50gc camera characteristics .
Parameter Configuration
Image Sensor CMV2000 CMOS
Video resolution 2MP, 2046*1086
Frame rate 50 fps
Mono/Color Color
Shutter Global shutter
3 ROS-BASED VISUAL AND
LIDAR ODOMETRY
3.1 ROS-based ORB SLAM Odometry
Oriented FAST (Rosten and Drummond, 2006) and
Rotated BRIEF (Calonder et al., 2010) algorithm,
5
Area Scan Camera from Basler AG company,
www.baslerweb.com/en/products/cameras/
6
camera calibration ROS package is based on
OpenCV library: wiki.ros.org/camera calibration
which form ORB SLAM
7
method is a feature-based
real-time SLAM library for monocular, stereo and
RGB-D cameras (Mur-Artal et al., 2015). It is able
to build a sparse 3D scene and to compute an on-
board camera trajectory, thereby recovering a vision-
based robot odometry. In cases of heterogeneous
environment, ORB-SLAM demonstrates robustness
to complex motion clutter, performing wide baseline
loop detection and real time automatic camera re-
localization. To process live monocular streams, a li-
brary with a ROS node is used.
The ORB-SLAM adapts main ideas of previous
SLAM works, such as Parallel Tracking and Map-
ping (PTAM, (Klein and Murray, 2007)) and Scale
Drift-Aware Large Scale Monocular SLAM (Strasdat
et al., 2010). Thus, it uses advanced approaches to lo-
calization, loop closing, bundle adjustment, keyframe
selection, feature matching, point triangulation, cam-
era localization for every frame, and relocalization
after tracking failure. Moreover, ORB-SLAM sur-
passes PTAM algorithm, providing camera tracking
with ORB-features extraction (Rublee et al., 2011),
scale-aware loop closing, co-visibility information for
large scale operation, occlusion handling, and invari-
ance to viewpoint at relocalization (Mur-Artal et al.,
2015). ORB-SLAM key properties include:
the same features for tracking, mapping, re-
localization and loop closing;
real time loop closing, which is based on the opti-
mization of a pose graph;
invariant relocalization of real time camera to
viewpoint and illumination.
ORB-SLAM is a real-time SLAM library in
ROS, which provides both necessary calculations and
graphical user interface (GUI) for visualization of a
camera trajectory, a sparse 3D reconstruction, and
real-time features on video frames. To launch ORB-
SLAM algorithm in ROS, the following operations
should be executed:
building a node for Monocular SLAM;
running Monocular Node:
rosrun ORB SLAM2 Mono path to vocabulary
path to webcam settings file
7
ORB-SLAM2 package is available at
https://github.com/raulmur/ORB SLAM2
ICINCO 2017 - 14th International Conference on Informatics in Control, Automation and Robotics
318
Monocular SLAM node maintains three parallel
threads: Tracking (to help in a camera localization),
Local Mapping (to build a new map) and Loop Clos-
ing (to obtain a closed-loop trajectory).
3.2 ROS-based LSD-SLAM Odometry
Large-Scale Direct Monocular SLAM
8
(LSD-SLAM)
creates a real-time global, semi-dense map in a fully
direct mode without using keypoints, corners or any
other local features (in opposite to feature-based
methods like ORB-SLAM). Direct featureless track-
ing is performed by image-to-image alignment us-
ing a coarse-to-fine approach with a robust Huber
weights (Engel et al., 2014). Depth is estimated only
using pixels near image boundaries and semi-dense
maps (which are denser than maps of feature-based
methods) are created continuously. LSD-SLAM
forms both a camera trajectory and a semi-dense 3D
scene reconstruction, where a global mapping is built
by performing a pose graph optimization. The ad-
vantage of LSD-SLAM over feature-based methods
is in reconstruction of a more complete 3D scene with
textured smooth surfaces, which could be missed by
feature-based algorithms.
LSD-SLAM is a fully direct method, which is ca-
pable to build real-time large-scale semi-dense maps
using an onboard computer. LSD-SLAM is launched
in ROS with:
Starting the camera driver:
roslaunch webcam camera usb camera.launch
Launching the LSD-SLAM viewer:
rosrun lsd slam viewer viewer
Initiation of the main node:
rosrun lsd slam core live slam
/image:=/usb cam node/image raw
/camera info:=/usb cam node/camera info
Note that LSD-SLAM consists of two ROS pack-
ages: (1) lsd slam core that includes full SLAM sys-
tem, which provides live camera operation live slam
using ROS input/output, and (2) lsd slam viewer,
which is optionally used for 3D visualization.
3.3 ROS-based Lidar Odometry
To obtain ROS-based lidar odometry for ”Engineer”
robot motion within indoor workspace, we used the
open source hector slam package
9
, which contains of
modules related to SLAM execution in unstructured
8
LSD-SLAM package is available at
https://github.com/tum-vision/lsd slam
9
ROS package hector slam is available at
https://github.com/tu-darmstadt-ros-pkg/hector slam
Figure 4: The block-scheme of the ”Engineer” robot trajec-
tory evaluation with onboard sensors and ground truth.
environments (Kohlbrecher et al., 2013). Its algo-
rithm relies on fast lidar data scanning and matching
at full lidar refresh rate. To stabilize the laser scan-
ner data, hector slam combines with an attitude esti-
mation and an optional pitch and roll angles, calculat-
ing probable locations and environment maps even for
rugged ground terrain (Kohlbrecher et al., 2013). To
recover a trajectory of moving robot with lidar data,
the ROS module hector
tra jectory server
10
keeps
tracking of multiple coordinate frames over time.
3.4 Indoor Tests with Crawler-type
Robot
Our goals in these indoor tests with the crawler robot
are: (1) to calculate visual odometry from the robot
motion within the workspace by using two ROS-
based V-SLAM packages: ORB and LSD-SLAM; (2)
to obtain onboard lidar odometry; (3) to verify the vi-
sual and lidar odometry with a trajectory calculated
by video processing of the external ground truth cam-
era. The block-scheme of the ”Engineer” robot path
evaluation with onboard sensors and ground truth is
shown in Fig. 4
At the initial stage of our experiments we put the
external ground truth camera above the workspace,
and calibrated both onboard and external cameras
with a chessboard at different locations. Our tests
were performed with a human-operated crawler-type
robot ”Engineer” followed a close-loop trajectory in
a small-size indoor workspace with office-style en-
vironment and partially glass walls (Fig. 5a). The
data was recorded with onboard sensors: 2D lidar
and high-resolution camera with a global shutter and a
10
ROS package hector tra jectory server is a part of
hector slam package, wiki.ros.org/hector trajectory server
Analysis of ROS-based Visual and Lidar Odometry for a Teleoperated Crawler-type Robot in Indoor Environment
319
(a) Test 1: complex robot motion.
(b) Test 2: forth-
and-back motion.
Figure 5: Lidar map for different robot trajectories (green
color) with ROS hector slam package in RViz viewer.
frame rate of 60 fps. Since robot’s onboard computer
can not work simultaneously with ROS packages of
lidar odometry and two visual SLAM, we launched
ROS-based hector slam package online and recorded
onboard and external cameras’ video in synchronous
mode. Then, we processed onboard video offline
with ORB and LSD-SLAM, comparing visual and li-
dar odometry with ground truth-based robot trajecto-
ries. The main drawbacks of the crawler robot mo-
tion are significant vibration and sharp turns that typi-
cally lead to poor visual SLAM results or fails of these
ROS packages. To minimize vibration effects on vi-
sual odometry, we provided a series of experiments,
moving robot forth-and-back at slow speed in teleop-
eration mode without turns to either side (Fig. 5b).
However, in spite of our precautions, strong vibra-
tion forced us to stabilize onboard video during post-
processing stage offline by OpenCV video stabiliza-
tion filter described in (Grundmann et al., 2011).
4 ANALYSIS OF VISUAL AND
LIDAR ODOMETRY
Lidar odometry. To process Hokuyo 2D Laser Scan-
ner data, we used ROS-based hector slam package,
which calculated 2D map of our indoor environment
and robot trajectory with the following visualization
in RViz
11
(Fig. 5). However, glass walls nearby the
workspace were transparent for lidar (Fig. 5a) that
can create a problem for autonomous navigation of
the robot in such type of indoor environment.
ORB-SLAM tests. Since ORB-SLAM is feature-
based method, its 3D point cloud is very sparse. How-
ever, ORB-SLAM performs map reconstruction over
selected keyframes with calculation of camera po-
sitions after every recall in all video dataset (see,
Fig. 6), building as well 2D robot motion trajectory.
LSD-SLAM tests. In our experiments with
crawler robot, LSD-SLAM has frequently failed in
conditions of camera vibrations and sharp turns, even
after video stabilization by the OpenCV filter.
11
RViz is 3D visualization tool for ROS, wiki.ros.org/rviz
Figure 6: ORB-SLAM map viewer with 3D point cloud
(left), and an image with extracted features (right).
Figure 7: The contrasting white label on the robot’s head
from the ground-truth camera.
Ground truth-based path evaluation. To mon-
itor the robot motion from the height of about 3m,
we used the external high resolution camera Basler
(see, Fig. 3), thus established ground truth. To clearly
identify the robot motion within the workspace, we
placed white label on the robot’s head. Thereby, from
a grayscale video of the ground truth camera we eas-
ily recognized the contrasting white label and robot
contour (see, Fig. 7), computing the robot geometri-
cal center and its corresponding trajectory.
Analysis of trajectories. Finally, we computed
and scaled visual and lidar-based trajectories for the
following comparative analysis. Typical trajecto-
ries are shown in Fig. 8, where green, red and blue
(dot) curves mean robot path evaluation calculated
by monocular ORB-SLAM, ground truth camera and
lidar data correspondingly. We used the root mean
square error (RMSE) as metrics of robot trajectory
evaluation accuracy. The robot path evaluated by ex-
ternal ground truth camera was used as a base path
to rescale all other trajectories in terms of ground
truth axes. Therefore, we developed a software to es-
timate a correspondence between every point of the
base path and the nearest points of another trajec-
tory by computing the square root of mean of squared
distances between these points. Thus, the maximum
RMSE reached 1.96 cm between the ground truth
and lidar-based trajectories, and 12.6 cm between the
ground truth and ORB-SLAM trajectories.
ICINCO 2017 - 14th International Conference on Informatics in Control, Automation and Robotics
320
Figure 8: The robot trajectories computed by monocular
ORB-SLAM (green curve), external ground-truth camera
(red curve), and lidar data (blue dot curve).
5 CONCLUSION AND FUTURE
WORK
In this paper we analyze and compare robot trajec-
tories acquired by onboard 2D lidar and monocular
camera, and evaluated by ROS-based visual odom-
etry, lidar odometry and the external ground truth
camera. We used two visual SLAM methods for the
robot path recovery: feature-based ORB-SLAM and
appearance-based LSD-SLAM, because they usually
demonstrate good results in tracking, mapping, and
camera localization. Our tests were performed with
a human-operated crawler-type robot ”Engineer” fol-
lowed a close-loop trajectory in a small-sized indoor
workspace with office-style environment and partially
glass walls. Since onboard computer of our robot can
not work simultaneously with ROS packages of lidar
odometry and two visual SLAM, we used ROS-based
hector slam package online and recorded onboard
and external cameras’ video in synchronous mode.
Then, we processed onboard video offline with ORB
and LSD-SLAM, comparing visual and lidar odome-
try with ground truth-based robot trajectory. The main
drawbacks of the crawler-type robot motion are sig-
nificant vibration and sharp turns that result in poor
results or even fails in ROS-based visual SLAM pack-
ages. To minimize vibration effects on visual odom-
etry, we moved robot forward and backward at slow
speed in teleoperation mode without sharp turns to ei-
ther side, and used OpenCV video stabilization fil-
ter offline as post-processing stage. However, in spite
of our precautions the vibrations were so strong that
LSD-SLAM odometry frequently failed and lost the
robot trajectory during its motion.
The comparative analysis of trajectories computed
by ORB-SLAM, lidar and external ground truth cam-
era data allowed to make the following conclusions:
(1) lidar odometry is close to the ground truth path
evaluation; (2) ORB-based visual odometry contin-
ues working in spite of strong camera vibration dur-
ing crawler motion, but its trajectory shows signifi-
cant deviations in comparison with the ground truth.
Our future plans deal with realization of other vi-
sual SLAM and odometry methods, providing tests
in more complex environment and improving experi-
mental technique for better accuracy estimation.
REFERENCES
Buyval, A., Afanasyev, I., and Magid, E. (2017). Compar-
ative analysis of ros-based monocular slam methods
for indoor navigation.
Calonder, M., Lepetit, V., Strecha, C., and Fua, P. (2010).
BRIEF: Binary Robust Independent Elementary Fea-
tures, pages 778–792. Springer Berlin Heidelberg,
Berlin, Heidelberg.
Engel, J., Sch
¨
ops, T., and Cremers, D. (2014). LSD-
SLAM: Large-Scale Direct Monocular SLAM, pages
834–849. Springer International Publishing, Cham.
Grundmann, M., Kwatra, V., and Essa, I. (2011). Auto-
directed video stabilization with robust l1 optimal
camera paths. In Proceedings of the 2011 IEEE Con-
ference on Computer Vision and Pattern Recognition,
CVPR ’11, pages 225–232, Washington, DC, USA.
IEEE Computer Society.
Klein, G. and Murray, D. (2007). Parallel tracking and map-
ping for small ar workspaces. In 2007 6th IEEE and
ACM International Symposium on Mixed and Aug-
mented Reality, pages 225–234.
Kohlbrecher, S., Meyer, J., Graber, T., Petersen, K., Klin-
gauf, U., and von Stryk, O. (2013). Hector open
source modules for autonomous mapping and naviga-
tion with rescue robots. In Robot Soccer World Cup,
pages 624–631. Springer.
Mur-Artal, R., Montiel, J. M. M., and Tard?s, J. D. (2015).
Orb-slam: A versatile and accurate monocular slam
system. IEEE Transactions on Robotics, 31(5):1147–
1163.
Rosten, E. and Drummond, T. (2006). Machine Learn-
ing for High-Speed Corner Detection, pages 430–443.
Springer Berlin Heidelberg, Berlin, Heidelberg.
Rublee, E., Rabaud, V., Konolige, K., and Bradski, G.
(2011). Orb: An efficient alternative to sift or surf. In
2011 International Conference on Computer Vision,
pages 2564–2571.
Sarvrood, Y., Hosseinyalamdary, S., and Gao, Y. (2016).
Visual-lidar odometry aided by reduced imu. ISPRS
International Journal of Geo-Information, 5(1):3.
Scaramuzza, D. and Fraundorfer, F. (2011). Visual odom-
etry [tutorial]. IEEE Robotics Automation Magazine,
18(4):80–92.
Strasdat, H., Montiel, J., and Davison, A. J. (2010). Scale
drift-aware large scale monocular slam. Robotics: Sci-
ence and Systems VI.
Zhang, J. and Singh, S. (2015). Visual-lidar odometry and
mapping: low-drift, robust, and fast. In 2015 IEEE
International Conference on Robotics and Automation
(ICRA), pages 2174–2181.
Analysis of ROS-based Visual and Lidar Odometry for a Teleoperated Crawler-type Robot in Indoor Environment
321