Simple Tutorial

TL; DR

Note

If you use SocketViewer, please launch the server in the other terminal and access to it with the web browser in advance.

Running the following commands will give a feel for what stella_vslam can do. The later parts of this chapter explains what each of the commands do in more detail.

# at the build directory of stella_vslam ...
$ pwd
~/lib/stella_vslam_examples/build/
$ ls
run_video_slam   ...

# download an ORB vocabulary from GitHub
curl -sL "https://github.com/stella-cv/FBoW_orb_vocab/raw/main/orb_vocab.fbow" -o orb_vocab.fbow

# download a sample dataset from Google Drive
FILE_ID="1d8kADKWBptEqTF7jEVhKatBEdN7g0ikY"
curl -sc /tmp/cookie "https://drive.google.com/uc?export=download&id=${FILE_ID}" > /dev/null
CODE="$(awk '/_warning_/ {print $NF}' /tmp/cookie)"
curl -sLb /tmp/cookie "https://drive.google.com/uc?export=download&confirm=${CODE}&id=${FILE_ID}" -o aist_living_lab_1.zip
unzip aist_living_lab_1.zip

# download a sample dataset from Google Drive
FILE_ID="1TVf2D2QvMZPHsFoTb7HNxbXclPoFMGLX"
curl -sc /tmp/cookie "https://drive.google.com/uc?export=download&id=${FILE_ID}" > /dev/null
CODE="$(awk '/_warning_/ {print $NF}' /tmp/cookie)"
curl -sLb /tmp/cookie "https://drive.google.com/uc?export=download&confirm=${CODE}&id=${FILE_ID}" -o aist_living_lab_2.zip
unzip aist_living_lab_2.zip

# run tracking and mapping
./run_video_slam -v ./orb_vocab.fbow -m ./aist_living_lab_1/video.mp4 -c ~/lib/stella_vslam/example/aist/equirectangular.yaml --frame-skip 3 --no-sleep --map-db-out map.msg
# click the [Terminate] button to close the viewer
# you can find map.msg in the current directory

# run localization
./run_video_slam --disable-mapping -v ./orb_vocab.fbow -m ./aist_living_lab_2/video.mp4 -c ~/lib/stella_vslam/example/aist/equirectangular.yaml --frame-skip 3 --no-sleep --map-db-in map.msg
# run localization with temporal mapping based odometry. loaded keyframes are prioritized for localization/localBA.
./run_video_slam --temporal-mapping -v ./orb_vocab.fbow -m ./aist_living_lab_2/video.mp4 -c ~/lib/stella_vslam/example/aist/equirectangular.yaml --frame-skip 3 --no-sleep --map-db-in map.msg

Sample Datasets

You can use stella_vslam with various video datasets. If you want to run stella_vslam with standard benchmarking detasets, please see this section.

Start by downloading some datasets you like.

Equirectangular Datasets

name

camera model

length

Google Drive

Baidu Wangpan

aist_entrance_hall_1

equirectangular (mono)

0:54

link

link (Pass: r7r4)

aist_entrance_hall_2

equirectangular (mono)

0:54

link

link (Pass: 4qma)

aist_factory_A_1

equirectangular (mono)

1:55

link

link (Pass: yy2u)

aist_factory_A_2

equirectangular (mono)

1:54

link

link (Pass: 9vey)

aist_factory_B_1

equirectangular (mono)

1:04

link

link (Pass: gpec)

aist_factory_B_2

equirectangular (mono)

1:34

link

link (Pass: ugrx)

aist_living_lab_1

equirectangular (mono)

2:16

link

link (Pass: 434m)

aist_living_lab_2

equirectangular (mono)

1:47

link

link (Pass: 549f)

aist_living_lab_3

equirectangular (mono)

2:06

link

link (Pass: cc2p)

aist_stairs_A_1

equirectangular (mono)

2:27

link

link (Pass: ncdr)

aist_stairs_B_1

equirectangular (mono)

2:55

link

link (Pass: xr5t)

aist_store_1

equirectangular (mono)

1:12

link

link (Pass: 47vq)

aist_store_2

equirectangular (mono)

1:44

link

link (Pass: xt8u)

aist_store_3

equirectangular (mono)

1:18

link

link (Pass: kghc)

ALL

equirectangular (mono)

link

link (Pass: vsv7)

Fisheye Datasets

name

camera model

length

Google Drive

Baidu Wangpan

aist_entrance_hall_1

fisheye (mono)

1:05

link

link (Pass: u86e)

aist_entrance_hall_2

fisheye (mono)

1:06

link

link (Pass: 9iyc)

aist_entrance_hall_3

fisheye (mono)

1:23

link

link (Pass: qaqc)

aist_entrance_hall_4

fisheye (mono)

1:27

link

link (Pass: em43)

aist_living_lab_1

fisheye (mono)

