GithubHelp home page GithubHelp logo

ov2slam / ov2slam Goto Github PK

View Code? Open in Web Editor NEW
572.0 20.0 128.0 9.63 MB

OV²SLAM is a Fully Online and Versatile Visual SLAM for Real-Time Applications

License: GNU General Public License v3.0

CMake 1.11% Shell 0.31% C++ 98.58%
ov2slam slam visison real-time visual-slam localization opencv versatile bundle-adjustment

ov2slam's Introduction

OV²SLAM

A Fully Online and Versatile Visual SLAM for Real-Time Applications

Paper: [arXiv]

Videos: [video #1], [video #2], [video #3], [video #4], [video #5], [video #6]

Authors: Maxime Ferrera, Alexandre Eudes, Julien Moras, Martial Sanfourche, Guy Le Besnerais ([email protected] / [email protected]).


April 2024 update: A ROS2 branch of OV2SLAM is now available here thanks to @MatPiech


OV²SLAM is a fully real-time Visual SLAM algorithm for Stereo and Monocular cameras. A complete SLAM pipeline is implemented with a carefully designed multi-threaded architecture allowing to perform Tracking, Mapping, Bundle Adjustment and Loop Closing in real-time. The Tracking is based on an undirect Lucas-Kanade optical-flow formulation and provides camera poses estimations at the camera's frame-rate. The Mapping works at the keyframes' rate and ensures continuous localization by populating the sparse 3D map and minimize drift through a local map tracking step. Bundle Adjustment is applied with an anchored inverse depth formulation, reducing the parametrization of 3D map points to 1 parameter instead of 3. Loop Closing is performed through an Online Bag of Words method thanks to iBoW-LCD. In opposition to classical offline BoW methods, no pre-trained vocabulary tree is required. Instead, the vocabulary tree is computed online from the descriptors extracted in the incoming video stream, making it always suited to the currently explored environment.

Related Paper:

If you use OV²SLAM in your work, please cite it as:

@article{fer2021ov2slam,
      title={{OV$^{2}$SLAM} : A Fully Online and Versatile Visual {SLAM} for Real-Time Applications},
      author={Ferrera, Maxime and Eudes, Alexandre and Moras, Julien and Sanfourche, Martial and {Le Besnerais}, Guy.},
      journal={IEEE Robotics and Automation Letters},
      year={2021}
     }

License

OV²SLAM is released under the GPLv3 license. For a closed-source version of OV²SLAM for commercial purposes, please contact ONERA (https://www.onera.fr/en/contact-us) or the authors.

Copyright (C) 2020 ONERA

1. Prerequisites

The library has been tested with Ubuntu 16.04 and 18.04, ROS Kinetic and Melodic and OpenCV 3. It should also work with ROS Noetic and OpenCV 4 but this configuration has not been fully tested.

1.0 C++11 or Higher

OV²SLAM makes use of C++11 features and should thus be compiled with a C++11 or higher flag.

1.1 ROS

ROS is used for reading the video images through bag files and for visualization purpose in Rviz.

ROS Installation

Make sure that the pcl_ros package is installed :

    sudo apt install ros-distro-pcl-ros

or even

    rosdep install ov2slam

1.2 Eigen3

Eigen3 is used throughout OV²SLAM. It should work with version >= 3.3.0, lower versions have not been tested.

1.3 OpenCV

OpenCV 3 has been used for the development of OV²SLAM, OpenCV 4 might be supported as well but it has not been tested. (Optional) The use of BRIEF descriptor requires that opencv_contrib was installed. If it is not the case, ORB will be used instead without scale and rotation invariance properties (which should be the exact equivalent of BRIEF).

WATCH OUT By default the CMakeLists.txt file assumes that opencv_contrib is installed, set the OPENCV_CONTRIB flag to OFF in CMakeLists.txt if it is not the case.

1.4 iBoW-LCD

A modified version of iBoW-LCD is included in the Thirdparty folder. It has been turned into a shared lib and is not a catkin package anymore. Same goes for OBIndex2, the required dependency for iBoW-LCD. Check the lcdetector.h and lcdetector.cc files to see the modifications w.r.t. to the original code.

1.5 Sophus

Sophus is used for SE(3), SO(3) elements representation. For convenience, a copy of Sophus has been included in the Thirdparty folder.

1.6 Ceres Solver

Ceres is used for optimization related operations such as PnP, Bundle Adjustment or PoseGraph Optimization. For convenience, a copy of Ceres has been included in the Thirdparty folder. Note that Ceres dependencies are still required.

1.6 (Optional) OpenGV

OpenGV can be used for Multi-View-Geometry (MVG) operations. The results reported in the paper were obtained using OpenGV. For convenience, if OpenGV is not installed, MVG operations' alternatives are proposed with OpenCV functions.
Note that the performances might be lower without OpenGV.

2. Installation

2.0 Clone

Clone the git repository in your catkin workspace:

    cd ~/catkin_ws/src/
    git clone https://github.com/ov2slam/ov2slam.git

2.1 Build Thirdparty libs

For convenience we provide a script to build the Thirdparty libs:

    cd ~/catkin_ws/src/ov2slam
    chmod +x build_thirdparty.sh
    ./build_thirdparty.sh

WATCH OUT By default, the script builds obindex2, ibow-lcd, sophus and ceres. If you want to use your own version of Sophus or Ceres you can comment the related lines in the script. Yet, about Ceres, as OV²SLAM is by default compiled with the "-march=native" flag, the Ceres lib linked to OV²SLAM must be compiled with this flag as well, which is not the default case (at least since Ceres 2.0). The build_thirdparty.sh script ensures that Ceres builds with the "-march=native" flag.

If you are not interested in the Loop Closing feature of OV²SLAM, you can also comment the lines related to obindex2 and ibow-lcd.

(Optional) Install OpenGV:

    cd your_path/
    git clone https://github.com/laurentkneip/opengv
    cd opengv
    mkdir build
    cd build/
    cmake ..
    sudo make -j4 install

2.2 Build OV²SLAM

Build OV²SLAM package with your favorite catkin tool:

    cd ~/catkin_ws/src/ov2slam
    catkin build --this
    source ~/catkin_ws/devel/setup.bash

OR

    cd ~/catkin_ws/
    catkin_make --pkg ov2slam
    source ~/catkin_ws/devel/setup.bash

3. Usage

Run OV²SLAM using:

    rosrun ov2slam ov2slam_node parameter_file.yaml

Visualize OV²SLAM outputs in Rviz by loading the provided configuration file: ov2slam_visualization.rviz.

4. Miscellaneous

Supported Cameras Model

Both the Pinhole Rad-tan and Fisheye camera's models are supported. The models are OpenCV-based. If you use Kalibr for camera calibration, the equivalencies are:

  • OpenCV "Pinhole" -> Kalibr "Pinhole Radtan"
  • OpenCV "Fisheye" -> Kalibr "Pinhole Equidistant"

Extrinsic Calibration

The stereo extrinsic parameters in the parameter files are expected to represent the transformation from the camera frame to the body frame (T_body_cam \ X_body = T_body_cam * X_cam). Therefore, if T_body_camleft is set as the Identity transformation, for the right camera we have: T_body_camright = T_camleft_camright. In Kalibr, the inverse transformation is provided (i.e. T_cam_body). Yet, Kalibr also provide the extrinsic transformation of each camera w.r.t. to the previous one with the field T_cn_cnm1. This transformation can be directly used in OV²SLAM by setting T_body_camleft = T_cn_cnm1 and T_body_camright = I_4x4.

Parameters File Description

Three directories are proposed within the parameter_files folder: accurate, average and fast. They all store the parameter files to be used with KITTI, EuRoC and TartanAir.

  • The accurate folder provides the parameters as used in the paper for the full method (i.e. OV²SLAM w. LC).

  • The fast folder provides the parameters as used in the paper for the Fast version of OV²SLAM.

  • The average folder is provided for convenience as an in-between mode.

Parameters details:
* debug: display debugging information or not
* log_timings: log and display main functions timings or not

* mono: set to 1 if you are in mono config
* stereo: set to 1 if you are in stereo config

* force_realtime: set to 1 if you want to enforce real-time processing (i.e. only process last received image, even if it leads to dropping not yet processed images)

* slam_mode: must be set to 1

* buse_loop_closer: set to 1 if you want to use LC

* bdo_stereo_rect: set to 1 if you want to apply stereo rectification (and use epipolar lines for stereo matching)
* alpha: to be set between 0 and 1, 0: rectified images contain only valid pixel / 1: rectified images contain all original pixels (see OpenCV doc for more details)

* bdo_undist: set to 1 if you want to process undistorted images (the alpha parameter will be used in this case too)

* finit_parallax: amount of parallax expected for creating new keyframes (should be set between 15. and 40.)

* use_shi_tomasi: set to 1 to use OpenCV GFTT keypoints detector 
* use_fast: set to 1 to use OpenCV FAST keypoints detector
* use_brief: set to 1 to extract BRIEF descriptors from detected keypoints (must be set to 1 for apply local map matching, see below)
* use_singlescale_detector: set to 1 to use our keypoints detector based on OpenCV cornerMinEigenVal function

* nmaxdist: size of image cells for extracting keypoints (the bigger the less keypoints you will have)

* nfast_th: FAST detector threshold (the lower the more sensitive the detector is)
* dmaxquality: GFTT and cornerMinEigenVal detector threshold (the lower the more sensitive the detector is)

* use_clahe: set to 1 to apply CLAHE on processed images
* fclahe_val: strength of the CLAHE effect

* do_klt: must be set to 1
* klt_use_prior: if set to 1, keypoints which are observation of 3D Map Points will be initialized with a constant velocity motion model to get a prior before applying KLT tracking
* btrack_keyframetoframe: if set to 1, KLT will be applied between previous keyframe and current frame instead of previous frame and current frame (setting it to 0 usually leads to better accuracy)
* nklt_win_size: size of the pixels patch to be used in the KLT tracking
* nklt_pyr_lvl: number of pyramid levels to be used with KLT in addition the full resolution image (i.e. if set to 1, two levels will be used: half-resolution, full-resolution)

* nmax_iter: max number of iterations for KLT optimization
* fmax_px_precision: maximum precision seeked with KLT (i.e. solution is not varying more than this parameter)

* fmax_fbklt_dist: maximum allowed error in the backward KLT tracking
* nklt_err: maximum allowed error between KLT tracks

* bdo_track_localmap: set to 1 to use local map tracking using computed descriptors at each keyframe

* fmax_desc_dist: distance ratio w.r.t. descriptor size for considering a good match (to be set between 0 and 1)
* fmax_proj_pxdist: maximum distance in pixels between a map point projection and a keypoint to consider it as a matching candidate

* doepipolar: set to 1 to apply 2D-2D epipolar based filtering
* dop3p : set to 1 to use a P3P-RANSAC pose estimation
* bdo_random: set to 1 to randomize RANSAC
* nransac_iter: maximum number of RANSAC iterations allowed
* fransac_err: maximum error in pixels for RANSAC

* fmax_reproj_err: maximum reprojection error in pixels when triangulating new map points
* buse_inv_depth: set to 1 to use an anchored inverse depth parametrization in BundleAdjustment, set to 0 to use XYZ parametrization

* robust_mono_th: threshold to be used for the robust Huber cost function in BundleAdjustment

* use_sparse_schur: set to 1 to use sparse schur (recommanded) (see Ceres doc)
* use_dogleg: set to 1 to apply Dogleg optimization (see Ceres doc)
* use_subspace_dogleg: set to 1 to apply subspace Dogleg optimization (see Ceres doc)
* use_nonmonotic_step: set to 1 to allow nonmonotic steps in optimization (see Ceres doc)

* apply_l2_after_robust: set to 1 to re-optimize without the Huber function after removal of detected outliers in BundleAdjustment

* nmin_covscore: minimum covisibility score w.r.t. to current keyframe for adding a keyframe as a state to optimize in BundleAdjustment

* fkf_filtering_ratio: ratio of co-observed 3D map points by 4 other keyframes to consider a keyframe as redundant and remove it from the map

* do_full_ba: if set to 1, a final full BundleAdjustment will be applied once the sequence has been entirely processed

Note on "-march=native"

If you experience issues when running OV²SLAM (segfault exceptions, ...), it might be related to the "-march=native" flag. By default, OpenGV and OV²SLAM come with this flag enabled but Ceres does not. Making sure that all of them are built with or without this flag might solve your problem.

ov2slam's People

Contributors

ferreram avatar ov2slam 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  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

ov2slam's Issues

Cannot catkin_make undefined reference libov2slam.so

Hi all,

I'm trying to build ov2slam on a Jetson TX2 within ROS melodic. I got the following error when I try the command catkin_make --pkg ov2slam :

/usr/bin/ld: warning: libopencv_core.so.3.4, needed by /home/thomas/catkin_ws/devel/lib/libov2slam.so, may conflict with libopencv_core.so.3.2 /usr/bin/ld: warning: libopencv_imgproc.so.3.4, needed by /usr/local/lib/libopencv_calib3d.so.3.4, may conflict with libopencv_imgproc.so.3.2 CMakeFiles/ov2slam_node.dir/src/ov2slam_node.cpp.o: In function main':
ov2slam_node.cpp:(.text.startup+0xd78): undefined reference to cv::FileStorage::FileStorage(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, int, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)' ov2slam_node.cpp:(.text.startup+0xf64): undefined reference to cv::FileNode::stringabi:cxx11 const'
ov2slam_node.cpp:(.text.startup+0xff8): undefined reference to cv::FileNode::string[abi:cxx11]() const' /home/thomas/catkin_ws/devel/lib/libov2slam.so: undefined reference to cv::FileNode::operator float() const'
/home/thomas/catkin_ws/devel/lib/libov2slam.so: undefined reference to cv::ORB::create(int, float, int, int, int, int, cv::ORB::ScoreType, int, int)' /home/thomas/catkin_ws/devel/lib/libov2slam.so: undefined reference to cv::FileNode::operator int() const'
/home/thomas/catkin_ws/devel/lib/libov2slam.so: undefined reference to cv::FastFeatureDetector::create(int, bool, cv::FastFeatureDetector::DetectorType)' /home/thomas/catkin_ws/devel/lib/libov2slam.so: undefined reference to cv::FileNode::operator double() const'
/home/thomas/catkin_ws/devel/lib/libov2slam.so: undefined reference to cv::Formatter::get(cv::Formatter::FormatType)' collect2: error: ld returned 1 exit status ov2slam/CMakeFiles/ov2slam_node.dir/build.make:316: recipe for target '/home/thomas/catkin_ws/devel/lib/ov2slam/ov2slam_node' failed make[2]: *** [/home/thomas/catkin_ws/devel/lib/ov2slam/ov2slam_node] Error 1 CMakeFiles/Makefile2:510: recipe for target 'ov2slam/CMakeFiles/ov2slam_node.dir/all' failed make[1]: *** [ov2slam/CMakeFiles/ov2slam_node.dir/all] Error 2 Makefile:140: recipe for target 'all' failed make: *** [all] Error 2 Invoking "make -j4 -l4" failed

An idea where it could come from ?

Facing below issue while building

I am using

No LSB modules are available.
Distributor ID: Ubuntu
Description: Ubuntu 18.04.6 LTS
Release: 18.04
Codename: bionic

and ROS distribution melodic

i am following the steps as mentioned in the wiki.

` ./build_thirdparty.sh

Building Obindex2 lib!

-- The CXX compiler identification is GNU 7.5.0
-- Check for working CXX compiler: /usr/bin/c++
-- Check for working CXX compiler: /usr/bin/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Build type: Release
-- Setting Release options
-- Performing Test COMPILER_SUPPORTS_CXX11
-- Performing Test COMPILER_SUPPORTS_CXX11 - Success
-- Performing Test COMPILER_SUPPORTS_CXX0X
-- Performing Test COMPILER_SUPPORTS_CXX0X - Success
-- Using flag -std=c++11.
-- Found OpenCV: /usr (found version "3.2.0")
-- Boost version: 1.65.1
-- Found the following Boost libraries:
-- system
-- filesystem
-- Found OpenMP_CXX: -fopenmp (found version "4.5")
-- Found OpenMP: TRUE (found version "4.5")
-- Compiler flags: -Wall -O3 -march=native -std=c++11 -fopenmp
-- Configuring done
-- Generating done
-- Build files have been written to: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/obindex2/build
Scanning dependencies of target obindex2
[ 80%] Building CXX object lib/CMakeFiles/obindex2.dir/src/binary_tree_node.cc.o
[ 80%] Building CXX object lib/CMakeFiles/obindex2.dir/src/binary_index.cc.o
[ 80%] Building CXX object lib/CMakeFiles/obindex2.dir/src/binary_descriptor.cc.o
[ 80%] Building CXX object lib/CMakeFiles/obindex2.dir/src/binary_tree.cc.o
[100%] Linking CXX shared library libobindex2.so
[100%] Built target obindex2

Building iBoW-LCD lib!

-- The CXX compiler identification is GNU 7.5.0
-- Check for working CXX compiler: /usr/bin/c++
-- Check for working CXX compiler: /usr/bin/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Build type: Release
-- Setting Release options
-- Performing Test COMPILER_SUPPORTS_CXX11
-- Performing Test COMPILER_SUPPORTS_CXX11 - Success
-- Performing Test COMPILER_SUPPORTS_CXX0X
-- Performing Test COMPILER_SUPPORTS_CXX0X - Success
-- Using flag -std=c++11.
-- Compiler flags: -Wall -O3 -march=native -std=c++11
-- Found OpenCV: /usr (found version "3.2.0")
-- Boost version: 1.65.1
-- Found the following Boost libraries:
-- system
-- filesystem
-- Found OpenMP_CXX: -fopenmp (found version "4.5")
-- Found OpenMP: TRUE (found version "4.5")
-- Configuring done
-- Generating done
-- Build files have been written to: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/ibow_lcd/build
Scanning dependencies of target lcdetector
[ 50%] Building CXX object CMakeFiles/lcdetector.dir/src/lcdetector.cc.o
/home/amjad/catkin_ws/src/ov2slam/Thirdparty/ibow_lcd/src/lcdetector.cc: In member function ‘void ibow_lcd::LCDetector::process(unsigned int, const std::vectorcv::KeyPoint&, const cv::Mat&, ibow_lcd::LCDetectorResult*)’:
/home/amjad/catkin_ws/src/ov2slam/Thirdparty/ibow_lcd/src/lcdetector.cc:132:8: warning: unused variable ‘overlap’ [-Wunused-variable]
bool overlap = island.overlaps(last_lc_island_);
^~~~~~~
[100%] Linking CXX shared library liblcdetector.so
[100%] Built target lcdetector

Building Sophus lib!

-- The C compiler identification is GNU 7.5.0
-- The CXX compiler identification is GNU 7.5.0
-- Check for working C compiler: /usr/bin/cc
-- Check for working C compiler: /usr/bin/cc -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Detecting C compile features
-- Detecting C compile features - done
-- Check for working CXX compiler: /usr/bin/c++
-- Check for working CXX compiler: /usr/bin/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Found Eigen3: /usr/include/eigen3 (Required is at least version "3.3.0")
-- Configuring done
-- Generating done
-- Build files have been written to: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/build
Install the project...
-- Install configuration: "Release"
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/share/sophus/cmake/SophusTargets.cmake
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/share/sophus/cmake/SophusConfig.cmake
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/share/sophus/cmake/SophusConfigVersion.cmake
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/average.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/common.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/geometry.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/interpolate.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/interpolate_details.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/num_diff.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/rotation_matrix.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/rxso2.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/rxso3.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/se2.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/se3.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/sim2.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/sim3.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/sim_details.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/so2.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/so3.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/types.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/velocities.hpp
-- Installing: /home/amjad/catkin_ws/src/ov2slam/Thirdparty/Sophus/install/include/sophus/formatstring.hpp

Building Ceres lib!

-- The C compiler identification is GNU 7.5.0
-- The CXX compiler identification is GNU 7.5.0
-- Check for working C compiler: /usr/bin/cc
-- Check for working C compiler: /usr/bin/cc -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Detecting C compile features
-- Detecting C compile features - done
-- Check for working CXX compiler: /usr/bin/c++
-- Check for working CXX compiler: /usr/bin/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Detected Ceres version: 2.0.0 from /home/amjad/catkin_ws/src/ov2slam/Thirdparty/ceres-solver/include/ceres/version.h
-- Detected available Ceres threading models: [CXX_THREADS, OPENMP, NO_THREADS]
-- Building with C++14
-- Found Eigen version 3.3.4: /usr/include/eigen3
-- Enabling use of Eigen as a sparse linear algebra library.
-- Looking for sgemm_
-- Looking for sgemm_ - found
-- Looking for pthread.h
-- Looking for pthread.h - found
-- Looking for pthread_create
-- Looking for pthread_create - not found
-- Looking for pthread_create in pthreads
-- Looking for pthread_create in pthreads - not found
-- Looking for pthread_create in pthread
-- Looking for pthread_create in pthread - found
-- Found Threads: TRUE
-- A library with BLAS API found.
-- Found LAPACK library: /usr/lib/x86_64-linux-gnu/liblapack.so;/usr/lib/x86_64-linux-gnu/libblas.so
-- A library with BLAS API found.
-- Failed to find SuiteSparse - Did not find AMD header (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find AMD library (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find CAMD header (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find CAMD library (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find COLAMD header (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find COLAMD library (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find CCOLAMD header (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find CCOLAMD library (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find CHOLMOD header (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find CHOLMOD library (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find SUITESPARSEQR header (required SuiteSparse component).
-- Failed to find SuiteSparse - Did not find SUITESPARSEQR library (required SuiteSparse component).
-- Did not find SUITESPARSE_CONFIG header (optional SuiteSparse component).
-- Did not find SUITESPARSE_CONFIG library (optional SuiteSparse dependency)
-- Did not find UFCONFIG header (optional SuiteSparse component).
-- Failed to find SuiteSparse - Failed to find either: SuiteSparse_config header & library (should be present in all SuiteSparse >= v4 installs), or UFconfig header (should be present in all SuiteSparse < v4 installs).
-- Did not find METIS library (optional SuiteSparse dependency)
-- Failed to find some/all required components of SuiteSparse. (missing: AMD_FOUND CAMD_FOUND COLAMD_FOUND CCOLAMD_FOUND CHOLMOD_FOUND SUITESPARSEQR_FOUND SUITESPARSE_VERSION)
-- Did not find all SuiteSparse dependencies, disabling SuiteSparse support.
-- Failed to find CXSparse - Could not find CXSparse include directory, set CXSPARSE_INCLUDE_DIR to directory containing cs.h
-- Did not find CXSparse, Building without CXSparse.
-- Building without Apple's Accelerate sparse support.
CMake Warning at CMakeLists.txt:392 (find_package):
By not providing "Findgflags.cmake" in CMAKE_MODULE_PATH this project has
asked CMake to find a package configuration file provided by "gflags", but
CMake did not find one.

Could not find a package configuration file provided by "gflags" (requested
version 2.2.0) with any of the following names:

gflagsConfig.cmake
gflags-config.cmake

Add the installation prefix of "gflags" to CMAKE_PREFIX_PATH or set
"gflags_DIR" to a directory containing one of the above files. If "gflags"
provides a separate development package or SDK, be sure it has been
installed.

-- Did not find Google Flags (gflags), Building without gflags.
-- Use of gflags disabled - no tests or tools will be built!
-- No preference for use of exported glog CMake configuration set, and no hints for include/library directories provided. Defaulting to preferring an installed/exported glog CMake configuration if available.
-- Failed to find installed glog CMake configuration, searching for glog build directories exported with CMake.
-- Failed to find an installed/exported CMake configuration for glog, will perform search for installed glog components.
-- Failed to find glog - Could not find glog include directory, set GLOG_INCLUDE_DIR to directory containing glog/logging.h
CMake Error at CMakeLists.txt:432 (message):
Can't find Google Log (glog). Please set either: glog_DIR (newer CMake
built versions of glog) or GLOG_INCLUDE_DIR & GLOG_LIBRARY or enable
MINIGLOG option to use minimal glog implementation.

-- Configuring incomplete, errors occurred!
See also "/home/amjad/catkin_ws/src/ov2slam/Thirdparty/ceres-solver/build/CMakeFiles/CMakeOutput.log".
See also "/home/amjad/catkin_ws/src/ov2slam/Thirdparty/ceres-solver/build/CMakeFiles/CMakeError.log".
make: *** No rule to make target 'install'. Stop. `

how to solve the above glog issue

thanks in advance

OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray

When I run 'rosbag play MH_04_difficult.bag', the question like that:

rex@rex:~/OV2_ws$ rosrun ov2slam ov2slam_node src/ov2slam/parameters_files/accurate/euroc/euroc_mono.yaml

Launching OV²SLAM...

Loading parameters file : src/ov2slam/parameters_files/accurate/euroc/euroc_mono.yaml...

Parameters file loaded...

SLAM Parameters are being setup...

ROS visualizer is being created...

SLAM Manager is being created...

OPENCV CONTRIB NOT FOUND! ORB DESCRIPTOR WILL BE USED!

OPENGV FOUND! OPENGV MVG FUNCTIONS WILL BE USED!

SetupCalibration()

Setting up camera, model selected : pinhole

Pinhole Camera Model created

Camera Calibration set as :

K =
458.654 0 367.215
0 457.296 248.375
0 0 1

D = -0.283408 0.0739591 0.00019359 1.76187e-05
opt K =
[458.654, 0, 367.215;
0, 457.296, 248.375;
0, 0, 1]


Feature Extractor is constructed!

Maximum nb of kps : 308
Maximum kps dist : 35
Minimum kps dist : 17
Maximum kps qual : 0.001
Minimum kps qual : 0.0005


Optimizer Object is created!

Estimator Object is created!

Optimizer Object is created!

LoopCloser Object is created!

Mapper Object is created!

Mapper is ready to process Keyframes!

Sensors Grabber is created...

OV²SLAM is ready to process incoming images!

Estimator is ready to process Keyframes!

Use LoopCLoser : 0
Starting the measurements reader thread!
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
OpenCV Error: Assertion failed (isIdentity(expr)) in _InputArray, file /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp, line 1843
terminate called after throwing an instance of 'cv::Exception'
what(): /home/rex/opencv-3.4.14/modules/core/src/matrix_expressions.cpp:1843: error: (-215) isIdentity(expr) in function _InputArray

Stack trace (most recent call last) in thread 28383:
#18 Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in
#17 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f590008671e, in clone
#16 Object "/lib/x86_64-linux-gnu/libpthread.so.0", at 0x7f5900f0c6da, in
#15 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f590062b6de, in
#14 Object "/home/rex/OV2_ws/devel/lib/libov2slam.so", at 0x7f590224ed0a, in SlamManager::run()
#13 Object "/home/rex/OV2_ws/devel/lib/libov2slam.so", at 0x7f590226a12c, in VisualFrontEnd::visualTracking(cv::Mat&, double)
#12 Object "/home/rex/OV2_ws/devel/lib/libov2slam.so", at 0x7f59022931aa, in MapManager::createKeyframe(cv::Mat const&, cv::Mat const&)
#11 Object "/home/rex/OV2_ws/devel/lib/libov2slam.so", at 0x7f5902292c3f, in MapManager::extractKeypoints(cv::Mat const&, cv::Mat const&)
#10 Object "/home/rex/OV2_ws/devel/lib/libov2slam.so", at 0x7f5902287bd3, in FeatureExtractor::detectSingleScale(cv::Mat const&, int, std::vector<cv::Point_, std::allocator<cv::Point_ > > const&, cv::Rect_ const&)
#9 Object "/usr/lib/x86_64-linux-gnu/libopencv_core.so.3.2", at 0x7f5901c71fff, in cv::parallel_for_(cv::Range const&, cv::ParallelLoopBody const&, double)
#8 Object "/usr/lib/x86_64-linux-gnu/libtbb.so.2", at 0x7f58fca8678f, in
#7 Object "/usr/lib/x86_64-linux-gnu/libtbb.so.2", at 0x7f58fca89e9a, in
#6 Object "/usr/lib/x86_64-linux-gnu/libtbb.so.2", at 0x7f58fca84d0b, in
#5 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f5900600ad9, in std::rethrow_exception(std::__exception_ptr::exception_ptr)
#4 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f5900600b20, in std::terminate()
#3 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f5900600ae5, in
#2 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f59005fa956, in
#1 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f58fffa5920, in abort
#0 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f58fffa3fb7, in gsignal
Aborted (Signal sent by tkill() 28354 1000)

Segmentation fault while running (Address not mapped to object)

Hi,
Firstly thanks for sharing your project for others to learn from. After successfully building the code as per instructions im facing this error while running it.
My environment is:
ubuntu 18.04,
ros melodic 1.14.12,
opencv 4.5.5,
eigen 3.3.4
opengv
ceres 2.0

I have already tried building opengv, ceres and ov2slam with turning off --march native but the same error persisted. Any suggestion would be highly appreciated. Thanks..:)

the error:
`[100%] Linking CXX executable /mnt/HD1/maazshare2/slam/Catkinov2slam/devel/lib/ov2slam/ov2slam_node
/usr/bin/ld: warning: libopencv_core.so.405, needed by /maazshare2/slam/Catkinov2slam/devel/lib/libov2slam.so, may conflict with libopencv_core.so.3.2
[100%] Built target ov2slam_node
maaz@maaz:/maazshare2/slam/Catkinov2slam$ source /maazshare2/slam/Catkinov2slam/devel/setup.bash
maaz@maaz:/maazshare2/slam/Catkinov2slam$ rosrun ov2slam ov2slam_node /maazshare2/slam/Catkinov2slam/src/ov2slam/parameters_files/accurate/kitti/kitti_00-02.yaml

Launching OV²SLAM...

Loading parameters file : /maazshare2/slam/Catkinov2slam/src/ov2slam/parameters_files/accurate/kitti/kitti_00-02.yaml...

Parameters file loaded...

SLAM Parameters are being setup...
Stack trace (most recent call last):
#14 Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in
#13 Object "/maazshare2/slam/Catkinov2slam/devel/lib/ov2slam/ov2slam_node", at 0x55b6f64350c9, in _start
#12 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f79fd4f7bf6, in __libc_start_main
#11 Object "/maazshare2/slam/Catkinov2slam/devel/lib/ov2slam/ov2slam_node", at 0x55b6f643562a, in main
#10 Object "/maazshare2/slam/Catkinov2slam/devel/lib/libov2slam.so", at 0x7f79ff3e645c, in SlamParams::SlamParams(cv::FileStorage const&)
#9 Object "/usr/local/lib/libopencv_core.so.405", at 0x7f79f9f28e38, in cv::FileNode::operator int() const
#8 Object "/usr/local/lib/libopencv_core.so.405", at 0x7f79f9f27d2d, in cv::FileStorage::Impl::getNodePtr(unsigned long, unsigned long) const
#7 Object "/usr/local/lib/libopencv_core.so.405", at 0x7f79f9f70ae9, in cv::error(int, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&, char const*, char const*, int)
#6 Object "/usr/local/lib/libopencv_core.so.405", at 0x7f79f9f708c9, in cv::Exception::Exception(int, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&, int)
#5 Object "/usr/lib/x86_64-linux-gnu/libopencv_core.so.3.2", at 0x7f79fea14e2b, in cv::Exception::formatMessage()
#4 Object "/usr/lib/x86_64-linux-gnu/libopencv_core.so.3.2", at 0x7f79fea14c4d, in cv::format(char const*, ...)
#3 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f79fd607ff8, in __vsnprintf_chk
#2 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f79fd532db9, in _IO_vfprintf
#1 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f79fd530b44, in
#0 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f79fd6644e1, in
Segmentation fault (Address not mapped to object [0x1e])
Segmentation fault (core dumped)`

*Note: On debugging the error comes while reading from the parameter file in slam_params.cpp:
debug_ = static_cast<int>(fsSettings["debug"]);;

Getting to work with CARLA Simulator

Hello devs,

I am trying to get the slam work with CARLA Simulator and I have defined the parameter file (simulation.yaml in avarage folder) as follows. Other params are same as KITTI. I have camera FPS at 20Hz in Simulator.

Camera.topic_left: /carla/ego_vehicle/rgb_left/image
Camera.topic_right: /carla/ego_vehicle/rgb_right/image

Camera.model_left: pinhole
Camera.model_right: pinhole

Camera.left_nwidth: 1241
Camera.left_nheight: 376

Camera.right_nwidth: 1241
Camera.right_nheight: 376

# Camera calibration and distortion parameters (OpenCV) 
Camera.fxl: 854.0449816523632
Camera.fyl: 854.0449816523632
Camera.cxl: 620.5
Camera.cyl: 188.0

Camera.k1l: 0.
Camera.k2l: 0.
Camera.p1l: 0.
Camera.p2l: 0.

Camera.fxr: 854.0449816523632
Camera.fyr: 854.0449816523632
Camera.cxr: 620.5
Camera.cyr: 188.0

Camera.k1r: 0.
Camera.k2r: 0.
Camera.p1r: 0.
Camera.p2r: 0.


// Camera Extrinsic parameters T_b_ci ( v_b = T_b_ci * v_ci )
body_T_cam0: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [1., 0., 0., 0.,
          0., 1., 0., 0.,
          0., 0., 1., 0.,
           0., 0., 0., 1.]

body_T_cam1: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [1., 0., 0., 0.06,
          0., 1., 0., 0.,
          0., 0., 1., 0.,
           0., 0., 0., 1.]
``

terminate called after throwing an instance of 'cv::Exception'
  what():  OpenCV(4.2.0) ../modules/video/src/lkpyramid.cpp:1391: error: (-215:Assertion failed) prevPyr[level * lvlStep1].size() == nextPyr[level * lvlStep2].size() in function 'calc'

Stack trace (most recent call last) in thread 307701:
#16   Object "", at 0xffffffffffffffff, in 
BFD: DWARF error: section .debug_info is larger than its filesize! (0x93ef57 vs 0x530ea0)
#15   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fa5bcebb132, in clone
#14   Source "/build/glibc-SzIz7B/glibc-2.31/nptl/pthread_create.c", line 477, in start_thread [0x7fa5bd3ad608]
#13   Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7fa5bd081de3, in std::error_code::default_error_condition() const
#12   Source "/home/sxv1kor/OV2SLAM/catkin_ws/src/ov2slam/src/mapper.cpp", line 83, in Mapper::run() [0x7fa5bd9248a6]
         80:                 std::vector<cv::Mat> vpyr_imright;
         81:                 cv::buildOpticalFlowPyramid(imright, vpyr_imright, pslamstate_->klt_win_size_, pslamstate_->nklt_pyr_lvl_);
         82: 
      >  83:                 pmap_->stereoMatching(*pnewkf, kf.vpyr_imleft_, vpyr_imright);
         84:                 
         85:                 if( pnewkf->nb2dkps_ > 0 && pnewkf->nb_stereo_kps_ > 0 ) {
#11   Source "/home/sxv1kor/OV2SLAM/catkin_ws/src/ov2slam/src/map_manager.cpp", line 550, in MapManager::stereoMatching(Frame&, std::vector<cv::Mat, std::allocator<cv::Mat> > const&, std::vector<cv::Mat, std::allocator<cv::Mat> > const&) [0x7fa5bd915cf1]
        547:         // Good / bad kps vector
        548:         std::vector<bool> vkpstatus;
        549: 
      > 550:         ptracker_->fbKltTracking(
        551:                     vleftpyr, 
        552:                     vrightpyr, 
        553:                     pslamstate_->nklt_win_size_, 
#10   Source "/home/sxv1kor/OV2SLAM/catkin_ws/src/ov2slam/src/feature_tracker.cpp", line 66, in FeatureTracker::fbKltTracking(std::vector<cv::Mat, std::allocator<cv::Mat> > const&, std::vector<cv::Mat, std::allocator<cv::Mat> > const&, int, int, float, float, std::vector<cv::Point_<float>, std::allocator<cv::Point_<float> > >&, std::vector<cv::Point_<float>, std::allocator<cv::Point_<float> > >&, std::vector<bool, std::allocator<bool> >&) const [0x7fa5bd910db2]
         63:     vkpsidx.reserve(nbkps);
         64: 
         65:     // Tracking Forward
      >  66:     cv::calcOpticalFlowPyrLK(vprevpyr, vcurpyr, vkps, vpriorkps, 
         67:                 vstatus, verr, klt_win_size,  nbpyrlvl, klt_convg_crit_, 
         68:                 (cv::OPTFLOW_USE_INITIAL_FLOW + cv::OPTFLOW_LK_GET_MIN_EIGENVALS) 
         69:                 );

Poor performance on KITTI dataset using monocular camera

Hi,

I am getting poor results while running the monocular OV2SLAM on KITTI sequence 00. I am using the provided accurate configuration kitti_00-02.yaml

Here is a screenshot from the final trajectory obtained with OpenGV and with OpenCV Contrib.
image

erminate called after throwing an instance of 'std::out_of_range' what(): _Map_base::at

Hi, when I run rosbag, I have this issue. But there's no issue, if I just run ov2slam.
There is the issue .
#0 __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:51
#1 0x00007ffff45b1921 in __GI_abort () at abort.c:79
#2 0x00007ffff4c06957 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#3 0x00007ffff4c0cae6 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#4 0x00007ffff4c0cb21 in std::terminate() ()
from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#5 0x00007ffff4c0cd54 in __cxa_throw ()
from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#6 0x00007ffff4c08837 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#7 0x00007ffff75b6b53 in std::__detail::_Map_base<int, std::pair<int const, std::shared_ptr >, std::allocator<std::pair<int const, std::shared_ptr > >, std::__detail::_Select1st, std::equal_to, std::hash, std::__detail::_Mod_range_hashing, std::__detail::_Default_ranged_hash, std::__detail::_Prime_rehash_policy, std::__detail::_Hashtable_traits<false, false, true>, true>::at (this=0x5555562bd360, __k=@0x5555562b3174: 0)
at /usr/include/c++/7/bits/hashtable_policy.h:774
#8 0x00007ffff75af04b in std::unordered_map<int, std::shared_ptr, std::hash, std::equal_to, std::allocator<std::pair<int const, std::shared_ptr > > >::at (this=0x5555562bd360, __k=@0x5555562b3174: 0)
at /usr/include/c++/7/bits/unordered_map.h:990
#9 0x00007ffff75df760 in VisualFrontEnd::epipolar2d2dFiltering (
this=0x5555565cb530)
at /home/zxn/install/my_slam_ws/src/my_slam/src/visual_front_end.cpp:530

Without ROS?

Hi! And thanks for making this code available. Is it technically possible to run it on Windows, without ROS?

Thanks!

Error: R is not orthogonal

Hello,

I'm trying to run OV2SLAM with an Intel Realsense T265, but I'm facing an issue with my yaml file. As you can see below, I set the camera model as fisheye and complete the file according to the parameters I got with the command : rs-enumerate-devices -c

I also set the extrinsic parameters according to the transformation between the left and the right fisheye cameras.

#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.topic_left: /camera/fisheye1/image_raw
Camera.topic_right: /camera/fisheye2/image_raw

Camera.model_left: fisheye
Camera.model_right: fisheye

Camera.left_nwidth: 848
Camera.left_nheight: 800

Camera.right_nwidth: 848
Camera.right_nheight: 800

# Camera calibration and distortion parameters
Camera.fxl: 287.854705810547
Camera.fyl: 287.795593261719
Camera.cxl: 426.878387451172
Camera.cyl: 400.959686279297

Camera.k1l: -0.0112883998081088
Camera.k2l: 0.0493851415812969
Camera.p1l: -0.0468114204704762
Camera.p2l: 0.00931846909224987

Camera.fxr: 287.768005371094
Camera.fyr: 287.635314941406
Camera.cxr: 421.719085693359
Camera.cyr: 394.745513916016

Camera.k1r: -0.0121076302602887
Camera.k2r: 0.0504187308251858
Camera.p1r: -0.0474353283643723
Camera.p2r: 0.00939208921045065

# Camera Extrinsic parameters T_b_ci ( v_b = T_b_ci * v_ci )
body_T_cam0: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data:  [0.99998, -0.000684938, 0.00627555, 0.0637358278036118,
           0.000680629, 1.0    , 0.000688822, -0.000107772735645995,
          -0.00627602, -0.000684538 , 0.99998, -0.000309090450173244,
          0.0, 0.0, 0.0, 1.0]

body_T_cam1: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [1., 0., 0., 0,
          0., 1., 0., 0,
          0., 0., 1., 0,
          0., 0., 0., 1.]

OV2SLAM has been built successfully, and it actually runs with the different euroc yaml files. But when I try to use my yaml file it gives me an error with Sophus :

error_ov2

Has somebody else encounter this error, please ? I really don't know what is the origin of this issue and how to fix that

Thank you

Rviz visualization

Hello,

"Visualize OV²SLAM outputs in Rviz by loading the provided configuration file: ov2slam_visualization.rviz."

Can you please update the read me with the corresponding command, it would be helpful.

Thank you
Gopi

IMU initial guess about orientation

Hi there,

I really adore this project!! So far it runs fine. Since I want to run it on a quadcopter next, I need the right orientations in 3D space. My plan is to use the IMU just for an initial guess about pitch/roll orientation and heading. Where in the code (which files) can I implement this? Where does ov2slam initialize this?

The problem, is that the trajectory is not right aligned with the x y grid. Also, the camera is tilted down a bit.

Screenshot from 2021-06-12 17-57-44

Thanks!
Best regards,
Tom

Crash after initialization due to wrong OpenCV version (solved)

Hi, thanks for the work.

The program crashes after initialization. All dependencies are built with the build_thirdparty.sh script.
Built using catkin_make

Here is the output:

rosrun ov2slam ov2slam_node src/ov2slam/parameters_files/accurate/kitti/kitti_00-02.yaml

Launching OV²SLAM...

Loading parameters file : src/ov2slam/parameters_files/accurate/kitti/kitti_00-02.yaml...

Parameters file loaded...

SLAM Parameters are being setup...

ROS visualizer is being created...

SLAM Manager is being created...

OPENCV CONTRIB FOUND! BRIEF DESCRIPTOR WILL BE USED!

OPENGV FOUND! OPENGV MVG FUNCTIONS WILL BE USED!

SetupCalibration()

Setting up camera, model selected : pinhole

Pinhole Camera Model created

Camera Calibration set as :

K =
718.856 0 607.193
0 718.856 185.216
0 0 1

D = 0 0 0 0
opt K =
[718.856, 0, 607.1928;
0, 718.856, 185.2157;
0, 0, 1]


Feature Extractor is constructed!

Maximum nb of kps : 396
Maximum kps dist : 35
Minimum kps dist : 17
Maximum kps qual : 0.001
Minimum kps qual : 0.0005


Optimizer Object is created!

Estimator Object is created!

Optimizer Object is created!

LoopCloser Object is created!

Mapper Object is created!

Mapper is ready to process Keyframes!

Sensors Grabber is created...

OV²SLAM is ready to process incoming images!

Estimator is ready to process Keyframes!

Use LoopCLoser : 1
LoopCloser is ready to process Keyframes!

Starting the measurements reader thread!

>>> Init current parallax (11.2527 px)
  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (21.1859 px)

    5-pt EssentialMatrix Ransac :
    nb pts : 240 / avg. parallax : 24.3881 / nransac_iter_ : 100 / fransac_err_ : 3 / bdo_random : 1

    Epipolar nb outliers : 1
    Essential Mat init : -0.00208749 -0.00138448 0.249987
    Essential Mat Intialization run time : 11[ms]

WARNING: Logging before InitGoogleLogging() is written to STDERR
E0405 23:14:52.941429 17590 solver.cc:531] Terminating: Invalid configuration. Solver::Options::eta = 0. Violated constraint: Solver::Options::eta > 0.0
E0405 23:14:52.941587 17590 solver.cc:531] Terminating: Invalid configuration. Solver::Options::eta = 0. Violated constraint: Solver::Options::eta > 0.0
free(): invalid size
Aborted (core dumped)

