Git Product home page Git Product logo

engcang / vins-application Goto Github PK

View Code? Open in Web Editor NEW
476.0 8.0 86.0 87.93 MB

VINS-Fusion, VINS-Fisheye, OpenVINS, EnVIO, ROVIO, S-MSCKF, ORB-SLAM2, NVIDIA Elbrus application of different sets of cameras and imu on different board including desktop and Jetson boards

License: BSD 3-Clause "New" or "Revised" License

Objective-C 0.03% CMake 3.77% C++ 94.92% C 0.38% Python 0.90%
cuda nvidia slam vio visual-slam ros ros2

vins-application's Introduction

VINS-application

Mainly focused on Build process and explanation

■ ROS1 algorithms:

VINS-Fusion, VINS-Fusion-GPU, VINS-Fisheye, OpenVINS, EnVIO, ROVIO, S-MSCKF, ORB-SLAM2, DM-VIO

■ ROS2 algorithms:

NVIDIA Isaac Elbrus


This repository contains many branches! as following:

■ ROS1 algorithms:

■ ROS2 algorithms:



Result clips: here

● Tested on: Jetson Xavier NX, Jetson Xavier AGX, Jetson TX2, Intel i9-10900k, i7-6700k, i7-8700k, i5-9600k

VINS-Fusion for PX4 with Masking: here

  • frame changed from world to map


Index

0. Algorithms:

■ ROS1 Algorithms:

  • VINS-Fusion CPU version / GPU version
    • Mainly uses Ceres-solver, OpenCV and Eigen and performance of VINS is strongly proportional to CPU performance and some parameters
  • VINS-Fisheye: VINS-Fusion's extension with more camera_models and CUDA acceleration
    • only for OpenCV 3.4.1 and Jetson TX2 (I guess, I failed on i9-10900k + RTX3080)
  • ROVIO: Iterative EKF based VIO, direct method (using patch)
  • S-MSCKF: Stereo version of MSCKF VIO
  • ORB-SLAM2: Feature based VO, Local and Global bundle adjustment
  • OpenVINS: MSCKF based VINS
  • EnVIO: Iterated-EKF Ensemble VIO based on ROVIO
  • DM-VIO: Monocular VIO with delayed marginalization and pose graph bundle adjustment based on DSO

■ ROS2 Algorithms:

  • NVIDIA Isaac Elbrus: GPU-accelerated Stereo Visual SLAM
    • Ubuntu 20.04: CUDA 11.4, 11.5 (not 11.6), NVIDIA-graphic driver from 470.103.01
    • Jetpack: 4.6.1 on Jetson Xavier AGX, Jetson Xavier NX

1. Parameters

2. Prerequisites

Ceres solver and Eigen: Mandatory for VINS (build Eigen first)

CUDA: Necessary for GPU version

cuDNN: Necessary for GPU version

OpenCV with CUDA and cuDNN: Necessary for GPU version

● CV_Bridge with Built OpenCV: Necessary for GPU version, and general ROS usage

USB performance: Have to improve performance of sensors with USB

IMU-Camera Calibration: Synchronization, time offset, extrinsic parameter

IMU-Camera rotational extrinsic: Rotational extrinsic between IMU and Cam

3. Installation and Execution

■ ROS1 Algorithms:

■ ROS2 Algorithms:




1. Parameters

● VINS-Fusion:

[click to see]
  • Camera frame rate
    • lower - low time delay, poor performance
    • higher - high time delay, better performance
    • has to be set from camera launch file: 10~30hz
  • Max tracking Feature number max_cnt
    • 100~150, same correlation as camera frame rates
  • time offset between IMU and cameras estimated_td: 1, td : value from kalibr
  • GPU acceleration use_gpu: 1, use_gpu_acc_flow: 1 (for GPU version)
  • Threads enabling - multiple_thread: 1


2. Prerequisites

● Ceres solver and Eigen: Mandatory for VINS

[click to see]
$ wget -O eigen.zip https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.zip #check version
$ unzip eigen.zip
$ cd eigen-3.3.7
& mkdir build && cd build
$ cmake .. && sudo make install
$ git clone https://gitlab.com/libeigen/eigen.git
$ cd eigen 
$ mkdir build && cd build
$ cmake .. && sudo make install
$ sudo apt-get install -y cmake libgoogle-glog-dev libatlas-base-dev libsuitesparse-dev
$ wget http://ceres-solver.org/ceres-solver-1.14.0.tar.gz
$ tar zxf ceres-solver-1.14.0.tar.gz
$ mkdir ceres-bin
$ mkdir solver && cd ceres-bin
$ cmake ../ceres-solver-1.14.0 -DEXPORT_BUILD_DIR=ON -DCMAKE_INSTALL_PREFIX="../solver"  #good for build without being root privileged and at wanted directory
$ make -j8 # 8 : number of cores
$ make test
$ make install


● CUDA: Necessary for GPU version

[click to see]
  • Install CUDA and Graphic Driver:
    $ sudo apt install gcc make
    get the right version of CUDA(with graphic driver) .deb file at https://developer.nvidia.com/cuda-downloads
    follow the installation instructions there!
        # .run file can be used as nvidia graphic driver. But, .deb file is recommended to install tensorRT further.

        # if want to install only graphic driver, get graphic driver install script at https://www.nvidia.com/Download/index.aspx?lang=en-us
        # sudo ./NVIDIA_<graphic_driver_installer>.run --dkms
        # --dkms option is recommended when you also install NVIDIA driver, to register it along with kernel
        # otherwise, NVIDIA graphic driver will be gone after kernel upgrade via $ sudo apt upgrade
    $ sudo reboot

    $ gedit ~/.bashrc
    # type and save
    export PATH=<CUDA_PATH>/bin:$PATH #ex: /usr/local/cuda-11.1
    export LD_LIBRARY_PATH=<CUDA_PATH>/lib64:$LD_LIBRARY_PATH #ex : /usr/local/cuda-11.1
    $ . ~/.bashrc

    # check if installed well
    $ dpkg-query -W | grep cuda
  • check CUDA version using nvcc --version
# check installed cuda version
$ nvcc --version
# if nvcc --version does not print out CUDA,
$ gedit ~/.profile
# type below and save
export PATH=<CUDA_PATH>/bin:$PATH #ex: /usr/local/cuda-11.1
export LD_LIBRARY_PATH=<CUDA_PATH>/lib64:$LD_LIBRARY_PATH #ex : /usr/local/cuda-11.1
$ source ~/.profile

● Trouble shooting for NVIDIA driver or CUDA: please see /var/log/cuda-installer.log or /var/log/nvidia-install.log

  • Installation failed. See log at /var/log/cuda-installer.log for details => mostly because of X server is being used.
    • turn off X server and install.
# if you are using lightdm
$ sudo service lightdm stop

# or if you are using gdm3
$ sudo service gdm3

# then press Ctrl+Alt+F3 -> login with your ID/password
$ sudo sh cuda_<version>_linux.run
  • The kernel module failed to load. Secure boot is enabled on this system, so this is likely because it was not signed by a key that is trusted by the kernel....
    • turn off Secure Boot as below reference
    • If you got this case, you should turn off Secure Boot and then turn off X server (as above) both.

● cuDNN: strong library for Neural Network used with CUDA