1:20

link

link (Pass: wcw4)

aist_living_lab_2

fisheye (mono)

2:26

link

link (Pass: dxns)

aist_living_lab_3

fisheye (mono)

3:43

link

link (Pass: 7n4q)

nu_eng2_corridor_1

fisheye (mono)

2:56

link

link (Pass: 71ws)

nu_eng2_corridor_2

fisheye (mono)

2:45

link

link (Pass: yrtj)

nu_eng2_corridor_3

fisheye (mono)

2:04

link

link (Pass: btpj)

ALL

fisheye (mono)

link

link (Pass: gumj)

After downloading and uncompressing a zip file, you will find a video file and a config file (old format) under the uncompressed directory.

$ ls dataset_name_X/
config.yaml  video.mp4

You can put the dataset in any directory where you have access to.

Additionally, please download a vocabulary file for FBoW from here.

For the rest of this chapter, we will use aist_living_lab_1 and aist_living_lab_2 datasets for our example.

Tracking and Mapping

Here we should know how to run SLAM and create a map database file with aist_living_lab_1 dataset. You can use ./run_video_slam to run SLAM with the video file.

# at the build directory of stella_vslam
$ ls
...
run_video_slam
...
$ ./run_video_slam -h
Allowed options:
  -h, --help               produce help message
  -v, --vocab arg          vocabulary file path
  -m, --video arg          video file path
  -c, --config arg         config file path
  --mask arg               mask image path
  --frame-skip arg (=1)    interval of frame skip
  --no-sleep               not wait for next frame in real time
  --auto-term              automatically terminate the viewer
  --log-level arg (=info)  log level

Execute the following command to run SLAM. The paths should be changed accordingly.

$ ./run_video_slam \
    -v /path/to/orb_vocab/orb_vocab.fbow \
    -c ~/lib/stella_vslam/example/aist/equirectangular.yaml \
    -m /path/to/aist_living_lab_1/video.mp4 \
    --frame-skip 3 \
    --map-db-out aist_living_lab_1_map.msg

The frame viewer and map viewer should launch as well. If the two viewers are not launching correctly, check if you launched the command with the appropriate paths.

_images/slam_frame_viewer_1.png _images/slam_map_viewer_1.png
[2019-05-20 17:52:41.677] [I] config file loaded: /path/to/stella_vslam/example/aist/equirectangular.yaml
  ___               __   _____ _      _   __  __
 / _ \ _ __  ___ _ _\ \ / / __| |    /_\ |  \/  |
| (_) | '_ \/ -_) ' \\ V /\__ \ |__ / _ \| |\/| |
 \___/| .__/\___|_||_|\_/ |___/____/_/ \_\_|  |_|
      |_|

Copyright (C) 2019,
National Institute of Advanced Industrial Science and Technology (AIST)
All rights reserved.
For the changes after forking,
Copyright (C) 2022, stella-cv, All rights reserved.

This is free software,
and you are welcome to redistribute it under certain conditions.
See the LICENSE file.

Camera Configuration:
- name: RICOH THETA S 960
- setup: Monocular
- fps: 30
- cols: 1920
- rows: 960
- color: RGB
- model: Equirectangular
ORB Configuration:
- number of keypoints: 2000
- scale factor: 1.2
- number of levels: 8
- initial fast threshold: 20
- minimum fast threshold: 7
- edge threshold: 19
- patch size: 31
- half patch size: 15
- mask rectangles:
  - [0, 1, 0, 0.1]
  - [0, 1, 0.84, 1]
  - [0, 0.2, 0.7, 1]
  - [0.8, 1, 0.7, 1]
Tracking Configuration:

[2019-05-20 17:52:41.678] [I] loading ORB vocabulary: /path/to/orb_vocab/orb_vocab.fbow
[2019-05-20 17:52:42.037] [I] startup SLAM system
[2019-05-20 17:52:42.038] [I] start local mapper
[2019-05-20 17:52:42.038] [I] start loop closer
[2019-05-20 17:52:42.395] [I] initialization succeeded with E
[2019-05-20 17:52:42.424] [I] new map created with 191 points: frame 0 - frame 2
[2019-05-20 17:53:39.092] [I] detect loop: keyframe 36 - keyframe 139
[2019-05-20 17:53:39.094] [I] pause local mapper
[2019-05-20 17:53:39.303] [I] resume local mapper
[2019-05-20 17:53:39.303] [I] start loop bundle adjustment
[2019-05-20 17:53:40.186] [I] finish loop bundle adjustment
[2019-05-20 17:53:40.186] [I] updating map with pose propagation
[2019-05-20 17:53:40.194] [I] pause local mapper
[2019-05-20 17:53:40.199] [I] resume local mapper
[2019-05-20 17:53:40.199] [I] updated map
[2019-05-20 17:55:36.218] [I] shutdown SLAM system
[2019-05-20 17:55:36.218] [I] encoding 1 camera(s) to store
[2019-05-20 17:55:36.218] [I] encoding 301 keyframes to store
[2019-05-20 17:55:37.906] [I] encoding 19900 landmarks to store
[2019-05-20 17:55:38.819] [I] save the MessagePack file of database to aist_living_lab_1_map.msg
median tracking time: 0.045391[s]
mean tracking time: 0.0472221[s]
[2019-05-20 17:55:40.087] [I] clear BoW database
[2019-05-20 17:55:40.284] [I] clear map database