Feeding a known position for optimization

I was wondering if it was possible to feed a known position (e.g. determined from an aruco marker) into the optimizer in order to reduce drift and help with re-localization.

Problem with the code

Hi, there are some problem with the launch, could you please help me to run the code.
The command when I run the code is:

 rosrun ov2slam ov2slam_node src/ov2slam/parameters_files/accurate/kitti/kitti_00-02.yaml 

and the kitti rosbag topic is:

/clock
/kitti/camera_color_left/camera_info
/kitti/camera_color_left/image_rect
/kitti/camera_color_right/camera_info
/kitti/camera_color_right/image_rect
/ov2slam_node/cam_pose_visual
/ov2slam_node/final_kfs_traj
/ov2slam_node/image_track
/ov2slam_node/kfs_traj
/ov2slam_node/local_kfs_window
/ov2slam_node/point_cloud
/ov2slam_node/vo_pose
/ov2slam_node/vo_traj
/rosout
/rosout_agg
/tf

But I met the error:

OpenCV Error: Assertion failed (!fixedType() || ((Mat*)obj)->type() == mtype) in create, file /build/opencv-L2vuMj/opencv-3.2.0+dfsg/modules/core/src/matrix.cpp, line 2246
terminate called after throwing an instance of 'cv::Exception'
  what():  /build/opencv-L2vuMj/opencv-3.2.0+dfsg/modules/core/src/matrix.cpp:2246: error: (-215) !fixedType() || ((Mat*)obj)->type() == mtype in function create

