A dataset containing synchronized visual, inertial and GNSS raw measurements.

GVINS-Dataset

Author/Maintainer: CAO Shaozu (shaozu.cao AT gmail.com), LU Xiuyuan (xluaj AT connect.ust.hk)

This repository hosts dataset collected during the development of GVINS. The dataset contains GNSS raw measurement, visual and inertial data which are necessary for GNSS-Visual-Inertial fusion algorithm.

1. Sensor Suit

sensorsuit

1.1. VI-Sensor

The visual and inertial data are collected using a VI-Sensor. The VI-Sensor has two Aptina MT9V034 image sensors, which form a stereo camera together, and a Analog Devices ADIS 16448 IMU. The image and inertial data from the VI-Sensor are well synchronized by hardware design. A detailed spec sheet of this sensor can be found here. The camera and IMU parameters can be found in GVINS-Dataset/data/visensor_parameters/.

1.2. u-blox ZED-F9P Receiver

We use u-blox ZED-F9P to collect GNSS raw measurements and ground truth location. The ZED-F9P owns an internal RTK engine which is capable to provide receiver's location at an accuracy of 1cm in open area. To obtain the RTK solution, a real-time RTCM stream from a 3km away GNSS observation station is fed to the receiver. The GNSS antenna in our platform is a Tallysman’s TW3882.

2. Synchronization

The time system between the VI-Sensor and the GNSS receiver is synchronized via Pluse Per Second (PPS) signal. The synchronization process is illustrated in the figure below:

sync_diagram

  1. The GNSS receiver reports the time information of next PPS signal. In our system the reporting frequency is set to 1Hz.
  2. The PPS signal from the GNSS receiver is used to trigger the external interrupt of VI-Sensor. In our system the frequency of PPS is set to 0.2 Hz.
  3. When VI-Sensor is interrupted by the PPS signal, it reports its local time to the host computer.

In this way the host computer knows both the global and local timestamps of the PPS signal so these two time systems get aligned together.

3. Dataset Details

The dataset is released in the form of rosbag and currently there are two rosbags available:

name duration size link
sports_field 25min 20.5GB OneDrive
complex_environment 32min 26.1GB OneDrive

The data items within the rosbag are listed below:

topic type frequency description
/cam0/image_raw sensor_msgs/Image 20Hz right camera
/cam1/image_raw sensor_msgs/Image 20Hz left camera
/imu0 sensor_msgs/Imu 200Hz IMU
/external_trigger gvins/LocalSensorExternalTrigger - publish when VI-Sensor is trigger. definition
/ublox_driver/receiver_lla sensor_msgs/NavSatFix 10Hz Receiver's GNSS solution (brief).
/ublox_driver/receiver_pvt gnss_comm/GnssPVTSolnMsg 10Hz Receiver's GNSS solution (verbose). definition
/ublox_driver/range_meas gnss_comm/GnssMeasMsg 10Hz GNSS raw measurement. definition
/ublox_driver/ephem gnss_comm/GnssEphemMsg - The broadcast ephemeris of GPS, Galileo and BeiDou. definition
/ublox_driver/glo_ephem gnss_comm/GnssGloEphemMsg - The broadcast ephemeris of GLONASS. definition
/ublox_driver/iono_params gnss_comm/StampedFloat64Array - The broadcast ionospheric parameters. definition
/ublox_driver/time_pulse_info gnss_comm/GnssTimePulseInfoMsg 1Hz The time information of next PPS signal. definition.

4. Toolkit

The toolkit provided in this package requires gnss_comm library.

4.1. Convert GNSS raw measurement to RINEX File

Many GNSS softwares like RTKLIB accept RINEX file as the input. To convert the GNSS raw measurements in the rosbag to the corresponding RINEX file, firstly clone this repo to your catkin workspace and set INPUT_BAG_FILEPATH and OUTPUT_RINEX_FILEPATH in toolkit/src/bag2rinex.cpp. Then build and run the toolkit with:

cd ~/catkin_ws/
catkin_make
source devel/setup.bash
rosrun gvins_dataset_toolkit bag2rinex

The observation RINEX file should be generated after a while. The corresponding GNSS ephemeris RINEX file can be found in GVINS-Dataset/data/ephemeris_rinex/.

4.2 Save RTK solution to csv file

To extract the RTK solution and status to a local csv file, firstly set INPUT_BAG_FILEPATH and OUTPUT_RTK_FILEPATH in toolkit/src/bag2rtk_solution.cpp. Then build and run the toolkit with:

cd ~/catkin_ws/
catkin_make
source devel/setup.bash
rosrun gvins_dataset_toolkit bag2rtk_solution

Each record in the generated csv file is in the form of:

gnss_ts_ns, ecef_px, ecef_py, ecef_pz, enu_vx, enu_vy, enu_vz, fix_type, valid_fix, diff_soln, carr_soln

, with each item described in the following:

name description
gnss_ts_ns GNSS time of the navigation epoch (expressed as Unix timestamp in ns)
ecef_p* The x, y, z component of the position in ECEF frame
enu_v* The x, y, z component of the velocity in ENU frame
fix_type GNSS fix type (0=no fix, 1=dead reckoning only, 2=2D-fix, 3=3D-fix, 4=GNSS+dead reckoning combined, 5=time only fix)
valid_fix if fix valid (1=valid fix)
diff_soln if differential correction were applied (1=applied)
carr_soln carrier phase range solution status (0=no carrier phase, 1=float, 2=fix)

5. License

The dataset is released under CC-BY-NC-SA-4.0 license.

Owner
Comments
  • How to set the frequency of PPS signal to 0.2 Hz by u-center?

    How to set the frequency of PPS signal to 0.2 Hz by u-center?

    You mentioned that in the README:

    1. The GNSS receiver reports the time information of next PPS signal. In our system the reporting frequency is set to 1Hz.
    2. The PPS signal from the GNSS receiver is used to trigger the external interrupt of VI-Sensor. In our system the frequency of PPS is set to 0.2 Hz. Did you set that by u-center as below? image But I don't know how to set the frequency of PPS signal to 0.2 Hz. And how to set the reporting frequency to 1Hz?
  • Question: testing VINS-Fusion with GVINS-Dataset

    Question: testing VINS-Fusion with GVINS-Dataset

    Thank you very much for sharing both GVINS and this dataset.

    Evaluating VINS-Fusion as visual-inertial (1 camera + 1 IMU) and global optimization with GNSS processed with RTKLIB, for Sports Field bag, estimations beyond 600 meters start to oscillate severely, as if the transformation WGPS_T_WVIO returned suddenly to identity matrix and then it is inmediatly corrected.

    imagen

    I suspect this is due to not limiting the size of the optimization problem in the global optimization node, as the version I am using takes into account every available result from VIO and GNSS (i.e. optimize() in globalOpt.cpp includes the whole localPoseMap). I have checked this here https://github.com/HKUST-Aerial-Robotics/VINS-Fusion/blob/master/global_fusion/src/globalOpt.cpp.

    imagen

    The time spent in global optimization increases over time, leading to vins_node's death after the bag has been played for 18 minutes 20 secs.: feeding the global optimization node with the standalone version of VINS-Mono succeeds estimating the whole trayectory, yet the huge oscillations remain (figure above shows the global optimization time using VINS-Mono as VIO).

    I am not completely sure I have not modified anything sensitive in the VINS-Fusion code, is this issue usual? I believe the problem resides in the global optimization not being limited.

    Thank you for your time.

  • Convert error

    Convert error

    Here is my modification:

    #define INPUT_BAG_FILEPATH "/home/XXXX/GVINS/sports_field/sports_field.bag" #define OUTPUT_RINEX_FILEPATH "/home/XXXX/GVINS/sports_field/"

    and it reports error:

    rosrun gvins_dataset_toolkit bag2rinex 段错误 (核心已转储)

  • error opening .bag file

    error opening .bag file

    I tried to use the gvins-dataset toolbox to convert GNSS raw data to RINEX file format, but there was no prompt Bag file failed to open. I don't know why? Similarly, saving RTK solution as CSV file also failed. It is worth noting that my file uses the data source provided in gvins image 这是我的输入信息 image

  • Camera calibration dataset / pinhole camera model

    Camera calibration dataset / pinhole camera model

    @shaozu thank you for making these datasets available to the public. We would like to run code on your dataset that supports only the pinhole camera model, not the Mei model. Do you think you could provide a calibration dataset such that we can run kalibr and use the model that we support? Or maybe you have calibrated a pinhole camera model yourself already or it would be very easy for you to do?

  • alpha and eta values for the MEI model

    alpha and eta values for the MEI model

    Hi all, I'm not particularly familiar with the MEI camera model, so I had a look at the paper first.

    It seems the matrix K depends on two parameters that are not provided by the yaml: alpha (required to get the skew) and eta, which depends on the parametric curve used.

    What assumptions have been made for alpha and eta? Can in first approximation assume alpha = 0 and eta = -1?

    Thanks, Marco.

Basic definitions and utility functions for GNSS raw measurement processing

gnss_comm Authors/Maintainers: CAO Shaozu (shaozu.cao AT gmail.com) The gnss_comm package contains basic definitions and utility functions for GNSS ra

Dec 21, 2022
RRxIO - Robust Radar Visual/Thermal Inertial Odometry: Robust and accurate state estimation even in challenging visual conditions.
RRxIO - Robust Radar Visual/Thermal Inertial Odometry: Robust and accurate state estimation even in challenging visual conditions.

RRxIO - Robust Radar Visual/Thermal Inertial Odometry RRxIO offers robust and accurate state estimation even in challenging visual conditions. RRxIO c