[click to see]
$ sudo tar zxf cudnn.tgz
$ sudo cp extracted_cuda/include/* <CUDA_PATH>/include/   #ex /usr/local/cuda-11.1/include/
$ sudo cp -P extracted_cuda/lib64/* <CUDA_PATH>/lib64/   #ex /usr/local/cuda-11.1/lib64/
$ sudo chmod a+r <CUDA_PATH>/lib64/libcudnn*   #ex /usr/local/cuda-11.1/lib64/libcudnn*



● OpenCV with CUDA and cuDNN

■ Ubuntu 18.04 - this repo mainly targets ROS1 for Ubuntu 18.04

[Click to see]
  • Build OpenCV with CUDA - references: link 1, link 2
    • for Xavier do as below or sh file from jetsonhacks here
    • If want to use C API (e.g. Darknet YOLO) with OpenCV3, then:
      • Patch as here to use other version (3.4.1 is the best)
        • should comment the /usr/local/include/opencv2/highgui/highgui_c.h line 139 as here after install
  • -D OPENCV_GENERATE_PKGCONFIG=YES option is also needed for OpenCV 4.X
    • and copy the generated opencv4.pc file to /usr/local/lib/pkgconfig or /usr/lib/aarch64-linux-gnu/pkgconfig for jetson boards
$ sudo apt-get purge libopencv* python-opencv
$ sudo apt-get update
$ sudo apt-get install -y build-essential pkg-config
$ sudo apt-get install -y cmake libavcodec-dev libavformat-dev libavutil-dev \
    libglew-dev libgtk2.0-dev libgtk-3-dev libjpeg-dev libpng-dev libpostproc-dev \
    libswscale-dev libtbb-dev libtiff5-dev libv4l-dev libxvidcore-dev \
    libx264-dev qt5-default zlib1g-dev libgl1 libglvnd-dev pkg-config \
    libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev mesa-utils #libeigen3-dev # recommend to build from source : http://eigen.tuxfamily.org/index.php?title=Main_Page
$ sudo apt-get install python2.7-dev python3-dev python-numpy python3-numpy
$ mkdir <opencv_source_directory> && cd <opencv_source_directory>


# check version
$ wget -O opencv.zip https://github.com/opencv/opencv/archive/3.4.1.zip # check version
$ unzip opencv.zip
$ cd <opencv_source_directory>/opencv 

$ wget -O opencv_contrib.zip https://github.com/opencv/opencv_contrib/archive/3.4.1.zip # check version
$ unzip opencv_contrib.zip

$ mkdir build && cd build
    
# check your BIN version : http://arnon.dk/matching-sm-architectures-arch-and-gencode-for-various-nvidia-cards/
# 8.6 for RTX3080 7.2 for Xavier, 5.2 for GTX TITAN X, 6.1 for GTX TITAN X(pascal), 6.2 for TX2
# -D BUILD_opencv_cudacodec=OFF #for cuda10-opencv3.4
    
$ cmake -D CMAKE_BUILD_TYPE=RELEASE \
      -D CMAKE_C_COMPILER=gcc-6 \
      -D CMAKE_CXX_COMPILER=g++-6 \
      -D CMAKE_INSTALL_PREFIX=/usr/local \
      -D OPENCV_GENERATE_PKGCONFIG=YES \
      -D WITH_CUDA=ON \
      -D OPENCV_DNN_CUDA=ON \
      -D WITH_CUDNN=ON \
      -D CUDA_ARCH_BIN=8.6 \
      -D CUDA_ARCH_PTX=8.6 \
      -D ENABLE_FAST_MATH=ON \
      -D CUDA_FAST_MATH=ON \
      -D WITH_CUBLAS=ON \
      -D WITH_LIBV4L=ON \
      -D WITH_GSTREAMER=ON \
      -D WITH_GSTREAMER_0_10=OFF \
      -D WITH_CUFFT=ON \
      -D WITH_NVCUVID=ON \
      -D WITH_QT=ON \
      -D WITH_OPENGL=ON \
      -D WITH_IPP=OFF \
      -D WITH_V4L=ON \
      -D WITH_1394=OFF \
      -D WITH_GTK=ON \
      -D WITH_EIGEN=ON \
      -D WITH_FFMPEG=ON \
      -D WITH_TBB=ON \
      -D BUILD_opencv_cudacodec=OFF \
      -D CUDA_NVCC_FLAGS="--expt-relaxed-constexpr" \
      -D OPENCV_EXTRA_MODULES_PATH=../opencv_contrib-3.4.1/modules \
      ../
$ time make -j8 # 8 : numbers of core
$ sudo make install
$ sudo rm -r <opencv_source_directory> #optional for saving disk, but leave this folder to uninstall later, if you need.

● Trouble shooting for OpenCV build error:

  • Please include the appropriate gl headers before including cuda_gl_interop.h => reference 1, 2, 3
  • modules/cudacodec/src/precomp.hpp:60:37: fatal error: dynlink_nvcuvid.h: No such file or directory compilation terminated. --> for CUDA version 10
    • => reference here
    • cmake ... -D BUILD_opencv_cudacodec=OFF ...
  • CUDA_nppicom_LIBRARY not found
    • $ sudo apt-get install nvidia-cuda-toolkit
    • or Edit opencv/cmake/OpenCVDetectCUDA.cmake as follows:
        ...
        ...
        if(CUDA_FOUND)
            set(HAVE_CUDA 1)
            ocv_list_filterout(CUDA_nppi_LIBRARY "nppicom") #this line is added
            ocv_list_filterout(CUDA_npp_LIBRARY "nppicom") #this line is added
            if(WITH_CUFFT)
                set(HAVE_CUFFT 1)
            endif()
        ...
        ...

■ Ubuntu 20.04 - this repo mainly targets ROS2 for Ubuntu 20.04

[Click to see]
  • Build OpenCV with CUDA - references: link 1
  • -D PYTHON3_PACKAGES_PATH=/usr/local/lib/python3.8/dist-packages
    • This is needed to prevent No module name cv2 when import cv2 in Python3
## optional, I just leave default OpenCV from ROS2, since I can set proper PATHS for desired OpenCV versions
## If you cannot, just do below:
$ sudo apt-get purge libopencv*
## (But you will have to sudo apt install ros-foxy-desktop again, when you need other packages related to this)

$ sudo apt-get purge python-opencv python3-opencv
$ pip uninstall opencv-python
$ sudo apt-get update
$ sudo apt-get install -y build-essential pkg-config
$ sudo apt-get install -y cmake libavcodec-dev libavformat-dev libavutil-dev \
    libglew-dev libgtk2.0-dev libgtk-3-dev libjpeg-dev libpng-dev libpostproc-dev \
    libswscale-dev libtbb-dev libtiff5-dev libv4l-dev libxvidcore-dev \
    libx264-dev qt5-default zlib1g-dev libgl1 libglvnd-dev pkg-config \
    libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev mesa-utils #libeigen3-dev # recommend to build from source : http://eigen.tuxfamily.org/index.php?title=Main_Page
$ sudo apt-get install python3-dev python3-numpy
$ mkdir <opencv_source_directory> && cd <opencv_source_directory>


# check version
$ wget -O opencv.zip https://github.com/opencv/opencv/archive/4.5.5.zip # check version
$ unzip opencv.zip
$ cd <opencv_source_directory>/opencv 

$ wget -O opencv_contrib.zip https://github.com/opencv/opencv_contrib/archive/4.5.5.zip # check version
$ unzip opencv_contrib.zip

$ mkdir build && cd build
    
# check your CUDA_ARCH_BIN and CUDA_ARCH_PTX version : http://arnon.dk/matching-sm-architectures-arch-and-gencode-for-various-nvidia-cards/
# 8.6 for RTX3080 7.2 for Xavier, 5.2 for GTX TITAN X, 6.1 for GTX TITAN X(pascal), 6.2 for TX2
# -D BUILD_opencv_cudacodec=OFF #for cuda10-opencv3.4
    
$ cmake -D CMAKE_BUILD_TYPE=RELEASE \
      -D CMAKE_C_COMPILER=gcc-9 \
      -D CMAKE_CXX_COMPILER=g++-9 \
      -D CMAKE_INSTALL_PREFIX=/usr/local \
      -D OPENCV_GENERATE_PKGCONFIG=YES \
      -D PYTHON_EXECUTABLE=/usr/bin/python3.8 \
      -D PYTHON2_EXECUTABLE="" \
      -D BUILD_opencv_python3=ON \
      -D BUILD_opencv_python2=OFF \
      -D PYTHON3_PACKAGES_PATH=/usr/local/lib/python3.8/dist-packages \
      -D BUILD_NEW_PYTHON_SUPPORT=ON \
      -D OPENCV_SKIP_PYTHON_LOADER=ON \
      -D WITH_CUDA=ON \
      -D OPENCV_DNN_CUDA=ON \
      -D WITH_CUDNN=ON \
      -D CUDA_ARCH_BIN=8.6 \
      -D CUDA_ARCH_PTX=8.6 \
      -D ENABLE_FAST_MATH=ON \
      -D CUDA_FAST_MATH=ON \
      -D WITH_CUBLAS=ON \
      -D WITH_LIBV4L=ON \
      -D WITH_GSTREAMER=ON \
      -D WITH_GSTREAMER_0_10=OFF \
      -D WITH_CUFFT=ON \
      -D WITH_NVCUVID=ON \
      -D WITH_QT=ON \
      -D WITH_OPENGL=ON \
      -D WITH_IPP=OFF \
      -D WITH_V4L=ON \
      -D WITH_1394=OFF \
      -D WITH_GTK=ON \
      -D WITH_EIGEN=ON \
      -D WITH_FFMPEG=ON \
      -D WITH_TBB=ON \
      -D BUILD_opencv_cudacodec=OFF \
      -D CUDA_NVCC_FLAGS="--expt-relaxed-constexpr" \
      -D OPENCV_EXTRA_MODULES_PATH=../opencv_contrib-4.5.5/modules \
      ../
$ time make -j20 # 20 : numbers of core
$ sudo make install
$ sudo rm -r <opencv_source_directory> #optional for saving disk, but leave this folder to uninstall later, if you need.

● Trouble shooting for OpenCV build error:

  • No troubles found yet


● CV_Bridge with built OpenCV: Necessary for whom built OpenCV manually from above

■ ROS1-cv_bridge

[Click: CV_bridge with OpenCV 3.X version]
  • If OpenCV with CUDA were built manually, build cv_bridge manually also
$ cd ~/catkin_ws/src && git clone https://github.com/ros-perception/vision_opencv
# since ROS Noetic is added, we have to checkout to melodic tree
$ cd vision_opencv && git checkout origin/melodic
$ gedit vision_opencv/cv_bridge/CMakeLists.txt
  • Edit OpenCV PATHS in CMakeLists and include cmake file
#when error, try both lines
find_package(OpenCV 3 REQUIRED PATHS /usr/local/share/OpenCV NO_DEFAULT_PATH
#find_package(OpenCV 3 HINTS /usr/local/share/OpenCV NO_DEFAULT_PATH
  COMPONENTS
    opencv_core
    opencv_imgproc
    opencv_imgcodecs
  CONFIG
)
include(/usr/local/share/OpenCV/OpenCVConfig.cmake) #under catkin_python_setup()
$ cd .. && catkin build cv_bridge

[Click: CV_bridge with OpenCV 4.X version]
$ cd ~/catkin_ws/src && git clone https://github.com/ros-perception/vision_opencv
# since ROS Noetic is added, we have to checkout to melodic tree
$ cd vision_opencv && git checkout origin/melodic
$ gedit vision_opencv/cv_bridge/CMakeLists.txt
  • Add options and edit OpenCV PATHS in CMakeLists
# add right after project()
set(CMAKE_CXX_STANDARD 11) 

# edit find_package(OpenCV)
#find_package(OpenCV 4 REQUIRED PATHS /usr/local/share/opencv4 NO_DEFAULT_PATH
find_package(OpenCV 4 REQUIRED
  COMPONENTS
    opencv_core
    opencv_imgproc
    opencv_imgcodecs
  CONFIG
)
include(/usr/local/lib/cmake/opencv4/OpenCVConfig.cmake)
  • Edit cv_bridge/src/CMakeLists.txt
# line number 35, Edit 3 -> 4
if (OpenCV_VERSION_MAJOR VERSION_EQUAL 4)
  • Edit cv_bridge/src/module_opencv3.cpp
// line number 110
//    UMatData* allocate(int dims0, const int* sizes, int type, void* data, size_t* step, int flags, UMatUsageFlags usageFlags) const
    UMatData* allocate(int dims0, const int* sizes, int type, void* data, size_t* step, AccessFlag flags, UMatUsageFlags usageFlags) const

// line number 140
//    bool allocate(UMatData* u, int accessFlags, UMatUsageFlags usageFlags) const
    bool allocate(UMatData* u, AccessFlag accessFlags, UMatUsageFlags usageFlags) const
$ cd .. && catkin build cv_bridge

■ ROS2-cv_bridge

[Click: CV_bridge with OpenCV 4.X version]
  • If OpenCV with CUDA were built manually, build cv_bridge manually also
$ cd ~/colcon_ws/src && git clone https://github.com/ros-perception/vision_opencv
$ cd vision_opencv
$ git checkout origin/ros2

$ cd ~/colcon_ws
$ colcon build --symlink-install --packages-select cv_bridge image_geometry --allow-overriding cv_bridge image_geometry
$ source install/setup.bash


● USB performance : Have to improve performance of sensors with USB

[click to see]
  • Link : here for x86_64 desktops
  • TX1/TX2 : here
  • For Xavier : here
$ sudo ./flash.sh -k kernel -C "usbcore.usbfs_memory_mb=1000" -k kernel-dtb jetson-xavier mmcblk0p1



● Calibration : Kalibr -> synchronization, time offset, extrinsic parameter

[click to see]
  • Kalibr -> synchronization, time offset
  • For ZED cameras : here
  • When Calibrating Fisheye camera like T265
    • Try with MEI camera model, as here, which is omni-radtan in Kalibr
    • and try this Pull to deal with NaNs here

● Trouble shooting for Kalibr errors

  • ImportError: No module named Image reference
$ gedit kalibr/aslam_offline_calibration/kalibr/python/kalibr_camera_calibration/MulticamGraph.py
#import Image
from PIL import Image
  • focal length initialization error
 $ gedit kalibr/aslam_cv/aslam_cameras/include/aslam/cameras/implementation/PinholeProjection.hpp
 # edit if sentence in line 781
 # comment from line 782 to 795
 f_guesses.push_back(2000.0) #initial guess of focal length!!!!
  • cameras are not connected
 $ gedit kalibr/aslam_offline_calibration/kalibr/python/kalibr_calibrate_cameras
 # comment from line 201 to 205

● IMU-Camera rotational extrinsic example

[click to see]
  • Between ROS standard body(IMU) and camera

  • Left view : Between ROS standard body(IMU) and down-pitched (look downward) camera




3. Installation and Execution

■ ROS1 Algorithms:

● VINS-Fusion

[with `OpenCV3`(original): click to see]
  • git clone and build from source
$ cd ~/catkin_ws/src
$ git clone https://github.com/HKUST-Aerial-Robotics/VINS-Fusion #CPU
or 
$ git clone https://github.com/pjrambo/VINS-Fusion-gpu #GPU
$ cd .. && catkin build camera_models # camera models first
$ catkin build

Before build VINS-Fusion, process below could be required.

  • For GPU version, Edit CMakeLists.txt for loop_fusion and vins_estimator
$ cd ~/catkin_ws/src/VINS-Fusion-gpu/loop_fusion && gedit CMakeLists.txt
or
$ cd ~/catkin_ws/src/VINS-Fusion-gpu/vins_estimator && gedit CMakeLists.txt
##For loop_fusion : line 19
#find_package(OpenCV)
include(/usr/local/share/OpenCV/OpenCVConfig.cmake)

##For vins_estimator : line 20
#find_package(OpenCV REQUIRED)
include(/usr/local/share/OpenCV/OpenCVConfig.cmake)

[with `OpenCV4`: click to see]
  • git clone and build, few cv codes are changed from original repo.
$ cd ~/catkin_ws/src
$ git clone https://github.com/engcang/vins-application #Only CPU version yet
$ cd vins-application

$ mv vins_estimator ..
$ mv camera_models ..
$ cd ..
$ rm -r vins-application

$ cd .. 
$ catkin build

● Trouble shooting for VINS-Fusion

[click to see]
  • Aborted error when running vins_node :
 $ echo "export MALLOC_CHECK_=0" >> ~/.bashrc
 $ source ~/.bashrc
  • If want to try to deal with NaNs, refer here


● VINS-Fisheye

only for OpenCV 3.4.1 and Jetson TX2 (I guess yet, I failed on i9-10900k + RTX3080)

[click to see]
  • Get libSGM and install with OpenCV option as below:
$ git clone https://github.com/fixstars/libSGM
$ cd libSGM
$ git submodule update --init

check and edit CMakeLists.txt
$ gedit CMakeLists.txt
Edit
BUILD_OPENCV_WRAPPER=ON and ENABLE_TESTS=ON

$ mkdir build && cd build
$ cmake .. -DBUILD_OPENCV_WRAPPER=ON -DENABLE_TESTS=ON
$ make -j6
$ sudo make install

do test
$ cd libSGM/build/test && ./sgm-test
  • Get VINS-Fisheye and install
$ cd ~/catkin_ws/src
$ git clone https://github.com/xuhao1/VINS-Fisheye
$ cd ..

build camera_models first
$ catkin build camera_models

$ gedit src/VINS-Fisheye/vins_estimator/CMakeLists.txt
edit as below:
set(ENABLE_BACKWARD false)
or
$ sudo apt install libdw-dev

$ catkin build

● OpenVINS

[click to see]
  • Get OpenVINS and install: refer doc, git
$ cd ~/catkin_ws/src
$ git clone https://github.com/rpng/open_vins/
$ cd ..
$ catkin build

● EnVIO

[click to see]
$ cd ~/catkin_ws/src
$ git clone https://github.com/lastflowers/envio.git
$ cd ..

$ catkin_make

or, if you want to use it with catkin build,
then

$ gedit src/envio/CMakeLists.txt
comment two lines, line 4 and 5
#set(CMAKE_CXX_COMPILER "/usr/bin/g++-5")
#set(CMAKE_C_COMPILER "/usr/bin/gcc-5")

$ catkin build    

● S-MSCKF

[click to see]

● Installation

 $ sudo apt-get install libsuitesparse-dev
 $ cd ~/catkin_ws/src && https://github.com/KumarRobotics/msckf_vio
 $ cd ~/catkin_ws && catkin build msckf_vio -DCMAKE_BUILD_TYPE=Release

● ROVIO

[click to see]

● Requirements

  • ROVIO receives input image as gray scale image - convert the RGB image as this file
  • Config files can be generated directly from Kalibr results:
$ rosrun kalibr kalibr_rovio_config --cam <cam-chain.yaml filename>
  • After using kalibr to convert the calibration result files to rovio_config files,
    • Make sure to Edit Camera1 and Camera2 into Camera0 and Camera1 in .info file
    • Make sure to Add Velocity Updates block in .info file

● Installation

$ cd ~/catkin_ws/src && git clone https://github.com/ANYbotics/kindr
$ cd .. && catkin build -j8
  • Install ROVIO
$ cd ~/catkin_ws/src && git clone https://github.com/ethz-asl/rovio
$ cd rovio && git submodule update --init --recursive

$ cd ..
$ catkin build rovio --cmake-args -DCMAKE_BUILD_TYPE=Release

# With with opengl scene (optional)
$ sudo apt-get install freeglut3-dev libglew-dev
$ catkin build rovio --cmake-args -DCMAKE_BUILD_TYPE=Release -DMAKE_SCENE=ON

● ORB-SLAM2

[click to see]

● Installation

 $ cd ~/catkin_ws/src && git clone https://github.com/appliedAI-Initiative/orb_slam_2_ros
 $ cd .. && rosdep install --from-paths src --ignore-src -r -y
 $ catkin build
  • highly recommend this pull request to speedup loading Vocabulary here

● DM-VIO

[click to see]
  • Install dependencies
$ sudo apt-get install cmake libsuitesparse-dev libeigen3-dev libboost-all-dev libyaml-cpp-dev libtbb-dev libgl1-mesa-dev libglew-dev pkg-config libegl1-mesa-dev libwayland-dev libxkbcommon-dev wayland-protocols -y

$ cd ~/your_workspace
$ git clone https://github.com/borglab/gtsam.git
$ cd gtsam
$ git checkout 4.2a6          # not strictly necessary but this is the version tested with.
$ mkdir build && cd build
$ cmake -DGTSAM_POSE3_EXPMAP=ON -DGTSAM_ROT3_EXPMAP=ON -DGTSAM_USE_SYSTEM_EIGEN=ON -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF ..
$ make -j
$ sudo make install

$ cd ~/your_workspace
$ git clone https://github.com/stevenlovegrove/Pangolin.git
$ cd Pangolin
$ git checkout v0.6
$ mkdir build && cd build
$ cmake ..
$ cmake --build .
$ sudo make install
  • Build DM-VIO and DM-VIO-ROS
$ cd ~/your_workspace
$ git clone https://github.com/lukasvst/dm-vio.git
$ cd dm-vio
$ mkdir build && cd build
$ cmake ..
$ make -j10
$ echo "export DMVIO_BUILD=`pwd`" >> ~/.bashrc && . ~/.bashrc

$ cd ~/your_workspace/src
$ git clone https://github.com/lukasvst/dm-vio-ros.git
$ cd ~/your_workspace
$ catkin build
$ . devel/setup.bash
$ sudo ldconfig
$ rosrun dmvio_ros node calib=camera_kaistvio.txt imuCalib=camchain_kaistvio.yaml settingsFile=setting_kaistvio.yaml mode=3 nogui=0 preset=1 quiet=1 useimu=1

■ ROS2 Algorithms:

● NVIDIA Isaac Elbrus

[click to see]

● Requirements

  • PC option1 - Ubuntu 20.04
    • CUDA: 11.4-11.5 (11.6 cannot install VPI 1.1.11)
    • NVIDIA Graphic driver >= 470.103.01
    • (Important) NVIDIA VPI 1.1.11 (Only this version) - install with this files after CUDA installation
  • PC option2 - Jetpack 4.6.1 on Jetson Xavier AGX / NX
  • Topics: Raw stereo image + camera info topics + (Important!) /tf_static (including base_frame (e.g., camera_link) to left and right camera frame)

● Installation

$ sudo apt install git-lfs
$ cd ~/colcon_ws/src
$ git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_visual_slam &&
git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_image_pipeline &&
git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common
$ cd ..
$ rosdep install -i -r --from-paths src --rosdistro foxy -y
$ colcon build --symlink-install && source install/setup.bash

● Run

  • Edit remapping topic names in the launch file below, before launching it.
# Copyright (c) 2021, NVIDIA CORPORATION.  All rights reserved.

    ...

import launch
from launch_ros.actions import ComposableNodeContainer, Node
from launch_ros.descriptions import ComposableNode

    ...
    
        remappings=[('stereo_camera/left/image', '/camera/infra1/image_rect_raw'),
                    ('stereo_camera/left/camera_info', '/camera/infra1/camera_info'),
                    ('stereo_camera/right/image', '/camera/infra2/image_rect_raw'),
                    ('stereo_camera/right/camera_info', '/camera/infra2/camera_info')]
    )

    ...
    
  • If you want to run it with bag file, then use or refer this launch file
    • since /tf_static cannot be recorded in bag file, static_transform_publisher should be added in the launch file as these lines

4. Comparison & Application

  • Conversion ROS topics into nav_msgs/Path to visualize in Rviz: use this github
  • Conversion compressed Images into raw Images: use this code

Simulation

  • VINS-Mono on FlightGoggles: youtube, with CPU youtube
  • ROVIO on FlightGoggles: youtube
  • ORB-SLAM2 on FlightGoggles: youtube
  • VINS with Loop fusion vs VINS on FlightGoggles: youtube
  • VINS-Mono vs ROVIO: youtube
  • VINS-Mono vs ROVIO vs ORB-SLAM2: youtube
  • VINS-Fusion (Stereo) vs S-MSCKF on FlightGoggles: youtube
  • VINS-Fusion (Stereo) based autonomous flight and 3D mapping using RGB-D camera: youtube

Real world

  • Hand-held - VINS-Mono with pointgrey cam, myAHRS+ imu on Jetson Xavier AGX: youtube, moved faster : youtube

  • Hand-held - ROVIO with Intel D435i on Jetson Xavier AGX: youtube

  • Hand-held - ORB-SLAM2 with Intel D435i on Jetson Xavier AGX: youtube

  • Hand-held - VINS(GPU version) with pointgrey, myAHRS at Intel i7-8700k, TITAN RTX: youtube

  • Hand-held - VINS(GPU version, Stereo) with Intel D435i, on Xavier AGX, max CPU clocked: youtube and youtube2 : screen

  • Hand-held - VINS-Fusion (Stereo) with Intel D435i and Pixhawk4 mini fused with T265 camera: here

  • Hand-held - VINS-Fusion (stereo) with Intel D435i and Pixhawk4 mini on 1km long underground tunnel: here

  • Hand-held - VINS-Fusion GPU version test using T265: here

  • Hand-held - VINS-Fusion (stereo) test using OAK-D: here

  • Hand-held - VINS-Fusion (stereo) test using OAK-D PRO: here

  • Real-Drone - VINS-Fusion with Intel D435i and Pixahwk4 mini on Real Hexarotor: here

  • Real-Drone - VINS-Fusion with Intel D435i and Pixahwk4 mini on Real Quadrotor: here

  • OpenVINS on KAIST VIO dataset: result youtube

  • EnVIO vs VINS-Fusion on KAIST VIO dataset: result youtube

  • DM-VIO vs VINS-Mono on KAIST VIO dataset: result youtube

  • NVIDIA Isaac Elbrus in real-world: result youtube


5. VINS on mini onboard PCs

  • Qualcomm RB5 vs Khadas VIM3 Pro - Video

vins-application's People

Contributors

engcang avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

vins-application's Issues

How to use d435i with Khadas VIM3?

How to find the device(realsense d435i) with khadas VIM3? I have found that libreasense doesn't support the ubuntu 4.9 kernel. Which version of librealsense needs to be installed?

cant make it work with ZED mini and d435i

Hi @engcang
Im testing VINS-Fusion CPU with ZED mini, can you ensure you are able to run it?

Im not able to correctly init VINS, I always obtain NaNs:

WARNING: Logging before InitGoogleLogging() is written to STDERR
W0814 15:14:59.771003 19283 parameter_block.h:349] Local parameterization Jacobian computation returnedan invalid matrix for x: -nan -nan -nan -nan
 Jacobian matrix : 0nan 0nan 0nan
-nan -nan 0nan
0nan -nan -nan
-nan 0nan -nan
F0814 15:14:59.771054 19283 parameter_block.h:189] Check failed: UpdateLocalParameterizationJacobian() Local parameterization Jacobian computation failed for x: -nan -nan -nan -nan

This in my config

zed_imu_config.yaml
%YAML:1.0

#common parameters
#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam; 
imu: 1         
num_of_cam: 1  

imu_topic: "/zed/zed_node/imu/data_raw"
image0_topic: "/zed/zed_node/left/image_rect_color"
image1_topic: "/zed/zed_node/right/image_rect_color"
output_path: "~/output/"

cam0_calib: "cam_pinhole_l.yaml"
cam1_calib: "cam_pinhole_r.yaml"
image_width: 672
image_height: 376
   

# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 1   # 0  Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
                        # 1  Have an initial guess about extrinsic parameters. We will optimize around your initial guess.

body_T_cam0: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [0.0014846158067664955, -0.9999566394077031, -0.009193215996598725, 0.0026856085760216626,
          0.026265352079174964, 0.009229046866280219, -0.9996124028712818, 0.0009023689144005919,
          0.9996539037067099, 0.0012425773190519185, 0.02627791478681095, 0.0006287860401229842,
          0, 0, 0, 1]
body_T_cam1: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [-0.0016843852880614036, -0.9999562677393219, -0.009199209479474446, -0.06711970546466307,
           0.025674324312040753, 0.009152946405229194, -0.9996284572996227, 0.0022119334059672777,
           0.9996689411586828, -0.0019199429545934121, 0.02565778442752982, 0.0006892909975584863,
           0, 0, 0, 1]

#Multiple thread support
multiple_thread: 8

#feature traker paprameters
max_cnt: 110            # max feature number in feature tracking
min_dist: 18            # min distance between two features 
freq: 0                # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image 
F_threshold: 1        # ransac threshold (pixel)
show_track: 0          # publish tracking image as topic
flow_back: 1            # perform forward and backward optical flow to improve feature tracking accuracy

#optimization parameters
max_solver_time: 0.045  # max solver itration time (ms), to guarantee real time
max_num_iterations: 8   # max solver itrations, to guarantee real time
keyframe_parallax: 10 # keyframe selection threshold (pixel)

#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.     
g_norm: 9.81007     # gravity magnitude

#unsynchronization parameters
estimate_td: 1                      # online estimate time offset between camera and imu
td: -0.04                             # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)

#loop closure parameters
load_previous_pose_graph: 0        # load and reuse previous pose graph; load from 'pose_graph_save_path'
pose_graph_save_path: "~/output/pose_graph/" # save and load path
save_image: 0                   # save image in pose graph for visualization prupose; you can close this function by setting 0 

thank you very much,
Francesco

Test Omni Swarm and D2SLAM

They are latest swarm SLAM, helping swarm UAV make global localization. Are you interested in trying these?

some inputs regarding D435i + vins_fusion

As you are one of the very few who were able to run VINS-FUSION on a VIO mode, I come back to you to clarify some points and ask for your feedback.

I am trying to run VINS FUSION with a D435i (like many people I guess). Using the available launch realsense_stereo_imu_config.yaml I experienced what may people reported, as soon as you touch the camera, the computed pose got crazy.

So I used Kalibr :

  • to calibrate the cameras and I got the following result:
cam0:
  cam_overlaps: [1]
  camera_model: pinhole
  distortion_coeffs: [0.3775752250096366, -0.08329757139021714, 0.6504570262599587, -0.4530039925701512]
  distortion_model: equidistant
  intrinsics: [395.5922288679944, 395.5957501002353, 319.88738279106286, 239.07386401539998]
  resolution: [640, 480]
  rostopic: /camera/infra1/image_rect_raw
cam1:
  T_cn_cnm1:
  - [0.9999953397168069, 9.448668958037214e-05, 0.0030514942108417595, -0.04984248508758902]
  - [-9.749429725933605e-05, 0.9999995096576434, 0.0009854843073503579, 6.189814698173665e-05]
  - [-0.0030513995994150846, -0.0009857772179980872, 0.9999948585886561, 0.00015202509092000083]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [0]
  camera_model: pinhole
  distortion_coeffs: [0.31220975539351176, 0.48299676137352554, -1.4010717249687126, 2.191483852686]
  distortion_model: equidistant
  intrinsics: [396.5827833428163, 396.75838144377565, 319.1950768721882, 238.53973946284336]
  resolution: [640, 480]
  rostopic: /camera/infra2/image_rect_raw

I think the calibration is ok because when I run VINS_FUSION with these parameters (imu = 0), I got a decent behavior. I will be more than happy to share the pdf report with you if necessary because I am not an expert in that field.

  • Camera IMu calibration, was not so straighforward because I do not have the noise density and randm walk values. So I used the Allan variance software and some code from matlab and I got this for the acceleration
    allan_acc
accelerometer_noise_density: 0.0011060    #Noise density (continuous-time)
accelerometer_random_walk:   8.6056e-05    #Bias random walk

but for the gyro I am clearly skeptical :
allan_gyro

because the values are the following:

gyroscope_noise_density:     50.427    #Noise density (continuous-time)
gyroscope_random_walk:       0.3480    #Bias random walk

Here I would like to get your opinion on these values?

However I was able to to do an imu-camera calibration:

cam0:
  T_cam_imu:
  - [0.999848715163262, 0.0018345448477758066, 0.017296856118190283, -0.009035083963879727]
  - [-0.001867318311452875, 0.999996491602708, 0.0018788040335944412, 0.002129300542443833]
  - [-0.01729334868368733, -0.0019108185351930207, 0.9998486329759259, -0.005593943362795322]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [1]
  camera_model: pinhole
  distortion_coeffs: [0.3775752250096366, -0.08329757139021714, 0.6504570262599587,
    -0.4530039925701512]
  distortion_model: equidistant
  intrinsics: [395.5922288679944, 395.5957501002353, 319.88738279106286, 239.07386401539998]
  resolution: [640, 480]
  rostopic: /camera/infra1/image_rect_raw
  timeshift_cam_imu: -0.028184396371617668
cam1:
  T_cam_imu:
  - [0.9997911085949877, 0.0019231918046627172, 0.020347985347160178, -0.058894395640646836]
  - [-0.0019818392674274344, 0.999993939322739, 0.0028624519050287085, 0.0021865657711008357]
  - [-0.02034235698054308, -0.002902180399802527, 0.9997888606407872, -0.005416418875488448]
  - [0.0, 0.0, 0.0, 1.0]
  T_cn_cnm1:
  - [0.9999953397168102, 9.448668958037212e-05, 0.003051494210841759, -0.04984248508758902]
  - [-9.749429725933604e-05, 0.9999995096576467, 0.0009854843073503574, 6.189814698173665e-05]
  - [-0.003051399599415084, -0.0009857772179980868, 0.9999948585886594, 0.00015202509092000083]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [0]
  camera_model: pinhole
  distortion_coeffs: [0.31220975539351176, 0.48299676137352554, -1.4010717249687126,
    2.191483852686]
  distortion_model: equidistant
  intrinsics: [396.5827833428163, 396.75838144377565, 319.1950768721882, 238.53973946284336]
  resolution: [640, 480]
  rostopic: /camera/infra2/image_rect_raw
  timeshift_cam_imu: -0.028184788415138273

Here I am also surprise because the timeshift is NEGATIVE! Is it possible?
Regarding the camera transformation, from a thread related to VINS_FUSION, I understood that body_T_cam0/1 is the transform from camera frame to the IMU frame

p = body_T_cam0 * q
p: point in IMU coordinates
q: point in camera coordinates

and with Kalibr T_cam_imu is the IMU extrinsics: transformation from IMU to camera coordinates (T_c_i) but I am puzzled so far to get the right format used by VINS_FUSION.

However despite all this work, I am still not be able to run VINS with the IMU. Sorry for being so long but do you see something wrong here that may explain why it is not working?

Thanks a lot

Using with ZED2 camera

Hello sir,

We are newly working on the VIO. We need help in using ZED2 camera with vins fusion. How can we convert the yaml and launch files according to ZED2? Also, which commands in terminal do we need to text for execute it?

Can't find the proper launch file for d435i

Hi,
I can't find the file which launches vins fusion node. I have a d435i. I have launched the rs_camera.launch file but stuck in launching node which launches vins/vins estimator. I can't see any launch file. The only launch file that I see is kaist.launch which is configured for stereo camera I think (most probably for T265). Any help is appreciated. Thanks !!

Using Vins with d435i realsense camera

Hi @engcang ,
I'm using vins with d435i camera and I'm using image of camera only not the imu of it because when we're enabling the imu the vins is getting extreme distorted,also we have done imu calibration perfectly and the calibration data is also perfect but i don't why it's getting distorted although vins is working great with image only so im using it for now.Now I'm facing an orientation problem in vins like in vins rviz the camera is in upward direction also when we move our drone upward the value of -y is increasing and when we are moving our drone forward the z is increasing...
Please help regarding the issue

Masking file

Hello, thank you for your explanations.

I am confused about the mask added to the VINS-Fusion for PX4

  1. what is the image used to create this mask in maskin.m?
  2. Does a different mask need to be used if using the d435i with different resolution (I'm guessing yes but making sure)
  3. What is improved by using this mask?

Thank you

Error in realsense-viewer

Required Info
Camera Model D435i
Firmware Version 05.12.13.50
Operating System & Version Ubuntu 18.04
Kernel Version (Linux Only) 4.9.140-tegra
Platform NVIDIA Jetson
SDK Version v2.45.0
Language C
Segment Robot- ROS v2.3.0

Issue Description

I am currently using auvidea j120 board with jetson TX2 and D435i.
However, there is some error i am currently facing when i am running realsense-viewer. The D435i camera does not have RGB image and is showing this error.

ERROR [547423751968] (synthetic-stream.cpp:48) Exception was thrown during user processing callback: 1kernel_other_to_depthILi4EEvPhPKhPK4int2PK14rs2_intrinsicsS8_

Steps taken
$ sudo apt-get install git libssl-dev libusb-1.0-0-dev pkg-config libgtk-3-dev
 $ sudo apt-get install libglfw3-dev libgl1-mesa-dev libglu1-mesa-dev
 $ git clone https://github.com/IntelRealSense/librealsense.git
 $ cd librealsense
 $ git checkout v2.45.0
 $ mkdir build && cd build
 $ cmake .. -DCMAKE_BUILD_TYPE=Release -DFORCE_RSUSB_BACKEND=ON -DBUILD_WITH_CUDA=true
 $ sudo make uninstall && make clean
 $ time make -j8 && sudo make install
 
 Below is the image of the realsense-viewer for your references
image

Test VID Fusion

There is a new VINS with rotos' dynamic called VID-Fusion. Do you plan to test this new one?

installation error when catkin build

tried to install the gpu version and when i build it it shows this
Profile: default
Extending: [cached] /opt/ros/noetic
Workspace: /home/peixuan/workspace2
Build Space: [exists] /home/peixuan/workspace2/build
Devel Space: [exists] /home/peixuan/workspace2/devel
Install Space: [unused] /home/peixuan/workspace2/install
Log Space: [exists] /home/peixuan/workspace2/logs
Source Space: [exists] /home/peixuan/workspace2/src
DESTDIR: [unused] None
Devel Space Layout: linked
Install Space Layout: None
Additional CMake Args: None
Additional Make Args: None
Additional catkin Make Args: None
Internal Make Job Server: True
Cache Job Environments: False
Whitelisted Packages: None
Blacklisted Packages: None
Workspace configuration appears valid.

[build] Found '4' packages in 0.0 seconds.
[build] Updating package table.
Starting >>> camera_models
Starting >>> global_fusion
Starting >>> vins

Errors << vins:cmake /home/peixuan/workspace2/logs/vins/build.cmake.000.log
CMake Error at /opt/ros/noetic/share/catkin/cmake/catkinConfig.cmake:83 (find_package):
Could not find a package configuration file provided by "camera_models"
with any of the following names:

camera_modelsConfig.cmake
camera_models-config.cmake

Add the installation prefix of "camera_models" to CMAKE_PREFIX_PATH or set
"camera_models_DIR" to a directory containing one of the above files. If
"camera_models" provides a separate development package or SDK, be sure it
has been installed.
Call Stack (most recent call first):
CMakeLists.txt:9 (find_package)

cd /home/peixuan/workspace2/build/vins; catkin build --get-env vins | catkin env -si /usr/bin/cmake /home/peixuan/workspace2/src/VINS-Fusion-gpu/vins_estimator --no-warn-unused-cli -DCATKIN_DEVEL_PREFIX=/home/peixuan/workspace2/devel/.private/vins -DCMAKE_INSTALL_PREFIX=/home/peixuan/workspace2/install; cd -

...............................................................................
Failed << vins:cmake [ Exited with code 1 ]
Failed <<< vins [ 4.9 seconds ]
Abandoned <<< loop_fusion [ Unrelated job failed ]

Errors << camera_models:make /home/peixuan/workspace2/logs/camera_models/build.make.001.log
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In constructor ‘camodocal::Chessboard::Chessboard(cv::Size, cv::Mat&)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:20:38: error: ‘CV_GRAY2BGR’ was not declared in this scope
20 | cv::cvtColor(image, mSketch, CV_GRAY2BGR);
| ^~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:26:37: error: ‘CV_BGR2GRAY’ was not declared in this scope
26 | cv::cvtColor(image, mImage, CV_BGR2GRAY);
| ^~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In member function ‘void camodocal::Chessboard::findCorners(bool)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:34:43: error: ‘CV_CALIB_CB_ADAPTIVE_THRESH’ was not declared in this scope
34 | CV_CALIB_CB_ADAPTIVE_THRESH +
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:35:43: error: ‘CV_CALIB_CB_NORMALIZE_IMAGE’ was not declared in this scope
35 | CV_CALIB_CB_NORMALIZE_IMAGE +
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:36:43: error: ‘CV_CALIB_CB_FILTER_QUADS’ was not declared in this scope
36 | CV_CALIB_CB_FILTER_QUADS +
| ^~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:37:43: error: ‘CV_CALIB_CB_FAST_CHECK’ was not declared in this scope
37 | CV_CALIB_CB_FAST_CHECK,
| ^~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In constructor ‘camodocal::Chessboard::Chessboard(cv::Size, cv::Mat&)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:20:38: error: ‘CV_GRAY2BGR’ was not declared in this scope
20 | cv::cvtColor(image, mSketch, CV_GRAY2BGR);
| ^~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In member function ‘bool camodocal::Chessboard::findChessboardCornersImproved(const cv::Mat&, const Size&, std::vector<cv::Point_ >&, int)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:144:43: error: ‘CV_CALIB_CB_NORMALIZE_IMAGE’ was not declared in this scope
144 | if (image.channels() != 1 || (flags & CV_CALIB_CB_NORMALIZE_IMAGE))
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:26:37: error: ‘CV_BGR2GRAY’ was not declared in this scope
26 | cv::cvtColor(image, mImage, CV_BGR2GRAY);
| ^~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:150:43: error: ‘CV_BGR2GRAY’ was not declared in this scope
150 | cv::cvtColor(image, norm_img, CV_BGR2GRAY);
| ^~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In member function ‘void camodocal::Chessboard::findCorners(bool)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:34:43: error: ‘CV_CALIB_CB_ADAPTIVE_THRESH’ was not declared in this scope
34 | CV_CALIB_CB_ADAPTIVE_THRESH +
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:161:17: error: ‘CV_CALIB_CB_FAST_CHECK’ was not declared in this scope
161 | if (flags & CV_CALIB_CB_FAST_CHECK)
| ^~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:35:43: error: ‘CV_CALIB_CB_NORMALIZE_IMAGE’ was not declared in this scope
35 | CV_CALIB_CB_NORMALIZE_IMAGE +
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:192:25: error: ‘CV_CALIB_CB_ADAPTIVE_THRESH’ was not declared in this scope
192 | if (flags & CV_CALIB_CB_ADAPTIVE_THRESH)
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:36:43: error: ‘CV_CALIB_CB_FILTER_QUADS’ was not declared in this scope
36 | CV_CALIB_CB_FILTER_QUADS +
| ^~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:198:61: error: ‘CV_ADAPTIVE_THRESH_MEAN_C’ was not declared in this scope
198 | cv::adaptiveThreshold(img, thresh_img, 255, CV_ADAPTIVE_THRESH_MEAN_C, CV_THRESH_BINARY, blockSize, (k/2)*5);
| ^~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:37:43: error: ‘CV_CALIB_CB_FAST_CHECK’ was not declared in this scope
37 | CV_CALIB_CB_FAST_CHECK,
| ^~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:198:88: error: ‘CV_THRESH_BINARY’ was not declared in this scope
198 | cv::adaptiveThreshold(img, thresh_img, 255, CV_ADAPTIVE_THRESH_MEAN_C, CV_THRESH_BINARY, blockSize, (k/2)*5);
| ^~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:207:67: error: ‘CV_THRESH_BINARY’ was not declared in this scope
207 | cv::threshold(img, thresh_img, thresh_level, 255, CV_THRESH_BINARY);
| ^~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In member function ‘bool camodocal::Chessboard::findChessboardCornersImproved(const cv::Mat&, const Size&, std::vector<cv::Point_ >&, int)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:144:43: error: ‘CV_CALIB_CB_NORMALIZE_IMAGE’ was not declared in this scope
144 | if (image.channels() != 1 || (flags & CV_CALIB_CB_NORMALIZE_IMAGE))
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:150:43: error: ‘CV_BGR2GRAY’ was not declared in this scope
150 | cv::cvtColor(image, norm_img, CV_BGR2GRAY);
| ^~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:215:57: error: ‘CV_SHAPE_CROSS’ was not declared in this scope
215 | cv::Mat kernel1 = cv::getStructuringElement(CV_SHAPE_CROSS, cv::Size(3,3), cv::Point(1,1));
| ^~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:216:57: error: ‘CV_SHAPE_RECT’ was not declared in this scope
216 | cv::Mat kernel2 = cv::getStructuringElement(CV_SHAPE_RECT, cv::Size(3,3), cv::Point(1,1));
| ^~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:161:17: error: ‘CV_CALIB_CB_FAST_CHECK’ was not declared in this scope
161 | if (flags & CV_CALIB_CB_FAST_CHECK)
| ^~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:320:43: error: ‘CV_TERMCRIT_EPS’ was not declared in this scope
320 | cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1));
| ^~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:320:61: error: ‘CV_TERMCRIT_ITER’ was not declared in this scope
320 | cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1));
| ^~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:192:25: error: ‘CV_CALIB_CB_ADAPTIVE_THRESH’ was not declared in this scope
192 | if (flags & CV_CALIB_CB_ADAPTIVE_THRESH)
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/calib/CameraCalibration.cc: In member function ‘void camodocal::CameraCalibration::drawResults(std::vectorcv::Mat&) const’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/calib/CameraCalibration.cc:235:40: error: ‘CV_GRAY2RGB’ was not declared in this scope
235 | cv::cvtColor(image, image, CV_GRAY2RGB);
| ^~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/calib/CameraCalibration.cc:253:37: error: ‘CV_AA’ was not declared in this scope; did you mean ‘CV_MSA’?
253 | 5, green, 2, CV_AA, drawShiftBits);
| ^~~~~
| CV_MSA
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/calib/CameraCalibration.cc:275:24: error: ‘CV_AA’ was not declared in this scope; did you mean ‘CV_MSA’?
275 | 1, CV_AA);
| ^~~~~
| CV_MSA
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:198:61: error: ‘CV_ADAPTIVE_THRESH_MEAN_C’ was not declared in this scope
198 | cv::adaptiveThreshold(img, thresh_img, 255, CV_ADAPTIVE_THRESH_MEAN_C, CV_THRESH_BINARY, blockSize, (k/2)5);
| ^~~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In member function ‘void camodocal::Chessboard::generateQuads(std::vector<boost::shared_ptrcamodocal::ChessboardQuad >&, cv::Mat&, int, int, bool)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1175:50: error: ‘CV_RETR_CCOMP’ was not declared in this scope
1175 | cv::findContours(image, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
| ^~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:198:88: error: ‘CV_THRESH_BINARY’ was not declared in this scope
198 | cv::adaptiveThreshold(img, thresh_img, 255, CV_ADAPTIVE_THRESH_MEAN_C, CV_THRESH_BINARY, blockSize, (k/2)5);
| ^~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1175:65: error: ‘CV_CHAIN_APPROX_SIMPLE’ was not declared in this scope
1175 | cv::findContours(image, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
| ^~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:207:67: error: ‘CV_THRESH_BINARY’ was not declared in this scope
207 | cv::threshold(img, thresh_img, thresh_level, 255, CV_THRESH_BINARY);
| ^~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:215:57: error: ‘CV_SHAPE_CROSS’ was not declared in this scope
215 | cv::Mat kernel1 = cv::getStructuringElement(CV_SHAPE_CROSS, cv::Size(3,3), cv::Point(1,1));
| ^~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1241:27: error: ‘CV_CALIB_CB_FILTER_QUADS’ was not declared in this scope
1241 | if (!(flags & CV_CALIB_CB_FILTER_QUADS) ||
| ^~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:216:57: error: ‘CV_SHAPE_RECT’ was not declared in this scope
216 | cv::Mat kernel2 = cv::getStructuringElement(CV_SHAPE_RECT, cv::Size(3,3), cv::Point(1,1));
| ^~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:320:43: error: ‘CV_TERMCRIT_EPS’ was not declared in this scope
320 | cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1));
| ^~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:320:61: error: ‘CV_TERMCRIT_ITER’ was not declared in this scope
320 | cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1));
| ^~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In member function ‘bool camodocal::Chessboard::checkChessboard(const cv::Mat&, cv::Size) const’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1586:72: error: ‘CV_THRESH_BINARY’ was not declared in this scope
1586 | cv::threshold(white, thresh, threshLevel + blackWhiteGap, 255, CV_THRESH_BINARY);
| ^~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1592:55: error: ‘CV_RETR_CCOMP’ was not declared in this scope
1592 | cv::findContours(thresh, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
| ^~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1592:70: error: ‘CV_CHAIN_APPROX_SIMPLE’ was not declared in this scope
1592 | cv::findContours(thresh, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
| ^~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In member function ‘void camodocal::Chessboard::generateQuads(std::vector<boost::shared_ptrcamodocal::ChessboardQuad >&, cv::Mat&, int, int, bool)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1175:50: error: ‘CV_RETR_CCOMP’ was not declared in this scope
1175 | cv::findContours(image, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
| ^~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1597:56: error: ‘CV_THRESH_BINARY_INV’ was not declared in this scope
1597 | cv::threshold(black, thresh, threshLevel, 255, CV_THRESH_BINARY_INV);
| ^~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1175:65: error: ‘CV_CHAIN_APPROX_SIMPLE’ was not declared in this scope
1175 | cv::findContours(image, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
| ^~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1241:27: error: ‘CV_CALIB_CB_FILTER_QUADS’ was not declared in this scope
1241 | if (!(flags & CV_CALIB_CB_FILTER_QUADS) ||
| ^~~~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc: In member function ‘bool camodocal::Chessboard::checkChessboard(const cv::Mat&, cv::Size) const’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1586:72: error: ‘CV_THRESH_BINARY’ was not declared in this scope
1586 | cv::threshold(white, thresh, threshLevel + blackWhiteGap, 255, CV_THRESH_BINARY);
| ^~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1592:55: error: ‘CV_RETR_CCOMP’ was not declared in this scope
1592 | cv::findContours(thresh, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
| ^~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1592:70: error: ‘CV_CHAIN_APPROX_SIMPLE’ was not declared in this scope
1592 | cv::findContours(thresh, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
| ^~~~~~~~~~~~~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/chessboard/Chessboard.cc:1597:56: error: ‘CV_THRESH_BINARY_INV’ was not declared in this scope
1597 | cv::threshold(black, thresh, threshLevel, 255, CV_THRESH_BINARY_INV);
| ^~~~~~~~~~~~~~~~~~~~
make[2]: *** [CMakeFiles/Calibrations.dir/build.make:76: CMakeFiles/Calibrations.dir/src/chessboard/Chessboard.cc.o] Error 1
make[2]: *** Waiting for unfinished jobs....
make[2]: *** [CMakeFiles/camera_models.dir/build.make:63: CMakeFiles/camera_models.dir/src/chessboard/Chessboard.cc.o] Error 1
make[2]: *** Waiting for unfinished jobs....
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/intrinsic_calib.cc: In function ‘int main(int, char)’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/intrinsic_calib.cc:277:26: error: ‘CV_AA’ was not declared in this scope
277 | CV_AA );
| ^~~~~
make[2]: *** [CMakeFiles/Calibrations.dir/build.make:89: CMakeFiles/Calibrations.dir/src/calib/CameraCalibration.cc.o] Error 1
make[2]: *** [CMakeFiles/Calibrations.dir/build.make:63: CMakeFiles/Calibrations.dir/src/intrinsic_calib.cc.o] Error 1
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/calib/CameraCalibration.cc: In member function ‘void camodocal::CameraCalibration::drawResults(std::vectorcv::Mat&) const’:
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/calib/CameraCalibration.cc:235:40: error: ‘CV_GRAY2RGB’ was not declared in this scope
235 | cv::cvtColor(image, image, CV_GRAY2RGB);
| ^~~~~~~~~~~
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/calib/CameraCalibration.cc:253:37: error: ‘CV_AA’ was not declared in this scope; did you mean ‘CV_MSA’?
253 | 5, green, 2, CV_AA, drawShiftBits);
| ^~~~~
| CV_MSA
/home/peixuan/workspace2/src/VINS-Fusion-gpu/camera_models/src/calib/CameraCalibration.cc:275:24: error: ‘CV_AA’ was not declared in this scope; did you mean ‘CV_MSA’?
275 | 1, CV_AA);
| ^~~~~
| CV_MSA
make[2]: *** [CMakeFiles/camera_models.dir/build.make:76: CMakeFiles/camera_models.dir/src/calib/CameraCalibration.cc.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:157: CMakeFiles/camera_models.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
make[1]: *** [CMakeFiles/Makefile2:265: CMakeFiles/Calibrations.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
cd /home/peixuan/workspace2/build/camera_models; catkin build --get-env camera_models | catkin env -si /usr/bin/make --jobserver-auth=3,4; cd -

...............................................................................
Failed << camera_models:make [ Exited with code 2 ]
Failed <<< camera_models [ 1 minute and 8.7 seconds ]
Finished <<< global_fusion [ 1 minute and 20.0 seconds ]
[build] Summary: 1 of 4 packages succeeded.
[build] Ignored: None.
[build] Warnings: None.
[build] Abandoned: 1 packages were abandoned.
[build] Failed: 2 packages failed.
[build] Runtime: 1 minute and 20.3 seconds total.
[build] Note: Workspace packages have changed, please re-source setup files to use them.

envio with d435i camera

i am trying to run envio with d435i i am confused with the launch file:

<node pkg="ensemble_vio" type="envio_node" name="envio_node">

    <rosparam command="load" file="$(arg calibration_file)" />

    <!-- Remapping : put your topics -->
    <remap from="/imu" to="/camera/imu"/>
    <remap from="/left_image" to="/camera/infra1/image_rect_raw"/>
    <remap from="/right_image" to="/camera/infra2/image_rect_raw"/>

    <!-- Vision processing parameters -->
    <param name="nx" value="25" type="int"/>
    <param name="ny" value="15" type="int"/>
    <param name="min_depth" value="0.3" type="double"/>
    <param name="max_depth" value="5" type="double"/>
    <param name="min_parallax" value="1" type="double"/>
    <param name="ransac_thr" value="1" type="double"/>

    <!-- Initial std_dev [rad, m, m/s, m/s^2, rad/s] -->
    <param name="P0/attitude" value="0.0175" type="double"/>
    <param name="P0/position" value="3e-2" type="double"/>
    <param name="P0/velocity" value="1e-1" type="double"/>
    <param name="P0/ba" value="0.1962" type="double"/>
    <param name="P0/bg" value="1.0e-3" type="double"/>
    <param name="P0/depth" value="1.5" type="double"/>
    <param name="P0/idepth" value="0.1" type="double"/>
    <param name="num_init_samples" value="500" type="int"/>

    <!-- Process noises [rad/s^(1/2), m/s^(3/2), m/s^(5/2), rad/s^(3/2)]-->
    <param name="Q/velocity" value="2e-3" type="double"/>
    <param name="Q/attitude" value="1e-4" type="double"/>
    <param name="Q/ba" value="2.5e-4" type="double"/>
    <param name="Q/bg" value="1e-7" type="double"/>

    <!-- Estimator parameters -->
    <param name="inverse_depth" value="false" type="bool"/>
    <param name="R_std" value="20" type="double"/>
    <!-- <param name="R_std" value="35" type="double"/> -->
    <param name="max_lifetime" value="300" type="int"/>
    <param name="thr_stop" value="1e-3" type="double"/>
    <param name="max_diff" value="30" type="double"/>
    <param name="N_en" value="100" type="int"/>
    <param name="use_stochastic_gradient" value="true" type="bool"/>
    <param name="thr_weak" value="3" type="double"/>

    <!-- Sparse setting -->
    <param name="thr_num" value="150" type="int"/>
    <param name="uniform_dist" value="30" type="int"/>
    <param name="max_iter" value="10" type="int"/>
<param name="max_itime" value="0.01" type="double"/>

    <!-- Vehicle to IMU z-y-x euler sequence -->
    <param name="roll_imu_vehicle" value="0.0" type="double"/>
    <param name="pitch_imu_vehicle" value="0.0" type="double"/>
    <param name="yaw_imu_vehicle" value="0.0" type="double"/>

</node>

i tried the same calibration file with vins fusion and its working great what thing i need to change in the launch file as i can see the changes will be in :

    <param name="P0/attitude" value="0.0175" type="double"/>
    <param name="P0/position" value="3e-2" type="double"/>
    <param name="P0/velocity" value="1e-1" type="double"/>
    <param name="P0/ba" value="0.1962" type="double"/>
    <param name="P0/bg" value="1.0e-3" type="double"/>
    <param name="P0/depth" value="1.5" type="double"/>
    <param name="P0/idepth" value="0.1" type="double"/>
    <param name="num_init_samples" value="500" type="int"/>

    <!-- Process noises [rad/s^(1/2), m/s^(3/2), m/s^(5/2), rad/s^(3/2)]-->
    <param name="Q/velocity" value="2e-3" type="double"/>
    <param name="Q/attitude" value="1e-4" type="double"/>
    <param name="Q/ba" value="2.5e-4" type="double"/>
    <param name="Q/bg" value="1e-7" type="double"/>

Please help me with this.
Thankyou

USB Performance ./flash.sh

Hi, could you provide more information on the USB performance section especially for ./flash.sh file? I am quite sure where this file comes from.

Thanks!

Question about building VINS-Fusion with GPU support using OpenCV 4.6.0

I'm trying to build VINS-Fusion with GPU support using OpenCV 4.6.0, but I'm encountering some difficulties. Specifically, I'm unsure about the correct configuration and build steps required to enable GPU acceleration with OpenCV 4.6.0.

I've already followed the installation instructions for VINS-Fusion and have successfully built it without GPU support. However, I'm not sure how to incorporate OpenCV 4.6.0 with CUDA support into the build process to enable GPU acceleration.

Could someone provide guidance or pointers on how to correctly configure and build VINS-Fusion with GPU support using OpenCV 4.6.0?

Environment:

Operating System: Ubuntu 20.04
OpenCV Version: 4.6.0
CUDA Toolkit Version: 11.4
Model: jetson xevier nx

VINS-Fusion CPU on Xavier NX

Hello, thanks for the detailed test and manual for VINS application. I see that you test VINS-Fusion GPU on Xavier NX, and do you test VINS-Fusion CPU? I tested it but it seems that NX CPU cannot supply enough computational consumption.

cann't run vins fusion gpu on Xavier

hello,I have some problem in rosrun vins.
My hardware is Xavier which has Jetpack4.3 and cuda10.0. I follow the steps in the article.I success complie the vins fusion gpu. But
double free or corruption (out)
Aborted (core dumped)

Uploading Screenshot from 2021-04-07 11-14-47.png…

Using with Intel RealSense T265

1.) Has any one used T265 with VINS Fusion
2.) Which is the convenient way calibrating T265 for VINS Fusion (like using Kalibr), if atall required.

Using vins on OAK-D-PRO

Hi, I am a beginner at VINS. We are currently trying to implement vins using Oak-d-pro. The environment I am using is Ubuntu 20.04, ROS 1 nonetic, and opencv 4. I feel quite confused after following the code configuration above. I am not sure how to establish a connection with the oak-ros simple mentioned under the oak-d branch, and how to run the currently configured vins code to achieve the effect you demonstrated. If it won't take up too much of your time, could you please guide me on what I should do to run it after configuring the config.yaml and Calibration data under the branch.Thanks a lot!

Test dm-vio

Dm-vio is dso vio version. It seems to be light and accuracy. Are you interested to test it?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.