Could you please give me some advice about that?

[Visual-Front-End]: Not ready to init yet!

Hello,

I am working on very high speed dataset, which is of 10,000 fps, so parallax is very less. In this case, thread is not going forward as it says continually,
[Visual-Front-End]: Not ready to init yet!

I tried reducing, finit_parallax parameter, then it is running but the trajectory is not correct.

What are the available options to successfully run ov2slam on very high speed dataset? Your suggestion in this regard are highly appreciated.

Thank you
Gopi

terminate called after throwing an instance of std::out_of_range

Hi, I am trying to run ov2slam with a camera. Initially, ov2slam can start with no problems, but it crashes when I make even the smallest movements. I am using a stereo camera and the frames are in grayscale. I hope you can guide me in rectifying this issue.

I have tried using the accurate, average, and fast parameter files.

Launching OV²SLAM...

Loading parameters file : /home/leanne/catkin_ws/src/ov2slam/parameters_files/accurate/kitti/kitti_00-02.yaml...

Parameters file loaded...

SLAM Parameters are being setup...

ROS visualizer is being created...

SLAM Manager is being created...

OPENCV CONTRIB NOT FOUND! ORB DESCRIPTOR WILL BE USED!

OPENGV FOUND! OPENGV MVG FUNCTIONS WILL BE USED!

SetupCalibration()

Setting up camera, model selected : pinhole

Pinhole Camera Model created

Camera Calibration set as :

K =
698.185 0 641.895
0 698.185 376.483
0 0 1

D = 0.176145 0.0290398 0.00101602 0.000205553
opt K =
[698.1849999999999, 0, 641.895;
0, 698.1849999999999, 376.4835;
0, 0, 1]


Feature Extractor is constructed!

Maximum nb of kps : 396
Maximum kps dist : 35
Minimum kps dist : 17
Maximum kps qual : 0.001
Minimum kps qual : 0.0005


Optimizer Object is created!

Estimator Object is created!

Optimizer Object is created!

LoopCloser Object is created!

Mapper Object is created!

Mapper is ready to process Keyframes!

Sensors Grabber is created...

OV²SLAM is ready to process incoming images!

Use LoopCLoser : 1
LoopCloser is ready to process Keyframes!

Estimator is ready to process Keyframes!

Starting the measurements reader thread!

=======================================================================
BRIEF CANNOT BE USED ACCORDING TO CMAKELISTS (Opencv Contrib not enabled)
ORB WILL BE USED BriefDescriptorExtractor! (BUT NO ROTATION OR SCALE INVARIANCE ENABLED)

=======================================================================
.
.
.
.
.

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.48992 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.45592 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.313045 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (5.15133 px)

terminate called after throwing an instance of 'std::out_of_range'
what(): vector::_M_range_check: __n (which is 423) >= this->size() (which is 396)
Aborted (core dumped)

Thank you! Apologies if it is basic question.

terminate called after throwing an instance of 'std::out_of_range'

Hi,

I always get the following error at some random frame on a specific dataset I'm using. I haven't modified any of the relevant functions in VisualFrontEnd. The dataset is quite large with 10,400 stereo images and resolution of 1006x597px (resized from 2013x1195px). Alternatively, if the error doesn't pop in the beginning or middle of the trajectory, the algorithm slows down considerably and freezes the computer, requiring a forced reboot. Any idea what could be the cause?


terminate called after throwing an instance of 'std::out_of_range'
what(): _Map_base::at
Stack trace (most recent call last) in thread 46957:
#14 Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in
#13 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f73f06d9292, in clone
#12 Object "/lib/x86_64-linux-gnu/libpthread.so.0", at 0x7f73f0bc9608, in
#11 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f73f089ade3, in
#10 Object "/home/kamijolab/catkin_ws/devel/lib/libov2slam.so", at 0x7f73f111b2c8, in SlamManager::run()
#9 Object "/home/kamijolab/catkin_ws/devel/lib/libov2slam.so", at 0x7f73f1136795, in VisualFrontEnd::visualTracking(cv::Mat&, double)
#8 Object "/home/kamijolab/catkin_ws/devel/lib/libov2slam.so", at 0x7f73f11362e4, in VisualFrontEnd::trackMono(cv::Mat&, double)
#7 Object "/home/kamijolab/catkin_ws/devel/lib/libov2slam.so", at 0x7f73f11323ae, in VisualFrontEnd::kltTracking()
#6 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f73f086537d, in std::__throw_out_of_range(char const*)
#5 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f73f086e6a8, in __cxa_throw
#4 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f73f086e3f6, in std::terminate()
#3 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f73f086e38b, in
#2 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f73f0862910, in
#1 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f73f05dc858, in abort
#0 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f73f05fd18b, in gsignal
Aborted (Signal sent by tkill() 46938 1000)

