Optimization-Based GNSS/INS Integrated Navigation System

Overview

OB_GINS

Optimization-Based GNSS/INS Integrated Navigation System

OB_GINS

We open-source OB_GINS, an optimization-based GNSS/INS integrated navigation system. The main features of OB_GINS are as follows:

  • A sliding-window optimizer for GNSS/INS integration;

  • Abstract IMU-preintegration implementation, including:

    • The normal IMU preintegration without the Earth's rotation consideration;
    • The normal IMU/ODO preintegration;
    • The refined IMU preintegration with the Earth's rotation consideration;
    • The refined IMU/ODO preintegration;
  • Implementation of the marginalization;

  • Tools for attitude parameterization and coordinate frames;

  • Tools for file IO;

Authors: Hailiang Tang, Xiaoji Niu, and Tisheng Zhang from the Integrated and Intelligent Navigation (i2Nav) Group, Wuhan University.

Related Paper:

  • Hailiang Tang, Xiaoji Niu, Tisheng Zhang, Jing Fan, and Jingnan Liu, “Exploring the Accuracy Potential of IMU Preintegration in Factor Graph Optimization,” Sep. 2021, Accessed: Sep. 08, 2021. [Online]. Available: https://arxiv.org/abs/2109.03010v1.
  • Le Chang, Xiaoji Niu, and Tianyi Liu, “GNSS/IMU/ODO/LiDAR-SLAM Integrated Navigation System Using IMU/ODO Pre-Integration,” Sensors, vol. 20, no. 17, p. 4702, Aug. 2020, doi: 10.3390/s20174702.
  • Junxiang Jiang, Xiaoji Niu, and Jingnan Liu, “Improved IMU Preintegration with Gravity Change and Earth Rotation for Optimization-Based GNSS/VINS,” Remote Sensing, vol. 12, no. 18, p. 3048, Sep. 2020, doi: 10.3390/rs12183048.

1 Prerequisites

1.1 System and compiler

We recommend you use Ubuntu 20.04 with the newest compiler (g++>=8.0 or clang>=7.0).

1.2 Ceres

Follow Ceres installation instructions.

1.3 abseil-cpp

Follow abseil-cpp installation instructions.

1.4 Eigen3

sudo apt install libeigen3-dev

1.5 yaml-cpp

sudo apt install libyaml-cpp-dev

2 Build OB_GINS and run demo

Once the prerequisites have been installed, you can clone this repository and build OB_GINS as follows:

# Clone the repository
git clone https://github.com/i2Nav-WHU/OB_GINS.git ~/

# Build OB_GINS
cd ~/OB_GINS
mkdir build && cd build
cmake ../ -DCAMKE_BUILD_TYPE=Release
make -j8

# Run demo dataset
cd ~/OB_GINS
./bin/ob_gins ./dataset/ob_gins.yaml

# Wait until the program finish

3 Datasets

3.1 Demo dataset

We offer a demo dataset with configuration file, which are located at dataset directory.

3.2 awesome-gins-datasets

One can find our open-source datasets at awesome-gins-datasets.

3.3 Your own dataset

The data formats used in OB_GINS are the same as the formats defined at awesome-gins-datasets. You can follow the formats to prepare your own datasets, or you can modify the source code as you need.

4 Acknowledgements

We thanks VINS-Fusion for providing a excellent platform for SLAM learners.

5 License

The source code is released under GPLv3 license.

We are still working on improving the code reliability. For any technical issues, please contact Hailiang Tang ([email protected]) or open an issue at this repository.

For commercial usage, please contact Prof. Xiaoji Niu ([email protected]).

