Skip to content

Running ROVIOLI in VIO mode

Marius Fehr edited this page Nov 30, 2017 · 6 revisions

In this tutorial, we use ROVIOLI to build a map in the visual-inertial odometry (VIO) mode, i.e., without using any localization. Two modes exists for running ROVIOLI in VIO mode:

Requirements

To run a ROVIOLI, the following calibration files are required:

See Sensor Calibration Format for more information on these files.

In addition, a bag file containing the dataset (see Sample Datasets) or a live source needs to be available.

Building a map from a rosbag

For this tutorial, we build a map from one of the Euroc datasets. Go to the Euroc dataset website and download the bag file for Machine Hall 01.

Use the following script:

#!/usr/bin/env bash
LOCALIZATION_MAP_OUTPUT=$1
ROSBAG=$2
NCAMERA_CALIBRATION="$ROVIO_CONFIG_DIR/ncamera-euroc.yaml"
IMU_PARAMETERS_MAPLAB="$ROVIO_CONFIG_DIR/imu-adis16488.yaml"
IMU_PARAMETERS_ROVIO="$ROVIO_CONFIG_DIR/imu-sigmas-rovio.yaml"
REST=$@

rosrun rovioli rovioli \
  --alsologtostderr=1 \
  --v=2 \
  --ncamera_calibration=$NCAMERA_CALIBRATION  \
  --imu_parameters_maplab=$IMU_PARAMETERS_MAPLAB \
  --imu_parameters_rovio=$IMU_PARAMETERS_ROVIO \
  --datasource_type="rosbag" \
  --save_map_folder="$LOCALIZATION_MAP_OUTPUT" \
  --optimize_map_to_localization_map=false \
  --map_builder_save_image_as_resources=false \
  --datasource_rosbag=$ROSBAG $REST

Note:

# Use this flag to remove (or change) the suffix (default: image_raw) from the camera topic.
--vio_camera_topic_suffix=""

Now, start a roscore and run the dataset:

# Make sure that your maplab workspace is sourced!
source ~/maplab_ws/devel/setup.bash
roscore&
rosrun rovioli tutorial_euroc save_folder MH_01_easy.bag

where save_folder is the name of the folder where the generated VI map will be saved.

After ROVIOLI is finished and the map is saved, save_folder should look like this:

$ tree save_folder
save_folder
├── metadata
├── resource_info
├── resources
└── vi_map
    ├── edges
    ├── landmark_index
    ├── missions
    ├── other_fields
    ├── vertices0
    ├── vertices1
    ├── ...

Building a map from a rostopic

Use the following script:

#!/usr/bin/env bash
LOCALIZATION_MAP_OUTPUT=$1
NCAMERA_CALIBRATION="$ROVIO_CONFIG_DIR/ncamera-euroc.yaml"
IMU_PARAMETERS_MAPLAB="$ROVIO_CONFIG_DIR/imu-adis16488.yaml"
IMU_PARAMETERS_ROVIO="$ROVIO_CONFIG_DIR/imu-sigmas-rovio.yaml"
REST=$@

rosrun rovioli rovioli \
  --alsologtostderr=1 \
  --v=2 \
  --ncamera_calibration=$NCAMERA_CALIBRATION  \
  --imu_parameters_maplab=$IMU_PARAMETERS_MAPLAB \
  --imu_parameters_rovio=$IMU_PARAMETERS_ROVIO \
  --datasource_type="rostopic" \
  --save_map_folder="$LOCALIZATION_MAP_OUTPUT" \
  --map_builder_save_image_as_resources=false \
  --optimize_map_to_localization_map=false $REST

Note:

# Use this flag to remove (or change) the suffix (default: image_raw) from the camera topic.
--vio_camera_topic_suffix=""

Now, using a Euroc dataset as a live source, call:

# Make sure that your maplab workspace is sourced!
source ~/maplab_ws/devel/setup.bash
roscore&
rosrun rovioli tutorial_euroc_live save_folder

Then, in a separate terminal, start your data source:

rosbag play MH_01_easy.bag  # or start your sensor node.

Visualization during ROVIOLI

The following rostopics are published during ROVIOLI:

  • /maplab_rovio/T_G_I
  • /maplab_rovio/T_G_M Identity in the case of no localization.
  • /maplab_rovio/T_M_I
  • /maplab_rovio/bias_acc
  • /maplab_rovio/bias_gyro
  • /maplab_rovio/velocity_I

The following visualizations are present in RViz:

  • /maplab_rovio/T_G_I: Marker visualization of the current pose.
  • /maplab_rovio/T_G_M: Marker of the transformation from global to mission frame (this is identity in the case of no localization).
  • vi_map_baseframe: Basefrom of the generated VI map.
  • vi_map_edges/viwls: Edges from the generated VI map. An edge links two vertices.
  • vi_map_vertices: Vertex positions of the generated VI map.
Clone this wiki locally