How to install ros-distro-pcl-ros and rosdep ov2slam

I flow this step run on ubuntu 16.04 ,i installed ros kinetic,

  1. Prerequisites Make sure that the pcl_ros package is installed :

    sudo apt install ros-distro-pcl-ros
    or even
    rosdep install ov2slam

How to install ros-distro-pcl-ros and ov2slam,because I am not found ppa source

Datasets

Dear developers:)
After studying your framework and the article about it for the possibility of using it on low-cost platforms a question about datasets came up.
The article says that you evaluate OV2SLAM on the benchmarking datasets EuRoC and KITTI. Is it possible in this case to use datasets obtained only from cameras, without using special sensors, which require EuRoC and KITTI?

Thanks a lot in advance.

Facing below issue while building Ov2SLAM Need help

[ 18%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/feature_extractor.cpp.o
/home/rti/catkin_ws/src/ov2slam/src/feature_extractor.cpp:44:9: error: redefinition of ‘class cv::ParallelLoopBodyLambdaWrapper’
class ParallelLoopBodyLambdaWrapper : public ParallelLoopBody
^~~~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/local/include/opencv2/core.hpp:3294:0,
from /home/rti/catkin_ws/src/ov2slam/include/frame.hpp:40,
from /home/rti/catkin_ws/src/ov2slam/include/feature_extractor.hpp:29,
from /home/rti/catkin_ws/src/ov2slam/src/feature_extractor.cpp:27:
/usr/local/include/opencv2/core/utility.hpp:584:7: note: previous definition of ‘class cv::ParallelLoopBodyLambdaWrapper’
class ParallelLoopBodyLambdaWrapper : public ParallelLoopBody
^~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/rti/catkin_ws/src/ov2slam/src/feature_extractor.cpp: In function ‘void cv::parallel_for_(const cv::Range&, std::function<void(const cv::Range&)>, double)’:
/home/rti/catkin_ws/src/ov2slam/src/feature_extractor.cpp:58:15: error: redefinition of ‘void cv::parallel_for_(const cv::Range&, std::function<void(const cv::Range&)>, double)’
inline void parallel_for_(const cv::Range& range, std::function<void(const cv::Range&)> functor, double nstripes=-1.)
^~~~~~~~~~~~~
In file included from /usr/local/include/opencv2/core.hpp:3294:0,
from /home/rti/catkin_ws/src/ov2slam/include/frame.hpp:40,
from /home/rti/catkin_ws/src/ov2slam/include/feature_extractor.hpp:29,
from /home/rti/catkin_ws/src/ov2slam/src/feature_extractor.cpp:27:
/usr/local/include/opencv2/core/utility.hpp:599:13: note: ‘void cv::parallel_for_(const cv::Range&, std::function<void(const cv::Range&)>, double)’ previously defined here
inline void parallel_for_(const Range& range, std::function<void(const Range&)> functor, double nstripes=-1.)
^~~~~~~~~~~~~
ov2slam/CMakeFiles/ov2slam.dir/build.make:206: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/feature_extractor.cpp.o' failed
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/src/feature_extractor.cpp.o] Error 1
CMakeFiles/Makefile2:550: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/all' failed
make[1]: *** [ov2slam/CMakeFiles/ov2slam.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j12 -l12" failed

Ubuntu 18.04 LTS.. Using windows WSL

FAST grid detection strategy -> ANMS

I have really enjoyed reading your work. Very impressive.

One suggestion to improve the keypoint detection stage is to move away from grid-based detection to ANMS strategies. It produces reasonable improvement over the traditional FAST keypoint detection while being computationally efficient.

P.S. It is a shameless advertisement of work from our group 😆

Sophus crash

Hi, and thnak you for making this code available. I have it compiled and running on Windows, but i am getting a crash after a few frames (Kitti dataset 03)

 - [Mapper (back-End)]: Stereo Triangulation!


         >>> (BEFORE STEREO TRIANGULATION) New KF nb 2d kps / 3d kps / stereokps : 76 / 77 / 123


 >>> 2.BA_SetupPb : 26.7952 ms

7.1497 ms

3
iter      cost      cost_change  |gradient|   |step|    tr_ratio  tr_radius  ls_iter  iter_time  total_time
   0  1.395001e+02    0.00e+00    3.73e+03   0.00e+00   0.00e+00  1.00e+04        0    5.94e-04    1.08e-03
Sophus ensure failed in function 'Sophus::SO3<double,0>::expAndTheta', file 'd:\testing\ov2slam-main\thirdparty\sophus\sophus\so3.hpp', line 619.
SO3::exp failed! omega: -nan(ind) -nan(ind) -nan(ind), real: -nan(ind), img: -nan(ind)
   1  6.812020e+01    7.14e+01    8.51e+02   1.84e-02   1.28e+00  3.00e+04        1    1.66e-03    5.55e-03
D:\testing\ov2slam-main\built\Release>

Any help greatly appreciated. What might be causing this?

Thanks!

Question about precision

Hi. I have a few questions:

  1. Is it possible to set body_T_cam0 to I_4x4 and body_T_cam1 to T_cam0_cam1.
  2. Why is it calculated that the translation part tx in T_cam0_cam1 is a positive number, we take the left camera as the origin, shouldn’t the translation transformation of the right camera relative to the left object be a negative number?
  3. I run this algorithm with the dataset and it works well, even if I deliberately change body_T_cam0 or body_T_cam1, I can get the running result, the difference is that the trajectory is not accurate. But when I run the algorithm with my own camera (realsense d455 and ZED2) in hand, the trajectory drifts very badly

euroc_mono.yaml: line 1: fg: no job control

Hello,

Can you please help with this error:

ov2slam/catkin_ws/src/ov2slam/parameters_files/accurate/euroc/euroc_mono.yaml: line 1: fg: no job control ov2slam/catkin_ws/src/ov2slam/parameters_files/accurate/euroc/euroc_mono.yaml: line 2: ---: command not found ov2slam/catkin_ws/src/ov2slam/parameters_files/accurate/euroc/euroc_mono.yaml: line 8: Camera.topic_left:: command not found
The error happens for every single line of yaml. Do not know what I should do.
Thank you!

Failed to open settings file...

The error message is: "Loading parameters file: parameter_file.yaml... Failed to open settings file..." when I ran the command "rosrun ov2slam ov2slam_node parameter_file.yaml".

Sudden scale drift on top down forward motion

Hey hey,

first of all ov2slam looks like a pretty promising SLAM for my application. The quick initialization and performance in the first few seconds is very nice. However, I experience very sudden scale drifts out of the blue. I made a quick video and attached a link to this in the bottom.
My question is: What can I do about it? I already chose the high accuracy settings, but it seems like something gets out of hand really fast. My camera setup is rather uncommon for the average SLAM dataset with rather low frame rate (7 Hz) and high resolution (1920x1080) with images looking top down from a forward flying drone. Any suggestions? I'd prefer robustness over fast performance.

https://drive.google.com/file/d/1k9GIVHZNiTi8cD-KGqulIvPmsWlW1TrU/view?usp=sharing

Add external velocitiy measurements

Hello,

first of all, great project!
Is there any way to integrate external velocity measurements (eg. wheel odometry) into the filter?
If so, where would be a good place to start in the source code?

Thanks!
James

terminate called without an active exception

I have run ov2slam on KITTI, EUROC and my own camera, and they all work well,but the same Stack trace will be output at the end. It seems that something wrong with threads, but I don't know how to solve it:

 Estimator thread is exiting.

 Bag reader SyncProcess thread is terminating!

Mapper is stopping!

 Going to write the computed trajectory into : ov2slam_traj.txt

Trajectory file written!

 Going to write the computed trajectory into : ov2slam_traj_kitti.txt

KITTITrajectory file written!

 Going to write the computed KFs trajectory into : ov2slam_kfs_traj.txt

Kfs Trajectory file written!

OV²SLAM is stopping!
terminate called without an active exception
Stack trace (most recent call last):
#8    Object "", at 0xffffffffffffffff, in 
#7    Object "/home/xtcl/ros_ws/devel/lib/ov2slam/ov2slam_node", at 0x559a113976a9, in _start
#6    Source "../csu/libc-start.c", line 310, in __libc_start_main [0x7f4f1a5d0bf6]
#5  | Source "/home/xtcl/ros_ws/src/ov2slam/src/ov2slam_node.cpp", line 208, in ~thread
    |   207:     // Start a thread for providing new measurements to the SLAM
    | > 208:     std::thread sync_thread(&SensorsGrabber::sync_process, &sb);
    |   209: 
    |   210:     // ROS Spin
      Source "/usr/include/c++/7/thread", line 135, in main [0x559a11397345]
        132:     ~thread()
        133:     {
        134:       if (joinable())
      > 135: 	std::terminate();
        136:     }
        137: 
        138:     thread& operator=(const thread&) = delete;
#4    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.25", at 0x7f4f1ac4ab20, in std::terminate()
#3    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.25", at 0x7f4f1ac4aae5, in 
#2    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.25", at 0x7f4f1ac44956, in 
#1    Source "/build/glibc-S9d2JN/glibc-2.27/stdlib/abort.c", line 79, in abort [0x7f4f1a5ef920]
#0    Source "../sysdeps/unix/sysv/linux/raise.c", line 51, in raise [0x7f4f1a5edfb7]
Aborted (Signal sent by tkill() 7465 1000)

Could not link library libov2slam

Hi all,
I'm trying to get ov2slam running on my Ubuntu 20.04 machine. I work with a version of Ceres already installed. When I'm running command catkin_make --pkg ov2slam, I get the following error :

`-- Configuring done
CMake Warning (dev) at ov2slam/CMakeLists.txt:127 (add_library):
Policy CMP0028 is not set: Double colon in target name means ALIAS or
IMPORTED target. Run "cmake --help-policy CMP0028" for policy details.
Use the cmake_policy command to set the policy and suppress this warning.

Target "ov2slam" links to target "Ceres::ceres" but the target was not
found. Perhaps a find_package() call is missing for an IMPORTED target, or
an ALIAS target is missing?
This warning is for project developers. Use -Wno-dev to suppress it.

-- Generating done
-- Build files have been written to: /home/thomas/catkin_ws/build

Running command: "make -j8 -l8" in "/home/thomas/catkin_ws/build/ov2slam"

[ 14%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/camera_visualizer.cpp.o
[ 14%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/visual_front_end.cpp.o
[ 14%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/ov2slam.cpp.o
[ 28%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/frame.cpp.o
[ 28%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/slam_params.cpp.o
[ 28%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/camera_calibration.cpp.o
[ 42%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/feature_tracker.cpp.o
[ 42%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/feature_extractor.cpp.o
[ 42%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/map_manager.cpp.o
[ 57%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/map_point.cpp.o
[ 57%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/mapper.cpp.o
[ 57%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/multi_view_geometry.cpp.o
[ 71%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/ceres_parametrization.cpp.o
[ 71%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/optimizer.cpp.o
[ 71%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/estimator.cpp.o
[ 85%] Building CXX object ov2slam/CMakeFiles/ov2slam.dir/src/loop_closer.cpp.o
[ 85%] Linking CXX shared library /home/thomas/catkin_ws/devel/lib/libov2slam.so
/usr/bin/ld: cannot find -lCeres::ceres
collect2: error: ld returned 1 exit status
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/build.make:524: /home/thomas/catkin_ws/devel/lib/libov2slam.so] Error 1
make[1]: *** [CMakeFiles/Makefile2:3761: ov2slam/CMakeFiles/ov2slam.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
Invoking "make -j8 -l8" failed`

I tried reinstalling Ceres, use the third-party version of Ceres but I always get the same error. Seems like code is built but link to library libov2slam can't be made (I checked and this lib does not appear on the designated location on my PC ( /home/thomas/catkin_ws/devel/lib/ ).

Anyone encountered this already ? Or does someone have an idea on how to solve the problem ?

Thank you !

How to get 3D keypoints with depth?

Hi, thanks for your work. I managed to compile and run it successfully.

I was wondering if there is any easy way to get a list of the keypoints for each frame as pixel position and depth. For now, I can save the resulting point cloud pmap_->pcloud_ with PCL and I see I could get pixel positions for each image as pcurframe_->getKeypointsPx().

However, I'm not sure how to access the 3D position of the keypoints and their depth. I see that there are two functions pcurframe_->getKeypoints3d() and pcurframe_->getKeypointsBv(), but how do I extract the information I need from them?

Thank you in advance for your help.

No such file or directory

No such file or directory
catkin_ws/src/ov2slam/src/feature_extractor.cpp:36:10: fatal error: xfeatures2d.hpp: No such file or directory

imu integration

@ferreram
Thank you very much for your work. Now ov2slam has not yet integrated imu. I am looking forward to the release of the integrated imu code, which is necessary for everyone's learning.

catkin_make --pkg ov2slam error: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/visual_front_end.cpp.o' failed

Environment description:ubuntu16.04 installed ROS kinetic,I successed run ORB-SLAM2,I am find great ov2slam。
I installed

  • opencv 3.4.3
  • gcc (Ubuntu 5.4.0-6ubuntu1~16.04.12) 5.4.0 20160609
  • eigen3 eigen-3.3.7
  • Pongolin Pangolin-0.5 (Not the latest)

I follow the instructions to install

1.init ROS and workspace
I installed ROS kinetic,and rviz also installed,I Make sure i installed follow this conmand: sudo apt install ros-kinetic-pcl-ros

mkdir -p /root/catkin_ov2slam/src && cd /root/catkin_ov2slam/src
    catkin_init_workspace
    cd ../ && catkin_make 

I run conmmand: rosdep install ov2slam, it warn me :

ERROR: the following packages/stacks could not have their rosdep keys resolved
to system dependencies:
ov2slam: Cannot locate rosdep definition for [catkin]

I do this conmmand ingonre step:
rosdep install --from-paths /root/catkin_ov2slam/src --ignore-src -y --rosdistro=kinetic

2. Installation
2.0 Clone
Clone the git repository in your catkin workspace:
2.1 Build Thirdparty libs and also build opengv
2.2 Build OV²SLAM
Build OV²SLAM package with :
cd ~/catkin_ov2slam/
catkin_make --pkg ov2slam(report errors)
source ~/catkin_ov2slam/devel/setup.bash (Not yet implemented here)

Problem description:After I have completed the necessary preparations,I run catkin_make --pkg ov2slam error,
some report errors:

In file included from /root/catkin_ov2slam/src/ov2slam/include/frame.hpp:42:0,
                 from /root/catkin_ov2slam/src/ov2slam/src/frame.cpp:27:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp: In instantiation of ‘Sophus::SE3<typename Eigen::internal::traits<T>::Scalar> Sophus::SE3Base<Derived>::inverse() const [with Derived = Sophus::SE3<double>; typename Eigen::internal::traits<T>::Scalar = double]’:
/root/catkin_ov2slam/src/ov2slam/src/frame.cpp:748:24:   required from here
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:210:35: error: no match for ‘operator*’ (operand types are ‘Sophus::SO3<double>’ and ‘const ScalarMultipleReturnType {aka const Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, const Eigen::Matrix<double, 3, 1> >}’)
     return SE3<Scalar>(invR, invR * (translation() * Scalar(-1)));
ov2slam/CMakeFiles/ov2slam.dir/build.make:143: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/feature_extractor.cpp.o' failed
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/src/feature_extractor.cpp.o] Error 1
ov2slam/CMakeFiles/ov2slam.dir/build.make:130: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/camera_calibration.cpp.o' failed
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/src/camera_calibration.cpp.o] Error 1
ov2slam/CMakeFiles/ov2slam.dir/build.make:117: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/slam_params.cpp.o' failed
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/src/slam_params.cpp.o] Error 1
In file included from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:8:0,
                 from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:7,
                 from /root/catkin_ov2slam/src/ov2slam/include/camera_visualizer.hpp:37,
                 from /root/catkin_ov2slam/src/ov2slam/src/camera_visualizer.cpp:31:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:106:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:110:26: error: ‘ReturnScalar’ was not declared in this scope
   using SO2Product = SO2<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:110:39: error: template argument 1 is invalid
   using SO2Product = SO2<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:113:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector2<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:113:45: error: template argument 1 is invalid
   using PointProduct = Vector2<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:116:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:116:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:214:15: error: ‘SO2Product’ does not name a type
   SOPHUS_FUNC SO2Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:249:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:265:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