Comments
  • Question about dVel and dTheta sampling frequency

    Question about dVel and dTheta sampling frequency

    I have seen in many of your papers that icm20602 datasets are in 200hz. I would like to know the raw imu sampling freqency. is imu samples (eg 1000hz) are trapzoidql integrated to achieve dvel and dtheta. Or it is a simple devided by 200 to represent dtheta and devel?

    opened by iceberg1369 5
  • 这是之前一位帅哥提出的issues,但是已经关闭了,我对这个问题也是不太理解,直接复制这个问题吧,可否有大佬解答一下?

    这是之前一位帅哥提出的issues,但是已经关闭了,我对这个问题也是不太理解,直接复制这个问题吧,可否有大佬解答一下?

    请教关于文档中的noise, 与 vins之间的 noise单位上存在等价转换关系吗 , 对于系统有影响吗? ob_gins: arw: 0.24 # deg/sqrt(hr) vrw: 0.24 # m/s/sqrt(hr) gbstd: 50.0 # deg/hr abstd: 250.0 # mGal corrtime: 1.0 # hr vins: #imu parameters The more accurate parameters you provide, the better performance acc_n: 0.1 # accelerometer measurement noise standard deviation. gyr_n: 0.01 # gyroscope measurement noise standard deviation. acc_w: 0.001 # accelerometer bias random work noise standard deviation. gyr_w: 0.0001 # gyroscope bias random work noise standard deviation.

    opened by fengyikawhi 1
  • 无法编译通过,出现错误

    无法编译通过,出现错误

    In file included from /home/YOng/Downloads/OB_GINS-main/src/ob_gins.cc:32: /home/YOng/Downloads/OB_GINS-main/src/factors/pose_parameterization.h:30:44: error: invalid use of incomplete type ‘class ceres::LocalParameterization’ class PoseParameterization : public ceres::LocalParameterization { ^~~~~~~~~~~~~~~~~~~~~ In file included from /usr/local/include/ceres/ceres.h:64, from /home/YOng/Downloads/OB_GINS-main/src/factors/gnss_factor.h:27, from /home/YOng/Downloads/OB_GINS-main/src/ob_gins.cc:30: /usr/local/include/ceres/problem.h:56:7: note: forward declaration of ‘class ceres::LocalParameterization’ class LocalParameterization; ^~~~~~~~~~~~~~~~~~~~~ In file included from /home/YOng/Downloads/OB_GINS-main/src/ob_gins.cc:32: /home/YOng/Downloads/OB_GINS-main/src/factors/pose_parameterization.h:35:10: error: ‘bool PoseParameterization::Plus(const double*, const double*, double*) const’ marked ‘override’, but does not override bool Plus(const double x, const double delta, double x_plus_delta) const override { ^~~~ /home/YOng/Downloads/OB_GINS-main/src/factors/pose_parameterization.h:52:10: error: ‘bool PoseParameterization::ComputeJacobian(const double, double) const’ marked ‘override’, but does not override bool ComputeJacobian(const double x, double jacobian) const override { ^~~~~~~~~~~~~~~ /home/YOng/Downloads/OB_GINS-main/src/factors/pose_parameterization.h:60:9: error: ‘int PoseParameterization::GlobalSize() const’ marked ‘override’, but does not override int GlobalSize() const override { ^~~~~~~~~~ /home/YOng/Downloads/OB_GINS-main/src/factors/pose_parameterization.h:64:9: error: ‘int PoseParameterization::LocalSize() const’ marked ‘override’, but does not override int LocalSize() const override { ^~~~~~~~~ /home/YOng/Downloads/OB_GINS-main/src/ob_gins.cc: In function ‘int main(int, char)’: /home/YOng/Downloads/OB_GINS-main/src/ob_gins.cc:311:95: error: cannot convert ‘PoseParameterization’ to ‘ceres::LocalParameterization*’ in initialization ceres::LocalParameterization parameterization = new (PoseParameterization); ^ /home/YOng/Downloads/OB_GINS-main/src/ob_gins.cc:313:63: error: no matching function for call to ‘ceres::Problem::AddParameterBlock(double [7], int, ceres::LocalParameterization&)’ parameterization); ^ In file included from /usr/local/include/ceres/ceres.h:64, from /home/YOng/Downloads/OB_GINS-main/src/factors/gnss_factor.h:27, from /home/YOng/Downloads/OB_GINS-main/src/ob_gins.cc:30: /usr/local/include/ceres/problem.h:261:8: note: candidate: ‘void ceres::Problem::AddParameterBlock(double*, int)’ void AddParameterBlock(double* values, int size); ^~~~~~~~~~~~~~~~~ /usr/local/include/ceres/problem.h:261:8: note: candidate expects 2 arguments, 3 provided /usr/local/include/ceres/problem.h:274:8: note: candidate: ‘void ceres::Problem::AddParameterBlock(double*, int, ceres::Manifold*)’ void AddParameterBlock(double* values, int size, Manifold* manifold); ^~~~~~~~~~~~~~~~~ /usr/local/include/ceres/problem.h:274:8: note: no known conversion for argument 3 from ‘ceres::LocalParameterization*’ to ‘ceres::Manifold*’ make[2]: *** [CMakeFiles/ob_gins.dir/build.make:104:CMakeFiles/ob_gins.dir/src/ob_gins.cc.o] 错误 1 make[1]: *** [CMakeFiles/Makefile2:83:CMakeFiles/ob_gins.dir/all] 错误 2 make: *** [Makefile:91:all] 错误 2

    opened by ISOEhy 1
  • 请教关于文章中ekf好于图优化的问题

    请教关于文章中ekf好于图优化的问题

    非常高兴学习这篇代码, 以下有三个问题想请教武大朋友们

    1. 请教关于图优化在网站中理论上是非常有利的 http://www.i2nav.com/index/newListDetail_yw.do?newskind_id=f8990a24cf86440483d7821d9c2975c9&newsinfo_id=e8eee7a6c9314db5b69508f3b4539f33

    exploring the Accuracy Potential of IMU Preintegration in Factor Graph Optimization 关于这篇文章中的比较 以ekf与m2相比, 似乎单纯在gnss-imu融合中, 基于优化的方式没有太多优势?

    image

    关于2020这篇文章的差异 https://www.mdpi.com/2072-4292/12/18/3048 这篇似乎推导更以vins为基础去补偿地球自转,柯次力等, 不过结果与exploring the Accuracy Potential of IMU Preintegration in Factor Graph Optimization稍有不同, 请教是定义上有不同,需要做什么样的调整,如旋转顺序,imu定义方向不同等

    1. 请教关于文档中的noise, 与 vins之间的 noise单位上存在等价转换关系吗 , 对于系统有影响吗? ob_gins: arw: 0.24 # deg/sqrt(hr) vrw: 0.24 # m/s/sqrt(hr) gbstd: 50.0 # deg/hr abstd: 250.0 # mGal corrtime: 1.0 # hr

    vins: #imu parameters The more accurate parameters you provide, the better performance acc_n: 0.1 # accelerometer measurement noise standard deviation. gyr_n: 0.01 # gyroscope measurement noise standard deviation.
    acc_w: 0.001 # accelerometer bias random work noise standard deviation.
    gyr_w: 0.0001 # gyroscope bias random work noise standard deviation.

    opened by arenas7307979 1
  • [ERROR] : sorry, unimplemented: non-trivial designated initializers not supported

    [ERROR] : sorry, unimplemented: non-trivial designated initializers not supported

    hi, thank you for your sharing, I'm having some problems when compiling, and I think g++8 should be able to handle that, but if g++ is an older version, what should I do to correct this code for successful build this project image

    opened by arenas7307979 1
  • Can't finish build without 'findabsl.cmake'

    Can't finish build without 'findabsl.cmake'

    First I build following instruction, while undergoing cmake step, error occurs like : CMake Error at CMakeLists.txt:41 (find_package): By not providing "Findabsl.cmake" in CMAKE_MODULE_PATH this project has asked CMake to find a package configuration file provided by "absl", but CMake did not find one.

    Could not find a package configuration file provided by "absl" with any of the following names:

     abslConfig.cmake
     absl-config.cmake
    

    Add the installation prefix of "absl" to CMAKE_PREFIX_PATH or set

    And I run ccmake .. to modify the path of absl to '/home/gary/Source/abseil-cpp/build/' The ccmake .. dorp error as: include could not find load file:

     /home/gary/Source/abseil-cpp/build/abslTargets.cmake
    

    Call Stack (most recent call first): CMakeLists.txt:38 (find_package)

    opened by Gary2077 1
Owner
i2Nav-WHU
Integrated and Intelligent Navigation Group, Wuhan University
i2Nav-WHU
Source code for the data dependency part of Jan Kossmann's PhD thesis "Unsupervised Database Optimization: Efficient Index Selection & Data Dependency-driven Query Optimization"

Unsupervised Database Optimization: Data Dependency-Driven Query Optimization Source code for the experiments presented in Chapter 8 of Jan Kossmann's

Jan Koßmann 4 Apr 24, 2022
2D/3D Registration and system integration for image-based navigation of orthopedic robotic applications, inculding femoroplasty, osteonecrosis, etc.

Registration and System Integration Software for Orthopedic Surgical Robotic System This repository contains software programs for image-based registr

Cong Gao 15 Sep 3, 2022
Tightly coupled GNSS-Visual-Inertial system for locally smooth and globally consistent state estimation in complex environment.

GVINS GVINS: Tightly Coupled GNSS-Visual-Inertial Fusion for Smooth and Consistent State Estimation. paper link Authors: Shaozu CAO, Xiuyuan LU and Sh

HKUST Aerial Robotics Group 587 Dec 30, 2022
The Gecko SDK (GSDK) combines all Silicon Labs 32-bit IoT product software development kits (SDKs) based on Gecko Platform into a single, integrated SDK.

Silicon Labs Gecko SDK (GSDK) The Gecko SDK (GSDK) combines Silicon Labs wireless software development kits (SDKs) and Gecko Platform into a single, i

Silicon Labs 163 Dec 28, 2022
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.

SparkFun Electronics 134 Dec 29, 2022
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

HKUST Aerial Robotics Group 70 Dec 21, 2022
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 du

HKUST Aerial Robotics Group 134 Dec 21, 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

Chen Chao 9 Sep 30, 2022
An open source GNSS receiver

greta-oto An open source GNSS receiver This project is an open source project of a consumer level GNSS receiver. It has the capability to receive L1 b

null 26 Nov 20, 2022
GLSL optimizer based on Mesa's GLSL compiler. Used to be used in Unity for mobile shader optimization.

GLSL optimizer ⚠️ As of mid-2016, the project is unlikely to have any significant developments. At Unity we are moving to a different shader compilati

Aras Pranckevičius 1.6k Jan 3, 2023
A laser cut Dreamcast Pop'n Music controller and integrated memory card using the Raspberry Pi Pico's Programmable IO

Dreamcast Pop'n Music Controller Using Raspbery Pi Pico (RP2040) Intro This is a homebrew controller for playing the Pop'n Music games on the Sega Dre

null 42 Dec 29, 2022
C.impl is a small portable C interpreter integrated with a line text editor

C.impl C.impl is a small portable C interpreter integrated with a line text editor, originally developed for the ELLO 1A computer: http://ello.cc The

KnivD 22 Nov 21, 2022
An Open Source tripmaster for navigation rallies

Open Rally Computer An open source tripmaster for navigation rallies Description The Open Rally Computer (previously known as Baja Pro) is a complete

Matias Godoy 48 Dec 31, 2022
C library designed for the TI MSP432P401R microprocessor and the TI Educational Booster Pack, to easily play and control songs with the integrated Piezo Buzzer.

MusicLib C library designed for the TI MSP432P401R microprocessor and the TI Educational Booster Pack, to easily play and control songs with the integ

Matteo Merler 1 Nov 24, 2021
Small Robot, with LIDAR and DepthCamera. Using ROS for Maping and Navigation

?? RoboCop ?? Small Robot, with LIDAR and DepthCamera. Using ROS for Maping and Navigation Made by Clemente Donoso, ?? Chile ???? RoboCop Lateral Fron

Clemente Donoso Krauss 2 Jan 4, 2022
Local Navigation Planner for Legged Robots

ANYmal Rough Terrain Planner Sampling based path planning for ANYmal, based on 2.5D height maps. More detailed instructions still to come. The paper d

Robotic Systems Lab - Legged Robotics at ETH Zürich 36 Dec 15, 2022
Invariant-ekf - C++ library to implement invariant extended Kalman filtering for aided inertial navigation.

inekf This repository contains a C++ library that implements an invariant extended Kalman filter (InEKF) for 3D aided inertial navigation. This filter

Ross Hartley 273 Dec 24, 2022
Lee Thomason 299 Dec 10, 2022
Arduino library for basic aerial navigation functions used for processing Euler angles, direction cosine matrices, quaternions, frame conversions, and more.

navduino Arduino library for basic aerial navigation functions used for Euler angles Direction cosine matrices Quaternions Rodrigues Rotation Vectors

PB2 7 Oct 24, 2022