Dec 20, 2022
ROS GNSS/INS driver for Inertial Labs positioning systems for the CARMA Platform
ROS GNSS/INS driver for Inertial Labs positioning systems for the CARMA Platform

CARMA Inertial Labs GNSS/INS Driver This is a fork of the Inertial Labs ROS package that is used for connecting to Inertial Labs GNSS/INS, IMU-P, AHRS

Dec 26, 2021
LVI-SAM: Tightly-coupled Lidar-Visual-Inertial Odometry via Smoothing and Mapping
LVI-SAM: Tightly-coupled Lidar-Visual-Inertial Odometry via Smoothing and Mapping

LVI-SAM This repository contains code for a lidar-visual-inertial odometry and mapping system, which combines the advantages of LIO-SAM and Vins-Mono

Jan 8, 2023
A Visual Studio extension containing a collection of tools to help contributing code to the Chromium project.

VsChromium VsChromium is a Visual Studio Extension containing a collection of tools useful for editing, navigating and debugging code. VsChromium was

Dec 30, 2022
VID-Fusion: Robust Visual-Inertial-Dynamics Odometry for Accurate External Force Estimation
VID-Fusion: Robust Visual-Inertial-Dynamics Odometry for Accurate External Force Estimation

VID-Fusion VID-Fusion: Robust Visual-Inertial-Dynamics Odometry for Accurate External Force Estimation Authors: Ziming Ding , Tiankai Yang, Kunyi Zhan

Nov 18, 2022
Continuous-Time Spline Visual-Inertial Odometry

Continuous-Time Spline Visual-Inertial Odometry Related Publications Direct Sparse Odometry, J. Engel, V. Koltun, D. Cremers, In IEEE Transactions on

Dec 7, 2022
Visual-inertial-wheel fusion odometry, better performance in scenes with drastic changes in light
Visual-inertial-wheel fusion odometry, better performance in scenes with drastic changes in light

VIW-Fusion An visual-inertial-wheel fusion odometry VIW-Fusion is an optimization-based viusla-inertial-wheel fusion odometry, which is developed as a

Dec 30, 2022
A run-time C++ library for working with units of measurement and conversions between them and with string representations of units and measurements

Units What's new Some of the CMake target names have changed in the latest release, please update builds appropriately Documentation A library that pr

Dec 14, 2022
This package provides localization in a pre-built map using ICP and odometry (or the IMU measurements).
This package provides localization in a pre-built map using ICP and odometry (or the IMU measurements).

Localization using ICP in a known map Overview This package localizes the lidar sensor in a given map using the ICP algorithm. It subscribes to lidar

Jan 3, 2023
📚🪛 Arduino library to calibrate and improve ADC measurements with the Raspberry Pi Pico.

Arduino-Pico-Analog-Correction Arduino library to calibrate and improve ADC measurements with the Raspberry Pi Pico. Can compensate ADC offsets, calcu

Jan 3, 2023
Visual Leak Detector for Visual C++ 2008-2015

Visual Leak Detector Introduction Visual C++ provides built-in memory leak detection, but its capabilities are minimal at best. This memory leak detec

Jan 8, 2023
this is very basic version for our dataset validation, only change the path, and align the frame of vio and Groundtruth
this is very basic version for our dataset validation, only change the path, and align the frame of vio and Groundtruth

VINS-Fusion for UrbanNavDataset Evaluation 1. Prerequisites please refer to VINS-Fusion Github 2. Build mkdir catkin/src cd catkin/src mkdir result cd

Dec 9, 2022
Unified Gaussian Preintegrated Measurements (UGPMs)

This repository provides the C++ implementation of the preintegration methods presented in our RSS'21 paper titled Continuous Integration over SO(3) for IMU Preintegration (with video here ). If you are using that code for any purpose, please cite the corresponding work as explained at the end of this page.

Nov 30, 2022
Helper C++ classes to quickly preintegrate IMU measurements between SLAM keyframes

mola-imu-preintegration Integrator of IMU angular velocity readings. This repository provides: IMUIntegrator and RotationIntegrator: C++ classes to in

Nov 21, 2022
The MLX90614 is an Infra Red thermometer for noncontact temperature measurements.
The MLX90614 is an Infra Red thermometer for noncontact temperature measurements.

The MLX90614 is an Infra Red thermometer for noncontact temperature measurements.

Dec 23, 2022
An Arduino library which allows you to communicate seamlessly with the full range of u-blox GNSS modules
An Arduino library which allows you to communicate seamlessly with the full range of u-blox GNSS modules

u-blox makes some incredible GNSS receivers covering everything from low-cost, highly configurable modules such as the SAM-M8Q all the way up to the surveyor grade ZED-F9P with precision of the diameter of a dime.

Dec 29, 2022
Multi-GNSS Precise Point Postioning with Ambiguity Resolution

This is demo for multi-GNSS precise point positioning with ambiguity resolution (PPP-AR), which is based on RTKLIB and RTKLIB_demo5. FEATURES ppp-ar w

Sep 30, 2022