In file included from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:7:0,
                 from /root/catkin_ov2slam/src/ov2slam/include/camera_visualizer.hpp:37,
                 from /root/catkin_ov2slam/src/ov2slam/src/camera_visualizer.cpp:31:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:110:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:114:26: error: ‘ReturnScalar’ was not declared in this scope
   using SO3Product = SO3<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:114:39: error: template argument 1 is invalid
   using SO3Product = SO3<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:117:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:117:45: error: template argument 1 is invalid
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:120:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:120:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:329:15: error: ‘SO3Product’ does not name a type
   SOPHUS_FUNC SO3Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:362:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:377:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
In file included from /root/catkin_ov2slam/src/ov2slam/include/camera_visualizer.hpp:37:0,
                 from /root/catkin_ov2slam/src/ov2slam/src/camera_visualizer.cpp:31:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:85:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:89:26: error: ‘ReturnScalar’ was not declared in this scope
   using SE3Product = SE3<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:89:39: error: template argument 1 is invalid
   using SE3Product = SE3<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:92:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:92:45: error: template argument 1 is invalid
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:95:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:95:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:308:15: error: ‘SE3Product’ does not name a type
   SOPHUS_FUNC SE3Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:325:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:335:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
ov2slam/CMakeFiles/ov2slam.dir/build.make:78: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/camera_visualizer.cpp.o' failed
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/src/camera_visualizer.cpp.o] Error 1
ov2slam/CMakeFiles/ov2slam.dir/build.make:104: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/frame.cpp.o' failed
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/src/frame.cpp.o] Error 1
In file included from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:8:0,
                 from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:7,
                 from /root/catkin_ov2slam/src/ov2slam/include/slam_params.hpp:37,
                 from /root/catkin_ov2slam/src/ov2slam/include/visual_front_end.hpp:34,
                 from /root/catkin_ov2slam/src/ov2slam/src/visual_front_end.cpp:29:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:106:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:110:26: error: ‘ReturnScalar’ was not declared in this scope
   using SO2Product = SO2<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:110:39: error: template argument 1 is invalid
   using SO2Product = SO2<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:113:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector2<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:113:45: error: template argument 1 is invalid
   using PointProduct = Vector2<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:116:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:116:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:214:15: error: ‘SO2Product’ does not name a type
   SOPHUS_FUNC SO2Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:249:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:265:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
In file included from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:7:0,
                 from /root/catkin_ov2slam/src/ov2slam/include/slam_params.hpp:37,
                 from /root/catkin_ov2slam/src/ov2slam/include/visual_front_end.hpp:34,
                 from /root/catkin_ov2slam/src/ov2slam/src/visual_front_end.cpp:29:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:110:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:114:26: error: ‘ReturnScalar’ was not declared in this scope
   using SO3Product = SO3<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:114:39: error: template argument 1 is invalid
   using SO3Product = SO3<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:117:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:117:45: error: template argument 1 is invalid
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:120:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:120:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:329:15: error: ‘SO3Product’ does not name a type
   SOPHUS_FUNC SO3Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:362:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:377:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
In file included from /root/catkin_ov2slam/src/ov2slam/include/slam_params.hpp:37:0,
                 from /root/catkin_ov2slam/src/ov2slam/include/visual_front_end.hpp:34,
                 from /root/catkin_ov2slam/src/ov2slam/src/visual_front_end.cpp:29:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:85:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:89:26: error: ‘ReturnScalar’ was not declared in this scope
   using SE3Product = SE3<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:89:39: error: template argument 1 is invalid
   using SE3Product = SE3<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:92:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:92:45: error: template argument 1 is invalid
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:95:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:95:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:308:15: error: ‘SE3Product’ does not name a type
   SOPHUS_FUNC SE3Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:325:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:335:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
In file included from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:8:0,
                 from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:7,
                 from /root/catkin_ov2slam/src/ov2slam/include/slam_params.hpp:37,
                 from /root/catkin_ov2slam/src/ov2slam/include/ov2slam.hpp:33,
                 from /root/catkin_ov2slam/src/ov2slam/src/ov2slam.cpp:30:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:106:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:110:26: error: ‘ReturnScalar’ was not declared in this scope
   using SO2Product = SO2<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:110:39: error: template argument 1 is invalid
   using SO2Product = SO2<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:113:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector2<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:113:45: error: template argument 1 is invalid
   using PointProduct = Vector2<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:116:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:116:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:214:15: error: ‘SO2Product’ does not name a type
   SOPHUS_FUNC SO2Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:249:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:265:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so2.hpp:289:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
In file included from /root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:7:0,
                 from /root/catkin_ov2slam/src/ov2slam/include/slam_params.hpp:37,
                 from /root/catkin_ov2slam/src/ov2slam/include/ov2slam.hpp:33,
                 from /root/catkin_ov2slam/src/ov2slam/src/ov2slam.cpp:30:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:110:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:114:26: error: ‘ReturnScalar’ was not declared in this scope
   using SO3Product = SO3<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:114:39: error: template argument 1 is invalid
   using SO3Product = SO3<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:117:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:117:45: error: template argument 1 is invalid
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:120:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:120:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:329:15: error: ‘SO3Product’ does not name a type
   SOPHUS_FUNC SO3Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:362:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:377:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/so3.hpp:399:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
In file included from /root/catkin_ov2slam/src/ov2slam/include/slam_params.hpp:37:0,
                 from /root/catkin_ov2slam/src/ov2slam/include/ov2slam.hpp:33,
                 from /root/catkin_ov2slam/src/ov2slam/src/ov2slam.cpp:30:
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:85:40: error: ‘ScalarBinaryOpTraits’ in namespace ‘Eigen’ does not name a template type
   using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:89:26: error: ‘ReturnScalar’ was not declared in this scope
   using SE3Product = SE3<ReturnScalar<OtherDerived>>;
                          ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:89:39: error: template argument 1 is invalid
   using SE3Product = SE3<ReturnScalar<OtherDerived>>;
                                       ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:92:32: error: ‘ReturnScalar’ was not declared in this scope
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:92:45: error: template argument 1 is invalid
   using PointProduct = Vector3<ReturnScalar<PointDerived>>;
                                             ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:95:43: error: ‘ReturnScalar’ was not declared in this scope
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                           ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:95:56: error: template argument 1 is invalid
   using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
                                                        ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:308:15: error: ‘SE3Product’ does not name a type
   SOPHUS_FUNC SE3Product<OtherDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:325:15: error: ‘PointProduct’ does not name a type
   SOPHUS_FUNC PointProduct<PointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:335:15: error: ‘HomogeneousPointProduct’ does not name a type
   SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:38: error: ‘ReturnScalar’ was not declared in this scope
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                      ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:51: error: template argument 2 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                   ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:63: error: template argument 1 is invalid
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                               ^
/root/catkin_ov2slam/src/ov2slam/Thirdparty/Sophus/sophus/se3.hpp:359:75: error: ‘type’ in namespace ‘::’ does not name a type
                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
                                                                           ^
In file included from /usr/local/include/boost/detail/endian.hpp:9:0,
                 from /usr/include/pcl-1.7/pcl/PCLPointCloud2.h:11,
                 from /usr/include/pcl-1.7/pcl/conversions.h:48,
                 from /opt/ros/kinetic/include/pcl_ros/point_cloud.h:8,
                 from /root/catkin_ov2slam/src/ov2slam/include/map_manager.hpp:32,
                 from /root/catkin_ov2slam/src/ov2slam/include/visual_front_end.hpp:35,
                 from /root/catkin_ov2slam/src/ov2slam/src/visual_front_end.cpp:29:

/usr/include/eigen3/Eigen/src/Core/../plugins/CommonCwiseUnaryOps.h:83:1: note:   no known conversion for argument 1 from ‘Sophus::SO3<double>’ to ‘const Scalar& {aka const double&}’
ov2slam/CMakeFiles/ov2slam.dir/build.make:91: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/visual_front_end.cpp.o' failed
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/src/visual_front_end.cpp.o] Error 1
ov2slam/CMakeFiles/ov2slam.dir/build.make:65: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/src/ov2slam.cpp.o' failed
make[2]: *** [ov2slam/CMakeFiles/ov2slam.dir/src/ov2slam.cpp.o] Error 1
CMakeFiles/Makefile2:488: recipe for target 'ov2slam/CMakeFiles/ov2slam.dir/all' failed
make[1]: *** [ov2slam/CMakeFiles/ov2slam.dir/all] Error 2
Makefile:143: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

I hope this problem is a typical error and can be effectively solved,thanks dear all~

'catkin build' fails -- CMake not linking OpenCV

Dear maintainers :)

I'm facing errors, when I try to 'catkin build':

  1. I can't build as stated in the instructions. I have to go to ~/catkin_ws and do a catkin build ov2slam from here (no big issue :))
  2. The build process gives the error: //usr/lib/aarch64-linux-gnu/libopencv_core.so.4.1: error adding symbols: DSO missing from command line and I'm a little curious about the double slash in //usr/lib/aarch64-linux-gnu..... - is that OK?

image

I have tried to do a catkin clean and repeat the process with catkin_make, but I get a similar result.

I'm running on a Jetson Xavier NX and OpenCV comes as a part of Jetpack and when I look in /usr/lib/aarch64-linux-gnu I can see that most libs are in two versions (3 and 4):

image

I have tried to link libopencv_core.so to libopencv_core.so.3.2 instead of libopencv_core.so.4.1, as suggested here: https://answers.opencv.org/question/217959/libopencv_coreso31-cannot-open-shared-object-file-no-such-file-or-directory/, but that doesn't change anything.

I have not installed opencv_contrib. I have therefor set the OPENCV_CONTRIB flag to OFF in CMakeLists.txt.
Further I have changed line 113 in /opt/ros/melodic/share/cv_bridge/cmake/cv_bridgeConfig.cmake from /usr/include/opencv to /usr/include/opencv4

Do you have a tip or solution, which can bring me forward with this?

Thanks a lot in advance.

Paper

Hi is it possible to use this Slam system for real drone control.
Where can I get find the paper.
Thank you

I can't let ovslam run for more than three seconds

The previous compilation runs smoothly, but when I run the euroc dataset, there are problems, whether it is a binocular or a monocular node. After using the rosbag play MH_03_medium.bag command, it only ran on rviz for less than three seconds. then the ovslam node told me that it has given up, the core has been dumped, and the initial point cloud picture appeared on the rviz leaf, and then there is no follow-up because of the ovslam node's crash. What is the problem?
2021-04-24 09-05-15屏幕截图

here are the core dump logs:

details
Starting the measurements reader thread!
*** Error in `/home/rap/catkin_ov/devel/lib/ov2slam/ov2slam_node': double free or corruption (out): 0x00007f2f084d1180 ***
======= Backtrace: =========
/lib/x86_64-linux-gnu/libc.so.6(+0x777f5)[0x7f2f38ebf7f5]
/lib/x86_64-linux-gnu/libc.so.6(+0x8038a)[0x7f2f38ec838a]
/lib/x86_64-linux-gnu/libc.so.6(cfree+0x4c)[0x7f2f38ecc58c]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN5Eigen10MatrixBaseINS_5BlockINS_6MatrixIdLin1ELin1ELi0ELin1ELin1EEELin1ELin1ELb0EEEE25applyHouseholderOnTheLeftINS_11VectorBlockINS1_IS3_Lin1ELi1ELb1EEELin1EEEEEvRKT_RKdPd+0x469)[0x7f2f3b9233d9]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN5Eigen19ColPivHouseholderQRINS_6MatrixIdLin1ELin1ELi0ELin1ELin1EEEE14computeInPlaceEv+0x899)[0x7f2f3b923d99]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN5Eigen9JacobiSVDINS_6MatrixIdLin1ELin1ELi0ELin1ELin1EEELi2EE7computeERKS2_j+0x1ea8)[0x7f2f3b929dc8]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN5Eigen9JacobiSVDINS_6MatrixIdLin1ELin1ELi0ELin1ELin1EEELi2EEC2ERKS2_j+0x23e)[0x7f2f3b95fd1e]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN6opengv13relative_pose13fivept_nisterERKNS0_19RelativeAdapterBaseERKNS_7IndicesE+0x21a)[0x7f2f3b95543a]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN6opengv13relative_pose13fivept_nisterERKNS0_19RelativeAdapterBaseERKSt6vectorIiSaIiEE+0x3c)[0x7f2f3b95560c]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZNK6opengv12sac_problems13relative_pose29CentralRelativePoseSacProblem24computeModelCoefficientsERKSt6vectorIiSaIiEERN5Eigen6MatrixIdLi3ELi4ELi0ELi3ELi4EEE+0x3348)[0x7f2f3b932698]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN6opengv3sac6RansacINS_12sac_problems13relative_pose29CentralRelativePoseSacProblemEE12computeModelEi+0x100)[0x7f2f3b6d7690]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN17MultiViewGeometry24opengv5ptEssentialMatrixERKSt6vectorIN5Eigen6MatrixIdLi3ELi1ELi0ELi3ELi1EEENS1_17aligned_allocatorIS3_EEES8_ifbbffRNS2_IdLi3ELi3ELi0ELi3ELi3EEERS3_RS0_IiSaIiEE+0x429)[0x7f2f3b6d5329]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN14VisualFrontEnd21epipolar2d2dFilteringEv+0x7b8)[0x7f2f3b68a518]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN14VisualFrontEnd9trackMonoERN2cv3MatEd+0x309)[0x7f2f3b68b099]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN14VisualFrontEnd14visualTrackingERN2cv3MatEd+0xb6)[0x7f2f3b68b3b6]
/home/rap/catkin_ov/devel/lib/libov2slam.so(_ZN11SlamManager3runEv+0x29d)[0x7f2f3b66a6ad]
/usr/lib/x86_64-linux-gnu/libstdc++.so.6(+0xd0e7e)[0x7f2f394fae7e]
/lib/x86_64-linux-gnu/libpthread.so.0(+0x76ba)[0x7f2f398156ba]
/lib/x86_64-linux-gnu/libc.so.6(clone+0x6d)[0x7f2f38f4f4dd]
======= Memory map: ========
00400000-0042a000 r-xp 00000000 08:05 1087206                            /home/rap/catkin_ov/devel/lib/ov2slam/ov2slam_node
0062a000-0062b000 r--p 0002a000 08:05 1087206                            /home/rap/catkin_ov/devel/lib/ov2slam/ov2slam_node
0062b000-0062c000 rw-p 0002b000 08:05 1087206                            /home/rap/catkin_ov/devel/lib/ov2slam/ov2slam_node
0062c000-0062d000 rw-p 00000000 00:00 0 
022f3000-02408000 rw-p 00000000 00:00 0                                  [heap]
7f2ee0000000-7f2ee0230000 rw-p 00000000 00:00 0 
7f2ee0230000-7f2ee4000000 ---p 00000000 00:00 0 
7f2ee4000000-7f2ee4424000 rw-p 00000000 00:00 0 
7f2ee4424000-7f2ee8000000 ---p 00000000 00:00 0 
7f2ee8000000-7f2ee831a000 rw-p 00000000 00:00 0 
7f2ee831a000-7f2eec000000 ---p 00000000 00:00 0 
7f2eec000000-7f2eec423000 rw-p 00000000 00:00 0 
7f2eec423000-7f2ef0000000 ---p 00000000 00:00 0 
7f2ef0000000-7f2ef0021000 rw-p 00000000 00:00 0 
7f2ef0021000-7f2ef4000000 ---p 00000000 00:00 0 
7f2ef4000000-7f2ef4021000 rw-p 00000000 00:00 0 
7f2ef4021000-7f2ef8000000 ---p 00000000 00:00 0 
7f2ef8000000-7f2ef8021000 rw-p 00000000 00:00 0 
7f2ef8021000-7f2efc000000 ---p 00000000 00:00 0 
7f2efc000000-7f2efc021000 rw-p 00000000 00:00 0 
7f2efc021000-7f2f00000000 ---p 00000000 00:00 0 
7f2f00000000-7f2f00021000 rw-p 00000000 00:00 0 
7f2f00021000-7f2f04000000 ---p 00000000 00:00 0 
7f2f05ffc000-7f2f05ffd000 ---p 00000000 00:00 0 
7f2f05ffd000-7f2f067fd000 rwxp 00000000 00:00 0 
7f2f067fd000-7f2f067fe000 ---p 00000000 00:00 0 
7f2f067fe000-7f2f06ffe000 rwxp 00000000 00:00 0 
7f2f06ffe000-7f2f06fff000 ---p 00000000 00:00 0 
7f2f06fff000-7f2f077ff000 rwxp 00000000 00:00 0 
7f2f077ff000-7f2f07800000 ---p 00000000 00:00 0 
7f2f07800000-7f2f08000000 rwxp 00000000 00:00 0 
7f2f08000000-7f2f08646000 rw-p 00000000 00:00 0 
7f2f08646000-7f2f0c000000 ---p 00000000 00:00 0 
7f2f0c000000-7f2f0c021000 rw-p 00000000 00:00 0 
7f2f0c021000-7f2f10000000 ---p 00000000 00:00 0 
7f2f10000000-7f2f10212000 rw-p 00000000 00:00 0 
7f2f10212000-7f2f14000000 ---p 00000000 00:00 0 
7f2f14000000-7f2f1434c000 rw-p 00000000 00:00 0 
7f2f1434c000-7f2f18000000 ---p 00000000 00:00 0 
7f2f18682000-7f2f187f9000 rw-p 00000000 00:00 0 
7f2f187f9000-7f2f187fa000 ---p 00000000 00:00 0 
7f2f187fa000-7f2f18ffa000 rwxp 00000000 00:00 0 
7f2f18ffa000-7f2f18ffb000 ---p 00000000 00:00 0 
7f2f18ffb000-7f2f197fb000 rwxp 00000000 00:00 0 
7f2f197fb000-7f2f197fc000 ---p 00000000 00:00 0 
7f2f197fc000-7f2f19ffc000 rwxp 00000000 00:00 0 
7f2f19ffc000-7f2f19ffd000 ---p 00000000 00:00 0 
7f2f19ffd000-7f2f1a7fd000 rwxp 00000000 00:00 0 
7f2f1a7fd000-7f2f1a7fe000 ---p 00000000 00:00 0 
7f2f1a7fe000-7f2f1affe000 rwxp 00000000 00:00 0 
7f2f1affe000-7f2f1afff000 ---p 00000000 00:00 0 
7f2f1afff000-7f2f1b7ff000 rwxp 00000000 00:00 0 
7f2f1b7ff000-7f2f1b800000 ---p 00000000 00:00 0 
7f2f1b800000-7f2f1c000000 rwxp 00000000 00:00 0 
7f2f1c000000-7f2f1c021000 rw-p 00000000 00:00 0 
7f2f1c021000-7f2f20000000 ---p 00000000 00:00 0 
7f2f20000000-7f2f20021000 rw-p 00000000 00:00 0 
7f2f20021000-7f2f24000000 ---p 00000000 00:00 0 
7f2f24000000-7f2f24066000 rw-p 00000000 00:00 0 
7f2f24066000-7f2f28000000 ---p 00000000 00:00 0 
7f2f28217000-7f2f283f2000 rw-p 00000000 00:00 0 
7f2f283f2000-7f2f283f3000 ---p 00000000 00:00 0 
7f2f283f3000-7f2f28bf3000 rwxp 00000000 00:00 0 
7f2f28bf3000-7f2f28bf4000 ---p 00000000 00:00 0 
7f2f28bf4000-7f2f293f4000 rwxp 00000000 00:00 0 
7f2f293f4000-7f2f29c86000 rw-p 00000000 00:00 0 
7f2f29c86000-7f2f29c87000 ---p 00000000 00:00 0 
7f2f29c87000-7f2f2a487000 rwxp 00000000 00:00 0 
7f2f2a487000-7f2f2a488000 ---p 00000000 00:00 0 
7f2f2a488000-7f2f2ac88000 rwxp 00000000 00:00 0 
7f2f2ac88000-7f2f2ac89000 ---p 00000000 00:00 0 
7f2f2ac89000-7f2f2b489000 rwxp 00000000 00:00 0 
7f2f2b489000-7f2f2b48a000 ---p 00000000 00:00 0 
7f2f2b48a000-7f2f2bc8a000 rwxp 00000000 00:00 0 
7f2f2bc8a000-7f2f2bc95000 r-xp 00000000 08:05 5247907                    /lib/x86_64-linux-gnu/libnss_files-2.23.so
7f2f2bc95000-7f2f2be94000 ---p 0000b000 08:05 5247907                    /lib/x86_64-linux-gnu/libnss_files-2.23.so
7f2f2be94000-7f2f2be95000 r--p 0000a000 08:05 5247907                    /lib/x86_64-linux-gnu/libnss_files-2.23.so
7f2f2be95000-7f2f2be96000 rw-p 0000b000 08:05 5247907                    /lib/x86_64-linux-gnu/libnss_files-2.23.so
7f2f2be96000-7f2f2be9c000 rw-p 00000000 00:00 0 
7f2f2be9c000-7f2f2bec2000 r-xp 00000000 08:05 5247839                    /lib/x86_64-linux-gnu/libexpat.so.1.6.0
7f2f2bec2000-7f2f2c0c2000 ---p 00026000 08:05 5247839                    /lib/x86_64-linux-gnu/libexpat.so.1.6.0
7f2f2c0c2000-7f2f2c0c4000 r--p 00026000 08:05 5247839                    /lib/x86_64-linux-gnu/libexpat.so.1.6.0
7f2f2c0c4000-7f2f2c0c5000 rw-p 00028000 08:05 5247839                    /lib/x86_64-linux-gnu/libexpat.so.1.6.0
7f2f2c0c5000-7f2f2c0ce000 r-xp 00000000 08:05 5247818                    /lib/x86_64-linux-gnu/libcrypt-2.23.so
7f2f2c0ce000-7f2f2c2cd000 ---p 00009000 08:05 5247818                    /lib/x86_64-linux-gnu/libcrypt-2.23.so
7f2f2c2cd000-7f2f2c2ce000 r--p 00008000 08:05 5247818                    /lib/x86_64-linux-gnu/libcrypt-2.23.so
7f2f2c2ce000-7f2f2c2cf000 rw-p 00009000 08:05 5247818                    /lib/x86_64-linux-gnu/libcrypt-2.23.so
7f2f2c2cf000-7f2f2c2fd000 rw-p 00000000 00:00 0 
7f2f2c2fd000-7f2f2c301000 r-xp 00000000 08:05 5247992                    /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7f2f2c301000-7f2f2c500000 ---p 00004000 08:05 5247992                    /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7f2f2c500000-7f2f2c501000 r--p 00003000 08:05 5247992                    /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7f2f2c501000-7f2f2c502000 rw-p 00004000 08:05 5247992                    /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7f2f2c502000-7f2f2ddb8000 r-xp 00000000 08:05 271943                     /usr/lib/x86_64-linux-gnu/libicudata.so.55.1
7f2f2ddb8000-7f2f2dfb7000 ---p 018b6000 08:05 271943                     /usr/lib/x86_64-linux-gnu/libicudata.so.55.1
7f2f2dfb7000-7f2f2dfb8000 r--p 018b5000 08:05 271943                     /usr/lib/x86_64-linux-gnu/libicudata.so.55.1
7f2f2dfb8000-7f2f2dfb9000 rw-p 018b6000 08:05 271943                     /usr/lib/x86_64-linux-gnu/libicudata.so.55.1
7f2f2dfb9000-7f2f2dfc4000 r-xp 00000000 08:05 271997                     /usr/lib/x86_64-linux-gnu/libjbig.so.0
7f2f2dfc4000-7f2f2e1c3000 ---p 0000b000 08:05 271997                     /usr/lib/x86_64-linux-gnu/libjbig.so.0
7f2f2e1c3000-7f2f2e1c4000 r--p 0000a000 08:05 271997                     /usr/lib/x86_64-linux-gnu/libjbig.so.0
7f2f2e1c4000-7f2f2e1c7000 rw-p 0000b000 08:05 271997                     /usr/lib/x86_64-linux-gnu/libjbig.so.0
7f2f2e1c7000-7f2f2e20d000 r-xp 00000000 08:05 281617                     /usr/lib/x86_64-linux-gnu/libquadmath.so.0.0.0
7f2f2e20d000-7f2f2e40c000 ---p 00046000 08:05 281617                     /usr/lib/x86_64-linux-gnu/libquadmath.so.0.0.0
7f2f2e40c000-7f2f2e40d000 r--p 00045000 08:05 281617                     /usr/lib/x86_64-linux-gnu/libquadmath.so.0.0.0
7f2f2e40d000-7f2f2e40e000 rw-p 00046000 08:05 281617                     /usr/lib/x86_64-linux-gnu/libquadmath.so.0.0.0
7f2f2e40e000-7f2f2e42f000 r-xp 00000000 08:05 5247875                    /lib/x86_64-linux-gnu/liblzma.so.5.0.0
7f2f2e42f000-7f2f2e62e000 ---p 00021000 08:05 5247875                    /lib/x86_64-linux-gnu/liblzma.so.5.0.0
7f2f2e62e000-7f2f2e62f000 r--p 00020000 08:05 5247875                    /lib/x86_64-linux-gnu/liblzma.so.5.0.0
7f2f2e62f000-7f2f2e630000 rw-p 00021000 08:05 5247875                    /lib/x86_64-linux-gnu/liblzma.so.5.0.0
7f2f2e630000-7f2f2e64e000 r-xp 00000000 08:05 3418903                    /opt/ros/kinetic/lib/libactionlib.so
7f2f2e64e000-7f2f2e84d000 ---p 0001e000 08:05 3418903                    /opt/ros/kinetic/lib/libactionlib.so
7f2f2e84d000-7f2f2e84f000 r--p 0001d000 08:05 3418903                    /opt/ros/kinetic/lib/libactionlib.so
7f2f2e84f000-7f2f2e850000 rw-p 0001f000 08:05 3418903                    /opt/ros/kinetic/lib/libactionlib.so
7f2f2e850000-7f2f2e876000 r-xp 00000000 08:05 275196                     /usr/lib/x86_64-linux-gnu/libaprutil-1.so.0.5.4
7f2f2e876000-7f2f2ea75000 ---p 00026000 08:05 275196                     /usr/lib/x86_64-linux-gnu/libaprutil-1.so.0.5.4
7f2f2ea75000-7f2f2ea76000 r--p 00025000 08:05 275196                     /usr/lib/x86_64-linux-gnu/libaprutil-1.so.0.5.4
7f2f2ea76000-7f2f2ea77000 rw-p 00026000 08:05 275196                     /usr/lib/x86_64-linux-gnu/libaprutil-1.so.0.5.4
7f2f2ea77000-7f2f2eaa8000 r-xp 00000000 08:05 275141                     /usr/lib/x86_64-linux-gnu/libapr-1.so.0.5.2
7f2f2eaa8000-7f2f2eca7000 ---p 00031000 08:05 275141                     /usr/lib/x86_64-linux-gnu/libapr-1.so.0.5.2
7f2f2eca7000-7f2f2eca8000 r--p 00030000 08:05 275141                     /usr/lib/x86_64-linux-gnu/libapr-1.so.0.5.2
7f2f2eca8000-7f2f2eca9000 rw-p 00031000 08:05 275141                     /usr/lib/x86_64-linux-gnu/libapr-1.so.0.5.2
7f2f2eca9000-7f2f2ecad000 r-xp 00000000 08:05 273655                     /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.2
7f2f2ecad000-7f2f2eeac000 ---p 00004000 08:05 273655                     /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.2
7f2f2eeac000-7f2f2eead000 r--p 00003000 08:05 273655                     /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.2
7f2f2eead000-7f2f2eeae000 rw-p 00004000 08:05 273655                     /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.2
7f2f2eeae000-7f2f2f02d000 r-xp 00000000 08:05 271957                     /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1
7f2f2f02d000-7f2f2f22d000 ---p 0017f000 08:05 271957                     /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1
7f2f2f22d000-7f2f2f23d000 r--p 0017f000 08:05 271957                     /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1
7f2f2f23d000-7f2f2f23e000 rw-p 0018f000 08:05 271957                     /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1
7f2f2f23e000-7f2f2f242000 rw-p 00000000 00:00 0 
7f2f2f242000-7f2f2f494000 r-xp 00000000 08:05 271945                     /usr/lib/x86_64-linux-gnu/libicui18n.so.55.1
7f2f2f494000-7f2f2f694000 ---p 00252000 08:05 271945                     /usr/lib/x86_64-linux-gnu/libicui18n.so.55.1
7f2f2f694000-7f2f2f6a3000 r--p 00252000 08:05 271945                     /usr/lib/x86_64-linux-gnu/libicui18n.so.55.1
7f2f2f6a3000-7f2f2f6a4000 rw-p 00261000 08:05 271945                     /usr/lib/x86_64-linux-gnu/libicui18n.so.55.1
7f2f2f6a4000-7f2f2f6ee000 r-xp 00000000 08:05 267537                     /usr/lib/x86_64-linux-gnu/libjasper.so.1.0.0
7f2f2f6ee000-7f2f2f8ee000 ---p 0004a000 08:05 267537                     /usr/lib/x86_64-linux-gnu/libjasper.so.1.0.0
7f2f2f8ee000-7f2f2f8ef000 r--p 0004a000 08:05 267537                     /usr/lib/x86_64-linux-gnu/libjasper.so.1.0.0
7f2f2f8ef000-7f2f2f8f3000 rw-p 0004b000 08:05 267537                     /usr/lib/x86_64-linux-gnu/libjasper.so.1.0.0
7f2f2f8f3000-7f2f2f8fa000 rw-p 00000000 00:00 0 
7f2f2f8fa000-7f2f2f96b000 r-xp 00000000 08:05 276657                     /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4
7f2f2f96b000-7f2f2fb6b000 ---p 00071000 08:05 276657                     /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4
7f2f2fb6b000-7f2f2fb6c000 r--p 00071000 08:05 276657                     /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4
7f2f2fb6c000-7f2f2fb6f000 rw-p 00072000 08:05 276657                     /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4
7f2f2fb6f000-7f2f2fb93000 r-xp 00000000 08:05 5247949                    /lib/x86_64-linux-gnu/libpng12.so.0.54.0
7f2f2fb93000-7f2f2fd92000 ---p 00024000 08:05 5247949                    /lib/x86_64-linux-gnu/libpng12.so.0.54.0
7f2f2fd92000-7f2f2fd93000 r--p 00023000 08:05 5247949                    /lib/x86_64-linux-gnu/libpng12.so.0.54.0
7f2f2fd93000-7f2f2fd94000 rw-p 00024000 08:05 5247949                    /lib/x86_64-linux-gnu/libpng12.so.0.54.0
7f2f2fd94000-7f2f2fded000 r-xp 00000000 08:05 272573                     /usr/lib/x86_64-linux-gnu/libwebp.so.5.0.4
7f2f2fded000-7f2f2ffed000 ---p 00059000 08:05 272573                     /usr/lib/x86_64-linux-gnu/libwebp.so.5.0.4
7f2f2ffed000-7f2f2ffee000 r--p 00059000 08:05 272573                     /usr/lib/x86_64-linux-gnu/libwebp.so.5.0.4
7f2f2ffee000-7f2f2fff0000 rw-p 0005a000 08:05 272573                     /usr/lib/x86_64-linux-gnu/libwebp.so.5.0.4
7f2f2fff0000-7f2f30047000 r-xp 00000000 08:05 272001                     /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2
7f2f30047000-7f2f30247000 ---p 00057000 08:05 272001                     /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2
7f2f30247000-7f2f30248000 r--p 00057000 08:05 272001                     /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2
7f2f30248000-7f2f30249000 rw-p 00058000 08:05 272001                     /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2
7f2f30249000-7f2f3026a000 r-xp 00000000 08:05 1073689                    /usr/lib/atlas-base/libcblas.so.3.0
7f2f3026a000-7f2f3046a000 ---p 00021000 08:05 1073689                    /usr/lib/atlas-base/libcblas.so.3.0
7f2f3046a000-7f2f3046b000 rw-p 00021000 08:05 1073689                    /usr/lib/atlas-base/libcblas.so.3.0
7f2f3046b000-7f2f30594000 r-xp 00000000 08:05 266992                     /usr/lib/x86_64-linux-gnu/libgfortran.so.3.0.0
7f2f30594000-7f2f30793000 ---p 00129000 08:05 266992                     /usr/lib/x86_64-linux-gnu/libgfortran.so.3.0.0
7f2f30793000-7f2f30794000 r--p 00128000 08:05 266992                     /usr/lib/x86_64-linux-gnu/libgfortran.so.3.0.0
7f2f30794000-7f2f30796000 rw-p 00129000 08:05 266992                     /usr/lib/x86_64-linux-gnu/libgfortran.so.3.0.0
7f2f30796000-7f2f30b2d000 r-xp 00000000 08:05 1073688                    /usr/lib/atlas-base/libatlas.so.3.0
7f2f30b2d000-7f2f30d2d000 ---p 00397000 08:05 1073688                    /usr/lib/atlas-base/libatlas.so.3.0
7f2f30d2d000-7f2f30d34000 rw-p 00397000 08:05 1073688                    /usr/lib/atlas-base/libatlas.so.3.0
7f2f30d34000-7f2f30d71000 r-xp 00000000 08:05 1073687                    /usr/lib/atlas-base/atlas/libblas.so.3.0
7f2f30d71000-7f2f30f71000 ---p 0003d000 08:05 1073687                    /usr/lib/atlas-base/atlas/libblas.so.3.0
7f2f30f71000-7f2f30f72000 rw-p 0003d000 08:05 1073687                    /usr/lib/atlas-base/atlas/libblas.so.3.0
7f2f30f72000-7f2f30f7e000 r-xp 00000000 08:05 272518                     /usr/lib/x86_64-linux-gnu/libunwind.so.8.0.1
7f2f30f7e000-7f2f3117d000 ---p 0000c000 08:05 272518                     /usr/lib/x86_64-linux-gnu/libunwind.so.8.0.1
7f2f3117d000-7f2f3117e000 r--p 0000b000 08:05 272518                     /usr/lib/x86_64-linux-gnu/libunwind.so.8.0.1
7f2f3117e000-7f2f3117f000 rw-p 0000c000 08:05 272518                     /usr/lib/x86_64-linux-gnu/libunwind.so.8.0.1
7f2f3117f000-7f2f3118d000 rw-p 00000000 00:00 0 
7f2f3118d000-7f2f311ad000 r-xp 00000000 08:05 262666                     /usr/lib/x86_64-linux-gnu/libgflags.so.2.1.2
7f2f311ad000-7f2f313ac000 ---p 00020000 08:05 262666                     /usr/lib/x86_64-linux-gnu/libgflags.so.2.1.2
7f2f313ac000-7f2f313ad000 r--p 0001f000 08:05 262666                     /usr/lib/x86_64-linux-gnu/libgflags.so.2.1.2
7f2f313ad000-7f2f313ae000 rw-p 00020000 08:05 262666                     /usr/lib/x86_64-linux-gnu/libgflags.so.2.1.2
7f2f313ae000-7f2f31405000 r-xp 00000000 08:05 3418946                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_flann3.so.3.3.1
7f2f31405000-7f2f31605000 ---p 00057000 08:05 3418946                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_flann3.so.3.3.1
7f2f31605000-7f2f31607000 r--p 00057000 08:05 3418946                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_flann3.so.3.3.1
7f2f31607000-7f2f31608000 rw-p 00059000 08:05 3418946                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_flann3.so.3.3.1
7f2f31608000-7f2f31633000 r-xp 00000000 08:05 1063406                    /home/rap/catkin_ov/src/ov2slam/Thirdparty/obindex2/build/lib/libobindex2.so
7f2f31633000-7f2f31833000 ---p 0002b000 08:05 1063406                    /home/rap/catkin_ov/src/ov2slam/Thirdparty/obindex2/build/lib/libobindex2.so
7f2f31833000-7f2f31834000 r--p 0002b000 08:05 1063406                    /home/rap/catkin_ov/src/ov2slam/Thirdparty/obindex2/build/lib/libobindex2.so
7f2f31834000-7f2f31835000 rw-p 0002c000 08:05 1063406                    /home/rap/catkin_ov/src/ov2slam/Thirdparty/obindex2/build/lib/libobindex2.so
7f2f31835000-7f2f31867000 r-xp 00000000 08:05 3419114                    /opt/ros/kinetic/lib/libtf2.so
7f2f31867000-7f2f31a66000 ---p 00032000 08:05 3419114                    /opt/ros/kinetic/lib/libtf2.so
7f2f31a66000-7f2f31a68000 r--p 00031000 08:05 3419114                    /opt/ros/kinetic/lib/libtf2.so
7f2f31a68000-7f2f31a69000 rw-p 00033000 08:05 3419114                    /opt/ros/kinetic/lib/libtf2.so
7f2f31a69000-7f2f31b0f000 r-xp 00000000 08:05 3419119                    /opt/ros/kinetic/lib/libtf2_ros.so
7f2f31b0f000-7f2f31d0f000 ---p 000a6000 08:05 3419119                    /opt/ros/kinetic/lib/libtf2_ros.so
7f2f31d0f000-7f2f31d13000 r--p 000a6000 08:05 3419119                    /opt/ros/kinetic/lib/libtf2_ros.so
7f2f31d13000-7f2f31d15000 rw-p 000aa000 08:05 3419119                    /opt/ros/kinetic/lib/libtf2_ros.so
7f2f31d15000-7f2f31ec4000 r-xp 00000000 08:05 276797                     /usr/lib/x86_64-linux-gnu/liblog4cxx.so.10.0.0
7f2f31ec4000-7f2f320c3000 ---p 001af000 08:05 276797                     /usr/lib/x86_64-linux-gnu/liblog4cxx.so.10.0.0
7f2f320c3000-7f2f320e9000 r--p 001ae000 08:05 276797                     /usr/lib/x86_64-linux-gnu/liblog4cxx.so.10.0.0
7f2f320e9000-7f2f320ea000 rw-p 001d4000 08:05 276797                     /usr/lib/x86_64-linux-gnu/liblog4cxx.so.10.0.0
7f2f320ea000-7f2f320ec000 rw-p 00000000 00:00 0 
7f2f320ec000-7f2f320ed000 r-xp 00000000 08:05 3418815                    /opt/ros/kinetic/lib/librosconsole_backend_interface.so
7f2f320ed000-7f2f322ec000 ---p 00001000 08:05 3418815                    /opt/ros/kinetic/lib/librosconsole_backend_interface.so
7f2f322ec000-7f2f322ed000 r--p 00000000 08:05 3418815                    /opt/ros/kinetic/lib/librosconsole_backend_interface.so
7f2f322ed000-7f2f322ee000 rw-p 00001000 08:05 3418815                    /opt/ros/kinetic/lib/librosconsole_backend_interface.so
7f2f322ee000-7f2f32304000 r-xp 00000000 08:05 3418816                    /opt/ros/kinetic/lib/librosconsole_log4cxx.so
7f2f32304000-7f2f32504000 ---p 00016000 08:05 3418816                    /opt/ros/kinetic/lib/librosconsole_log4cxx.so
7f2f32504000-7f2f32506000 r--p 00016000 08:05 3418816                    /opt/ros/kinetic/lib/librosconsole_log4cxx.so
7f2f32506000-7f2f32507000 rw-p 00018000 08:05 3418816                    /opt/ros/kinetic/lib/librosconsole_log4cxx.so
7f2f32507000-7f2f3251e000 r-xp 00000000 08:05 271397                     /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.58.0
7f2f3251e000-7f2f3271d000 ---p 00017000 08:05 271397                     /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.58.0
7f2f3271d000-7f2f3271e000 r--p 00016000 08:05 271397                     /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.58.0
7f2f3271e000-7f2f3271f000 rw-p 00017000 08:05 271397                     /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.58.0
7f2f3271f000-7f2f32725000 r-xp 00000000 08:05 275720                     /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0
7f2f32725000-7f2f32925000 ---p 00006000 08:05 275720                     /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0
7f2f32925000-7f2f32926000 r--p 00006000 08:05 275720                     /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0
7f2f32926000-7f2f32927000 rw-p 00007000 08:05 275720                     /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0
7f2f32927000-7f2f3294b000 r-xp 00000000 08:05 266978                     /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0
7f2f3294b000-7f2f32b4a000 ---p 00024000 08:05 266978                     /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0
7f2f32b4a000-7f2f32b4c000 r--p 00023000 08:05 266978                     /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0
7f2f32b4c000-7f2f32b4d000 rw-p 00025000 08:05 266978                     /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0
7f2f32b4d000-7f2f32b54000 r-xp 00000000 08:05 3418811                    /opt/ros/kinetic/lib/libcpp_common.so
7f2f32b54000-7f2f32d53000 ---p 00007000 08:05 3418811                    /opt/ros/kinetic/lib/libcpp_common.so
7f2f32d53000-7f2f32d54000 r--p 00006000 08:05 3418811                    /opt/ros/kinetic/lib/libcpp_common.so
7f2f32d54000-7f2f32d55000 rw-p 00007000 08:05 3418811                    /opt/ros/kinetic/lib/libcpp_common.so
7f2f32d55000-7f2f32d73000 r-xp 00000000 08:05 3418817                    /opt/ros/kinetic/lib/libxmlrpcpp.so
7f2f32d73000-7f2f32f72000 ---p 0001e000 08:05 3418817                    /opt/ros/kinetic/lib/libxmlrpcpp.so
7f2f32f72000-7f2f32f73000 r--p 0001d000 08:05 3418817                    /opt/ros/kinetic/lib/libxmlrpcpp.so
7f2f32f73000-7f2f32f74000 rw-p 0001e000 08:05 3418817                    /opt/ros/kinetic/lib/libxmlrpcpp.so
7f2f32f74000-7f2f32f8d000 r-xp 00000000 08:05 5247999                    /lib/x86_64-linux-gnu/libz.so.1.2.8
7f2f32f8d000-7f2f3318c000 ---p 00019000 08:05 5247999                    /lib/x86_64-linux-gnu/libz.so.1.2.8
7f2f3318c000-7f2f3318d000 r--p 00018000 08:05 5247999                    /lib/x86_64-linux-gnu/libz.so.1.2.8
7f2f3318d000-7f2f3318e000 rw-p 00019000 08:05 5247999                    /lib/x86_64-linux-gnu/libz.so.1.2.8
7f2f3318e000-7f2f33195000 r-xp 00000000 08:05 5247962                    /lib/x86_64-linux-gnu/librt-2.23.so
7f2f33195000-7f2f33394000 ---p 00007000 08:05 5247962                    /lib/x86_64-linux-gnu/librt-2.23.so
7f2f33394000-7f2f33395000 r--p 00006000 08:05 5247962                    /lib/x86_64-linux-gnu/librt-2.23.so
7f2f33395000-7f2f33396000 rw-p 00007000 08:05 5247962                    /lib/x86_64-linux-gnu/librt-2.23.so
7f2f33396000-7f2f33399000 r-xp 00000000 08:05 5247832                    /lib/x86_64-linux-gnu/libdl-2.23.so
7f2f33399000-7f2f33598000 ---p 00003000 08:05 5247832                    /lib/x86_64-linux-gnu/libdl-2.23.so
7f2f33598000-7f2f33599000 r--p 00002000 08:05 5247832                    /lib/x86_64-linux-gnu/libdl-2.23.so
7f2f33599000-7f2f3359a000 rw-p 00003000 08:05 5247832                    /lib/x86_64-linux-gnu/libdl-2.23.so
7f2f3359a000-7f2f3369d000 r-xp 00000000 08:05 266977                     /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.58.0
7f2f3369d000-7f2f3389d000 ---p 00103000 08:05 266977                     /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.58.0
7f2f3389d000-7f2f338a1000 r--p 00103000 08:05 266977                     /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.58.0
7f2f338a1000-7f2f338a2000 rw-p 00107000 08:05 266977                     /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.58.0
7f2f338a2000-7f2f33cbf000 r-xp 00000000 08:05 3418949                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_imgcodecs3.so.3.3.1
7f2f33cbf000-7f2f33ebf000 ---p 0041d000 08:05 3418949                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_imgcodecs3.so.3.3.1
7f2f33ebf000-7f2f33ec5000 r--p 0041d000 08:05 3418949                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_imgcodecs3.so.3.3.1
7f2f33ec5000-7f2f33ed0000 rw-p 00423000 08:05 3418949                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_imgcodecs3.so.3.3.1
7f2f33ed0000-7f2f33ed1000 rw-p 00000000 00:00 0 
7f2f33ed1000-7f2f33fd9000 r-xp 00000000 08:05 5247878                    /lib/x86_64-linux-gnu/libm-2.23.so
7f2f33fd9000-7f2f341d8000 ---p 00108000 08:05 5247878                    /lib/x86_64-linux-gnu/libm-2.23.so
7f2f341d8000-7f2f341d9000 r--p 00107000 08:05 5247878                    /lib/x86_64-linux-gnu/libm-2.23.so
7f2f341d9000-7f2f341da000 rw-p 00108000 08:05 5247878                    /lib/x86_64-linux-gnu/libm-2.23.so
7f2f341da000-7f2f341fa000 r-xp 00000000 08:05 1073685                    /usr/lib/atlas-base/libf77blas.so.3.0
7f2f341fa000-7f2f343f9000 ---p 00020000 08:05 1073685                    /usr/lib/atlas-base/libf77blas.so.3.0
7f2f343f9000-7f2f343fa000 rw-p 0001f000 08:05 1073685                    /usr/lib/atlas-base/libf77blas.so.3.0
7f2f343fa000-7f2f349d9000 r-xp 00000000 08:05 1073686                    /usr/lib/atlas-base/atlas/liblapack.so.3.0
7f2f349d9000-7f2f34bd9000 ---p 005df000 08:05 1073686                    /usr/lib/atlas-base/atlas/liblapack.so.3.0
7f2f34bd9000-7f2f34bde000 rw-p 005df000 08:05 1073686                    /usr/lib/atlas-base/atlas/liblapack.so.3.0
7f2f34bde000-7f2f34bfc000 r-xp 00000000 08:05 266240                     /usr/lib/x86_64-linux-gnu/libglog.so.0.0.0
7f2f34bfc000-7f2f34dfb000 ---p 0001e000 08:05 266240                     /usr/lib/x86_64-linux-gnu/libglog.so.0.0.0
7f2f34dfb000-7f2f34dfc000 r--p 0001d000 08:05 266240                     /usr/lib/x86_64-linux-gnu/libglog.so.0.0.0
7f2f34dfc000-7f2f34dfd000 rw-p 0001e000 08:05 266240                     /usr/lib/x86_64-linux-gnu/libglog.so.0.0.0
7f2f34dfd000-7f2f34e0d000 rw-p 00000000 00:00 0 
7f2f34e0d000-7f2f34ee8000 r-xp 00000000 08:05 3418972                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_features2d3.so.3.3.1
7f2f34ee8000-7f2f350e8000 ---p 000db000 08:05 3418972                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_features2d3.so.3.3.1
7f2f350e8000-7f2f350ed000 r--p 000db000 08:05 3418972                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_features2d3.so.3.3.1
7f2f350ed000-7f2f350ef000 rw-p 000e0000 08:05 3418972                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_features2d3.so.3.3.1
7f2f350ef000-7f2f350f0000 rw-p 00000000 00:00 0 
7f2f350f0000-7f2f35291000 r-xp 00000000 08:05 3418973                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_calib3d3.so.3.3.1
7f2f35291000-7f2f35491000 ---p 001a1000 08:05 3418973                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_calib3d3.so.3.3.1
7f2f35491000-7f2f35493000 r--p 001a1000 08:05 3418973                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_calib3d3.so.3.3.1
7f2f35493000-7f2f35494000 rw-p 001a3000 08:05 3418973                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_calib3d3.so.3.3.1
7f2f35494000-7f2f35495000 rw-p 00000000 00:00 0 
7f2f35495000-7f2f357fe000 r-xp 00000000 08:05 3418979                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_video3.so.3.3.1
7f2f357fe000-7f2f359fd000 ---p 00369000 08:05 3418979                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_video3.so.3.3.1
7f2f359fd000-7f2f359ff000 r--p 00368000 08:05 3418979                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_video3.so.3.3.1
7f2f359ff000-7f2f35a0a000 rw-p 0036a000 08:05 3418979                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_video3.so.3.3.1
7f2f35a0a000-7f2f35a1a000 r-xp 00000000 08:05 1063431                    /home/rap/catkin_ov/src/ov2slam/Thirdparty/ibow_lcd/build/liblcdetector.so
7f2f35a1a000-7f2f35c1a000 ---p 00010000 08:05 1063431                    /home/rap/catkin_ov/src/ov2slam/Thirdparty/ibow_lcd/build/liblcdetector.so
7f2f35c1a000-7f2f35c1b000 r--p 00010000 08:05 1063431                    /home/rap/catkin_ov/src/ov2slam/Thirdparty/ibow_lcd/build/liblcdetector.so
7f2f35c1b000-7f2f35c1c000 rw-p 00011000 08:05 1063431                    /home/rap/catkin_ov/src/ov2slam/Thirdparty/ibow_lcd/build/liblcdetector.so
7f2f35c1c000-7f2f35ee7000 r-xp 00000000 08:05 3418955                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_xfeatures2d3.so.3.3.1
7f2f35ee7000-7f2f360e7000 ---p 002cb000 08:05 3418955                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_xfeatures2d3.so.3.3.1
7f2f360e7000-7f2f360eb000 r--p 002cb000 08:05 3418955                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_xfeatures2d3.so.3.3.1
7f2f360eb000-7f2f360ec000 rw-p 002cf000 08:05 3418955                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_xfeatures2d3.so.3.3.1
7f2f360ec000-7f2f36117000 r-xp 00000000 08:05 3418812                    /opt/ros/kinetic/lib/librostime.so
7f2f36117000-7f2f36316000 ---p 0002b000 08:05 3418812                    /opt/ros/kinetic/lib/librostime.so
7f2f36316000-7f2f36318000 r--p 0002a000 08:05 3418812                    /opt/ros/kinetic/lib/librostime.so
7f2f36318000-7f2f36319000 rw-p 0002c000 08:05 3418812                    /opt/ros/kinetic/lib/librostime.so
7f2f36319000-7f2f3634f000 r-xp 00000000 08:05 3419121                    /opt/ros/kinetic/lib/libtf.so
7f2f3634f000-7f2f3654f000 ---p 00036000 08:05 3419121                    /opt/ros/kinetic/lib/libtf.so
7f2f3654f000-7f2f36551000 r--p 00036000 08:05 3419121                    /opt/ros/kinetic/lib/libtf.so
7f2f36551000-7f2f36552000 rw-p 00038000 08:05 3419121                    /opt/ros/kinetic/lib/libtf.so
7f2f36552000-7f2f38b71000 r-xp 00000000 08:05 3418939                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_imgproc3.so.3.3.1
7f2f38b71000-7f2f38d71000 ---p 0261f000 08:05 3418939                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_imgproc3.so.3.3.1
7f2f38d71000-7f2f38d87000 r--p 0261f000 08:05 3418939                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_imgproc3.so.3.3.1
7f2f38d87000-7f2f38da9000 rw-p 02635000 08:05 3418939                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_imgproc3.so.3.3.1
7f2f38da9000-7f2f38e48000 rw-p 00000000 00:00 0 
7f2f38e48000-7f2f39008000 r-xp 00000000 08:05 5247808                    /lib/x86_64-linux-gnu/libc-2.23.so
7f2f39008000-7f2f39208000 ---p 001c0000 08:05 5247808                    /lib/x86_64-linux-gnu/libc-2.23.so
7f2f39208000-7f2f3920c000 r--p 001c0000 08:05 5247808                    /lib/x86_64-linux-gnu/libc-2.23.so
7f2f3920c000-7f2f3920e000 rw-p 001c4000 08:05 5247808                    /lib/x86_64-linux-gnu/libc-2.23.so
7f2f3920e000-7f2f39212000 rw-p 00000000 00:00 0 
7f2f39212000-7f2f39229000 r-xp 00000000 08:05 5247555                    /lib/x86_64-linux-gnu/libgcc_s.so.1
7f2f39229000-7f2f39428000 ---p 00017000 08:05 5247555                    /lib/x86_64-linux-gnu/libgcc_s.so.1
7f2f39428000-7f2f39429000 r--p 00016000 08:05 5247555                    /lib/x86_64-linux-gnu/libgcc_s.so.1
7f2f39429000-7f2f3942a000 rw-p 00017000 08:05 5247555                    /lib/x86_64-linux-gnu/libgcc_s.so.1
7f2f3942a000-7f2f395fd000 r-xp 00000000 08:05 281605                     /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.28
7f2f395fd000-7f2f397fd000 ---p 001d3000 08:05 281605                     /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.28
7f2f397fd000-7f2f39808000 r--p 001d3000 08:05 281605                     /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.28
7f2f39808000-7f2f3980b000 rw-p 001de000 08:05 281605                     /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.28
7f2f3980b000-7f2f3980e000 rw-p 00000000 00:00 0 
7f2f3980e000-7f2f39826000 r-xp 00000000 08:05 5247954                    /lib/x86_64-linux-gnu/libpthread-2.23.so
7f2f39826000-7f2f39a25000 ---p 00018000 08:05 5247954                    /lib/x86_64-linux-gnu/libpthread-2.23.so
7f2f39a25000-7f2f39a26000 r--p 00017000 08:05 5247954                    /lib/x86_64-linux-gnu/libpthread-2.23.so
7f2f39a26000-7f2f39a27000 rw-p 00018000 08:05 5247954                    /lib/x86_64-linux-gnu/libpthread-2.23.so
7f2f39a27000-7f2f39a2b000 rw-p 00000000 00:00 0 
7f2f39a2b000-7f2f39a2e000 r-xp 00000000 08:05 271399                     /usr/lib/x86_64-linux-gnu/libboost_system.so.1.58.0
7f2f39a2e000-7f2f39c2d000 ---p 00003000 08:05 271399                     /usr/lib/x86_64-linux-gnu/libboost_system.so.1.58.0
7f2f39c2d000-7f2f39c2e000 r--p 00002000 08:05 271399                     /usr/lib/x86_64-linux-gnu/libboost_system.so.1.58.0
7f2f39c2e000-7f2f39c2f000 rw-p 00003000 08:05 271399                     /usr/lib/x86_64-linux-gnu/libboost_system.so.1.58.0
7f2f39c2f000-7f2f39c5e000 r-xp 00000000 08:05 3418814                    /opt/ros/kinetic/lib/librosconsole.so
7f2f39c5e000-7f2f39e5e000 ---p 0002f000 08:05 3418814                    /opt/ros/kinetic/lib/librosconsole.so
7f2f39e5e000-7f2f39e60000 r--p 0002f000 08:05 3418814                    /opt/ros/kinetic/lib/librosconsole.so
7f2f39e60000-7f2f39e61000 rw-p 00031000 08:05 3418814                    /opt/ros/kinetic/lib/librosconsole.so
7f2f39e61000-7f2f39e63000 r-xp 00000000 08:05 3418813                    /opt/ros/kinetic/lib/libroscpp_serialization.so
7f2f39e63000-7f2f3a062000 ---p 00002000 08:05 3418813                    /opt/ros/kinetic/lib/libroscpp_serialization.so
7f2f3a062000-7f2f3a063000 r--p 00001000 08:05 3418813                    /opt/ros/kinetic/lib/libroscpp_serialization.so
7f2f3a063000-7f2f3a064000 rw-p 00002000 08:05 3418813                    /opt/ros/kinetic/lib/libroscpp_serialization.so
7f2f3a064000-7f2f3a1ec000 r-xp 00000000 08:05 3418818                    /opt/ros/kinetic/lib/libroscpp.so
7f2f3a1ec000-7f2f3a3ec000 ---p 00188000 08:05 3418818                    /opt/ros/kinetic/lib/libroscpp.so
7f2f3a3ec000-7f2f3a3f2000 r--p 00188000 08:05 3418818                    /opt/ros/kinetic/lib/libroscpp.so
7f2f3a3f2000-7f2f3a3f6000 rw-p 0018e000 08:05 3418818                    /opt/ros/kinetic/lib/libroscpp.so
7f2f3a3f6000-7f2f3b0f9000 r-xp 00000000 08:05 3418980                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_core3.so.3.3.1
7f2f3b0f9000-7f2f3b2f9000 ---p 00d03000 08:05 3418980                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_core3.so.3.3.1
7f2f3b2f9000-7f2f3b305000 r--p 00d03000 08:05 3418980                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_core3.so.3.3.1
7f2f3b305000-7f2f3b32b000 rw-p 00d0f000 08:05 3418980                    /opt/ros/kinetic/lib/x86_64-linux-gnu/libopencv_core3.so.3.3.1
7f2f3b32b000-7f2f3b330000 rw-p 00000000 00:00 0 
7f2f3b330000-7f2f3b358000 r-xp 00000000 08:05 3419083                    /opt/ros/kinetic/lib/libcv_bridge.so
7f2f3b358000-7f2f3b557000 ---p 00028000 08:05 3419083                    /opt/ros/kinetic/lib/libcv_bridge.so
7f2f3b557000-7f2f3b559000 r--p 00027000 08:05 3419083                    /opt/ros/kinetic/lib/libcv_bridge.so
7f2f3b559000-7f2f3b55a000 rw-p 00029000 08:05 3419083                    /opt/ros/kinetic/lib/libcv_bridge.so
7f2f3b55a000-7f2f3bb9c000 r-xp 00000000 08:05 1087192                    /home/rap/catkin_ov/devel/lib/libov2slam.so
7f2f3bb9c000-7f2f3bd9b000 ---p 00642000 08:05 1087192                    /home/rap/catkin_ov/devel/lib/libov2slam.so
7f2f3bd9b000-7f2f3bda3000 r--p 00641000 08:05 1087192                    /home/rap/catkin_ov/devel/lib/libov2slam.so
7f2f3bda3000-7f2f3bdaa000 rw-p 00649000 08:05 1087192                    /home/rap/catkin_ov/devel/lib/libov2slam.so
7f2f3bdaa000-7f2f3bdab000 rw-p 00000000 00:00 0 
7f2f3bdab000-7f2f3bdd1000 r-xp 00000000 08:05 5247780                    /lib/x86_64-linux-gnu/ld-2.23.so
7f2f3be00000-7f2f3bf7d000 rw-p 00000000 00:00 0 
7f2f3bfbc000-7f2f3bfd0000 rw-p 00000000 00:00 0 
7f2f3bfd0000-7f2f3bfd1000 r--p 00025000 08:05 5247780                    /lib/x86_64-linux-gnu/ld-2.23.so
7f2f3bfd1000-7f2f3bfd2000 rw-p 00026000 08:05 5247780                    /lib/x86_64-linux-gnu/ld-2.23.so
7f2f3bfd2000-7f2f3bfd3000 rw-p 00000000 00:00 0 
7ffdcbf73000-7ffdcbf93000 rwxp 00000000 00:00 0                          [stack]
7ffdcbf93000-7ffdcbf95000 rw-p 00000000 00:00 0 
7ffdcbf95000-7ffdcbf98000 r--p 00000000 00:00 0                          [vvar]
7ffdcbf98000-7ffdcbf9a000 r-xp 00000000 00:00 0                          [vdso]
ffffffffff600000-ffffffffff601000 r-xp 00000000 00:0和热0 0                  [vsyscall]

Error while running rosrun

I got this error when running rosrun ov2slam ov2slam_node parameter_file.yaml could you please help

Loading parameters file : parameter_file.yaml...
Failed to open settings file...

I encountered some problems running rosrun ov2slam ov2slam_node

Use LoopCLoser : 0
Starting the measurements reader thread!
>>> Init current parallax (0.466868 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.252692 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.604587 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.154153 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.282535 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.526127 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.244141 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.535359 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.472971 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.674219 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.705831 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.656366 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.695807 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.6398 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.729231 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.99357 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.24852 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.0204 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.02562 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.949801 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.816886 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (0.952165 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.0405 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.07615 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.09784 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.01908 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.49889 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (2.01812 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.93337 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (2.23187 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (2.24096 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (2.24164 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (2.22841 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (1.65796 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (2.90082 px)

  • [Visual-Front-End]: Not ready to init yet!

    Init current parallax (5.06881 px)
    Stack trace (most recent call last) in thread 8588:
    #10 Object "", at 0xffffffffffffffff, in
    #9 Source "../sysdeps/unix/sysv/linux/x86_64/clone.S", line 95, in clone [0x7efe2098a71e]
    #8 Source "/build/glibc-S9d2JN/glibc-2.27/nptl/pthread_create.c", line 463, in start_thread [0x7efe20e796da]
    #7 Source "/home/builder/ktietz/cos6/ci_cos6/ctng-compilers_1622658800915/work/.build/x86_64-conda-linux-gnu/src/gcc/libstdc++-v3/src/c++11/thread.cc", line 80, in execute_native_thread_routine [0x7efe22a0b038]
    #6 Source "/home/sjy/catkin_ws/src/ov2slam/src/ov2slam.cpp", line 156, in run [0x7efe2214723c]
    153: if( pslamstate
    ->debug
    )
    154: std::cout << "\n \t >>> [SLAM Node] New image send to Front-End\n";
    155:
    156: bool is_kf_req = pvisualfrontend_->visualTracking(img_left, time);
    157:
    158: // Save current pose
    159: Logger::addSE3Pose(time, pcurframe_->getTwc(), is_kf_req);
    #5 Source "/home/sjy/catkin_ws/src/ov2slam/src/visual_front_end.cpp", line 47, in visualTracking [0x7efe22163200]
    44: if( pslamstate_->debug_ || pslamstate_->log_timings_ )
    45: Profiler::Start("0.Full-Front_End");
    46:
    47: bool iskfreq = trackMono(iml, time);
    48:
    49: if( iskfreq ) {
    50: pmap_->createKeyframe(cur_img_, iml);
    #4 Source "/home/sjy/catkin_ws/src/ov2slam/src/visual_front_end.cpp", line 95, in trackMono [0x7efe22162ee0]
    93: if( pslamstate_->doepipolar_ ) {
    94: // Check2d2dOutliers
    95: epipolar2d2dFiltering();
    96: }
    97:
    98: if( pslamstate_->mono_ && !pslamstate_->bvision_init_ )
    #3 Source "/home/sjy/catkin_ws/src/ov2slam/src/visual_front_end.cpp", line 569, in epipolar2d2dFiltering [0x7efe221623e1]
    566: pcurframe_->pcalib_leftcam_->fx_,
    567: pcurframe_->pcalib_leftcam_->fy_,
    568: Rkfc, tkfc,
    569: voutliersidx);
    570:
    571: if( pslamstate_->debug_ )
    572: std::cout << "\n \t>>> Epipolar nb outliers : " << voutliersidx.size();
    #2 Source "/home/sjy/catkin_ws/src/ov2slam/src/multi_view_geometry.cpp", line 662, in opengv5ptEssentialMatrix [0x7efe221ab64d]
    659: // ransac.threshold_ = (1.0 - cos(atan(errth/focal)));
    660: ransac.max_iterations_ = nmaxiter;
    661:
    662: ransac.computeModel(0);
    663:
    664: // If no solution found, return false
    665: if( ransac.inliers_.size() < 10 ) {
    #1 Source "/usr/local/include/opengv/sac/implementation/Ransac.hpp", line 78, in computeModel [0x7efe221adcc9]
    75: }
    76:
    77: // Search for inliers in the point cloud for the current plane model M
    78: if(!sac_model_->computeModelCoefficients( selection, model_coefficients ))
    79: {
    80: //++iterations_;
    81: ++ skipped_count;
    #0 Object "/home/sjy/catkin_ws/devel/lib/libov2slam.so", at 0x7efe222049d8, in opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem::computeModelCoefficients(std::vector<int, std::allocator > const&, Eigen::Matrix<double, 3, 4, 0, 3, 4>&) const
    Segmentation fault (Signal sent by the kernel [(nil)])
    段错误 (核心已转储)

some detail question

Hi,
nice work!
I have two question when I read the code as follows.

 [1]. visual_front_end.cpp line521,  **" if( nbkps < 8 )"**  why doesn't  "if(nbparallax < 8)"

 [2].ceres_parametrization.cpp line180  **"J_se3pose.block<2,3>(0,3).noalias() = J_lRcw * Sophus::SO3d::hat(wpt);"**
      I think **"J_se3pose.block<2,3>(0,3).noalias() = J_lRcw * Sophus::SO3d::hat(wpt-twc);"** is more accurate

Segmentation fault

When I try to launch ov2slam_node the following error appears:

Launching OV²SLAM...


Loading parameters file : src/ov2slam/parameters_files/example/example.yaml...
Stack trace (most recent call last):
#2    Object "/lib/aarch64-linux-gnu/libc.so.6", at 0x7f7f1c757b, in __vsnprintf_chk
#1    Object "/lib/aarch64-linux-gnu/libc.so.6", at 0x7f7f130f37, in vfprintf
#0    Object "/lib/aarch64-linux-gnu/libc.so.6", at 0x7f7f164450, in strlen
Segmentation fault (Address not mapped to object [0x65646f4e646461])
Segmentation fault (core dumped)

I have used -march=native flag for OpenGV and used the bundled ceres.

Do you have any idea what is causing it?

OpenCV Include problem

Hello devs,

I am trying to build the project. I am getting this OpenCV include problem:

/home/sxv1kor/OV2SLAM/catkin_ws/src/ov2slam/src/feature_extractor.cpp:36:10: fatal error: opencv2/xfeatures2d.hpp: No such file or directory
   36 | #include <opencv2/xfeatures2d.hpp>

I have opencv-contrib installed in my system:

sudo apt install libopencv-contrib-dev libopencv-contrib4.2 
Reading package lists... Done
Building dependency tree       
Reading state information... Done
libopencv-contrib-dev is already the newest version (4.2.0+dfsg-5).
libopencv-contrib4.2 is already the newest version (4.2.0+dfsg-5).
0 upgraded, 0 newly installed, 0 to remove and 288 not upgraded.

So i explicitly included in CMakeLists.txt:

find_package(OpenCV REQUIRED)
include_directories( ${OpenCV_INCLUDE_DIRS} )
message(STATUS "Found OpenCV include libraries at: ${OpenCV_INCLUDE_DIRS} ")

And I can see that the dirs are there:

-- Found OpenCV: /usr (found version "4.2.0") 
-- Found OpenCV include libraries at: /usr/include/opencv4 

Now why is the project not including the headers ?

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.