Please click the Terminate button to close the viewer.

After terminating, you will find a map database file aist_living_lab_1_map.msg.

$ ls
...
aist_living_lab_1_map.msg
...

The format of map database files is MessagePack, so you can reuse created maps for any third-party applications other than stella_vslam.

Localization

In this section, we will localize the frames in aist_living_lab_2 dataset using the created map file aist_living_lab_1_map.msg. You can use ./run_video_slam with --map-db-in aist_living_lab_1_map.msg --disable-mapping to run localization. Execute the following command to start localization. The paths should be changed accordingly.

$ ./run_video_slam --disable-mapping \
    -v /path/to/orb_vocab/orb_vocab.fbow \
    -c ~/lib/stella_vslam/example/aist/equirectangular.yaml \
    -m /path/to/aist_living_lab_2/video.mp4 \
    --frame-skip 3 \
    --map-db-in aist_living_lab_1_map.msg

The frame viewer and map viewer should launch as well. If the two viewers are not launching correctly, check if you launched the command with the appropriate paths.

You can see if the current frame is being localized, based on the prebuild map.

_images/localize_frame_viewer_1.png
[2019-05-20 17:58:54.728] [I] config file loaded: /path/to/stella_vslam/example/aist/equirectangular.yaml
  ___               __   _____ _      _   __  __
 / _ \ _ __  ___ _ _\ \ / / __| |    /_\ |  \/  |
| (_) | '_ \/ -_) ' \\ V /\__ \ |__ / _ \| |\/| |
 \___/| .__/\___|_||_|\_/ |___/____/_/ \_\_|  |_|
      |_|

Copyright (C) 2019,
National Institute of Advanced Industrial Science and Technology (AIST)
All rights reserved.
For the changes after forking,
Copyright (C) 2022, stella-cv, All rights reserved.

This is free software,
and you are welcome to redistribute it under certain conditions.
See the LICENSE file.

Camera Configuration:
- name: RICOH THETA S 960
- setup: Monocular
- fps: 30
- cols: 1920
- rows: 960
- color: RGB
- model: Equirectangular
ORB Configuration:
- number of keypoints: 2000
- scale factor: 1.2
- number of levels: 8
- initial fast threshold: 20
- minimum fast threshold: 7
- edge threshold: 19
- patch size: 31
- half patch size: 15
- mask rectangles:
  - [0, 1, 0, 0.1]
  - [0, 1, 0.84, 1]
  - [0, 0.2, 0.7, 1]
  - [0.8, 1, 0.7, 1]
Tracking Configuration:

[2019-05-20 17:58:54.729] [I] loading ORB vocabulary: /path/to/orb_vocab/orb_vocab.fbow
[2019-05-20 17:58:55.083] [I] clear map database
[2019-05-20 17:58:55.083] [I] clear BoW database
[2019-05-20 17:58:55.083] [I] load the MessagePack file of database from aist_living_lab_1_map.msg
[2019-05-20 17:58:57.832] [I] decoding 1 camera(s) to load
[2019-05-20 17:58:57.832] [I] load the tracking camera "RICOH THETA S 960" from JSON
[2019-05-20 17:58:58.204] [I] decoding 301 keyframes to load
[2019-05-20 17:59:02.013] [I] decoding 19900 landmarks to load
[2019-05-20 17:59:02.036] [I] registering essential graph
[2019-05-20 17:59:02.564] [I] registering keyframe-landmark association
[2019-05-20 17:59:03.161] [I] updating covisibility graph
[2019-05-20 17:59:03.341] [I] updating landmark geometry
[2019-05-20 17:59:04.189] [I] startup SLAM system
[2019-05-20 17:59:04.190] [I] start local mapper
[2019-05-20 17:59:04.191] [I] start loop closer
[2019-05-20 17:59:04.195] [I] pause local mapper
[2019-05-20 17:59:04.424] [I] relocalization succeeded
[2019-05-20 18:01:12.387] [I] shutdown SLAM system
median tracking time: 0.0370831[s]
mean tracking time: 0.0384683[s]
[2019-05-20 18:01:12.390] [I] clear BoW database
[2019-05-20 18:01:12.574] [I] clear map database

If you set the --mapping option, the mapping module is enabled to extend the prebuild map.