Giter Club home page Giter Club logo

kimera-vio's Introduction

Kimera-VIO: Open-Source Visual Inertial Odometry

Build Status For evaluation plots, check our jenkins server.

Authors: Antoni Rosinol, Yun Chang, Marcus Abate, Nathan Hughes, Sandro Berchier, Luca Carlone

What is Kimera-VIO?

Kimera-VIO is a Visual Inertial Odometry pipeline for accurate State Estimation from Stereo + IMU data. It can optionally use Mono + IMU data instead of stereo cameras.

Publications

We kindly ask to cite our paper if you find this library useful:

@InProceedings{Rosinol20icra-Kimera,
  title = {Kimera: an Open-Source Library for Real-Time Metric-Semantic Localization and Mapping},
  author = {Rosinol, Antoni and Abate, Marcus and Chang, Yun and Carlone, Luca},
  year = {2020},
  booktitle = {IEEE Intl. Conf. on Robotics and Automation (ICRA)},
  url = {https://github.com/MIT-SPARK/Kimera},
  pdf = {https://arxiv.org/pdf/1910.02490.pdf}
}
@article{Rosinol21arxiv-Kimera,
   title = {Kimera: from {SLAM} to Spatial Perception with {3D} Dynamic Scene Graphs},
   author = {Rosinol, Antoni and Violette, Andrew and Abate, Marcus and Hughes, Nathan and Chang, Yun
   and Shi, Jingnan and Gupta, Arjun and Carlone, Luca},
   year = {2021},
   journal = {arXiv preprint arXiv: 2101.06894},
   pdf = {https://arxiv.org/pdf/2101.06894.pdf} 
}

Related Publications

Backend optimization is based on:

Alternatively, the Regular VIO Backend, using structural regularities, is described in this paper:

Demo

1. Installation

Tested on Ubuntu 20.04.

Prerequisites

Note: if you want to avoid building all dependencies yourself, we provide a docker image that will install them for you. Check installation instructions in docs/kimera_vio_install.md.

Note 2: if you use ROS, then Kimera-VIO-ROS can install all dependencies and Kimera inside a catkin workspace.

Installation Instructions

Find how to install Kimera-VIO and its dependencies here: Installation instructions.

2. Usage

General tips

The LoopClosureDetector (and PGO) module is disabled by default. If you wish to run the pipeline with loop-closure detection enabled, set the use_lcd flag to true. For the example script, this is done by passing -lcd at commandline like so:

./scripts/stereoVIOEUROC.bash -lcd

To log output, set the log_output flag to true. For the script, this is done with the -log commandline argument. By default, log files will be saved in output_logs.

To run the pipeline in sequential mode (one thread only), set parallel_runto false. This can be done in the example script with the -s argument at commandline.

i. Euroc Dataset

Download Euroc's dataset

Datasets MH_04 and V2_03 have different number of left/right frames. We suggest using instead our version of Euroc here.

  • Unzip the dataset to your preferred directory, for example, in ~/Euroc/V1_01_easy:
mkdir -p ~/Euroc/V1_01_easy
unzip -o ~/Downloads/V1_01_easy.zip -d ~/Euroc/V1_01_easy

Yamelize Euroc's dataset

Add %YAML:1.0 at the top of each .yaml file inside Euroc. You can do this manually or run the yamelize.bash script by indicating where the dataset is (it is assumed below to be in ~/path/to/euroc):

You don't need to yamelize the dataset if you download our version here

cd Kimera-VIO
bash ./scripts/euroc/yamelize.bash -p ~/path/to/euroc

Run Kimera-VIO in Euroc's dataset

Using a bash script bundling all command-line options and gflags:

cd Kimera-VIO
bash ./scripts/stereoVIOEuroc.bash -p "PATH_TO_DATASET/V1_01_easy"

Alternatively, one may directly use the executable in the build folder: ./build/stereoVIOEuroc. Nevertheless, check the script ./scripts/stereoVIOEuroc.bash to understand what parameters are expected, or check the parameters section below.

Kimera can also run in monocular mode. For Euroc, this means only processing the left image. To use this simply use the parameters in params/EurocMono. In the bash script there is a PARAMS_PATH variable that can be set to point to these parameters instead.

ii. Using ROS wrapper

We provide a ROS wrapper of Kimera-VIO that you can find at: https://github.com/MIT-SPARK/Kimera-VIO-ROS.

This library can be cloned into a catkin workspace and built alongside the ROS wrapper.

iii. Evaluation and Debugging

For more information on tools for debugging and evaluating the pipeline, see our documentation

iv. Unit Testing

We use gtest for unit testing. To run the unit tests: build the code, navigate inside the build folder and run testKimeraVIO:

cd build
./testKimeraVIO

A useful flag is ./testKimeraVIO --gtest_filter=foo to only run the test you are interested in (regex is also valid).

Alternatively, you can run rosrun kimera_vio run_gtest.py from anywhere on your system if you've built Kimera-VIO through ROS and sourced the workspace containing Kimera-VIO. This script passes all arguments to testKimeraVIO, so you should feel free to use whatever flags you would normally use.

3. Parameters

Kimera-VIO accepts two independent sources of parameters:

  • YAML files: contains parameters for Backend and Frontend.
  • gflags contains parameters for all the rest.

To get help on what each gflag parameter does, just run the executable with the --help flag: ./build/stereoVIOEuroc --help. You should get a list of gflags similar to the ones here.

  • Optionally, you can try the VIO using structural regularities, as in our ICRA 2019 paper, by specifying the option -r: ./stereoVIOEuroc.bash -p "PATH_TO_DATASET/V1_01_easy" -r

OpenCV's 3D visualization also has some shortcuts for interaction: check tips for usage

Camera parameters can be described using the pinhole model or the omni model. The omni model is based on the OCamCalib toolbox described in this paper. A tutorial for generating the calibration can be found here.

The Omni camera model requires these additional parameters:

omni_affine
omni_distortion_center

The distortion polynomial is stored in the distortion_coefficients field. The matlab toolbox gives only 4 coefficients as output, however Kimera supports 5 coefficients. The second one can be set to zero. For example, if your output from OCamCalib is [1, 2, 3, 4] then you can set distortion_coefficients to [1, 0, 2, 3, 4] in the camera parameters file.

Inverse polynomial for projection is not required. In the omni camera case, the intrinsics field represents the intrinsics of a ideal pinhole model of the fisheye camera, which is primarily used when instantiating gtsam calibrations that currently are only implemented for pinhole cameras. Leaving it blank is sufficient as the code will generate a ideal model based on the image size. You may supply your own ideal pinhole intrinsics and they will be used instead. In the pinhole case, these values must be supplied consistently with the camera parameters (focal lengths and image center).

4. Contribution guidelines

We strongly encourage you to submit issues, feedback and potential improvements. We follow the branch, open PR, review, and merge workflow.

To contribute to this repo, ensure your commits pass the linter pre-commit checks. To enable these checks you will need to install linter. We also provide a .clang-format file with the style rules that the repo uses, so that you can use clang-format to reformat your code.

Also, check tips for development and our developer guide.

5. FAQ

Issues

If you have problems building or running the pipeline and/or issues with dependencies, you might find useful information in our FAQ or in the issue tracker.

How to interpret console output

I0512 21:05:55.136549 21233 Pipeline.cpp:449] Statistics
-----------                                  #	Log Hz	{avg     +- std    }	[min,max]
Data Provider [ms]                      	    0	
Display [ms]                            	  146	36.5421	{8.28082 +- 2.40370}	[3,213]
VioBackend [ms]                         	   73	19.4868	{15.2192 +- 9.75712}	[0,39]
VioFrontend Frame Rate [ms]             	  222	59.3276	{5.77027 +- 1.51571}	[3,12]
VioFrontend Keyframe Rate [ms]          	   73	19.6235	{31.4110 +- 7.29504}	[24,62]
VioFrontend [ms]                        	  295	77.9727	{12.1593 +- 10.7279}	[3,62]
Visualizer [ms]                         	   73	19.4639	{3.82192 +- 0.805234}	[2,7]
backend_input_queue Size [#]            	   73	18.3878	{1.00000 +- 0.00000}	[1,1]
data_provider_left_frame_queue Size (#) 	  663	165.202	{182.265 +- 14.5110}	[1,359]
data_provider_right_frame_queue Size (#)	  663	165.084	{182.029 +- 14.5150}	[1,359]
display_input_queue Size [#]            	  146	36.5428	{1.68493 +- 0.00000}	[1,12]
stereo_frontend_input_queue Size [#]    	  301	75.3519	{4.84718 +- 0.219043}	[1,5]
visualizer_backend_queue Size [#]       	   73	18.3208	{1.00000 +- 0.00000}	[1,1]
visualizer_frontend_queue Size [#]      	  295	73.9984	{4.21695 +- 1.24381}	[1,7]
  • # number of samples taken.
  • Log Hz average number of samples taken per second in Hz.
  • avg average of the actual value logged. Same unit as the logged quantity.
  • std standard deviation of the value logged.
  • [min,max] minimum and maximum values that the logged value took.

There are two main things logged: the time it takes for the pipeline modules to run (i.e. VioBackend, Visualizer etc), and the size of the queues between pipeline modules (i.e. backend_input_queue).

For example:

VioBackend [ms]                         	   73	19.4868	{15.2192 +- 9.75712}	[0,39]

Shows that the Backend runtime got sampled 73 times, at a rate of 19.48Hz (which accounts for both the time the Backend waits for input to consume and the time it takes to process it). That it takes 15.21ms to consume its input with a standard deviation of 9.75ms and that the least it took to run for one input was 0ms and the most it took so far is 39ms.

For the queues, for example:

stereo_frontend_input_queue Size [#]    	  301	75.3519	{4.84718 +- 0.219043}	[1,5]

Shows that the Frontend input queue got sampled 301 times, at a rate of 75.38Hz. That it stores an average of 4.84 elements, with a standard deviation of 0.21 elements, and that the min size it had was 1 element, and the max size it stored was of 5 elements.

6. Chart

vio_chart

overall_chart

7. BSD License

Kimera-VIO is open source under the BSD license, see the LICENSE.BSD file.

kimera-vio's People

Contributors

andrewhaeffner avatar bearn01d avatar cheng-hsiung avatar dominic101 avatar jingnanshi avatar marcusabate avatar mhkabir avatar nathanhhughes avatar ruffsl avatar sandro-berchier avatar tonioteran avatar tonirv avatar violetteavi avatar wallbraker avatar yuluntian avatar yunzc 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  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

kimera-vio's Issues

Build errors with OpenCV 4

Description:
Prerequisites state that an OpenCV version >= 3.3.1 is needed, but the cmake find_package command cannot find a newer major version. When removing the 3.3.1, some components fail to build, e.g., StereoVisionFrontEnd.cpp, Tracker.cpp, StereoFrame.cpp.

Command:
Running make with OpenCV 4.0.0.

Console output:
OpenCV C API variables appear to not be within the scope; an additional include might be warranted for OpenCV >= 4. Some examples include:

  • CV_TM_SQDIFF_NORMED
  • CV_FONT_HERSHEY_COMPLEX
  • CV_FILLED
  • CV_THRESH_TOZERO

Some example output:

/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp: In static member function ‘static void VIO::UtilsOpenCV::ExtractCorners(const cv::Mat&, std::vector<cv::Point_<float> >*, const double&, const double&, int, const double&, bool)’:
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp:241:29: error: ‘CV_TERMCRIT_EPS’ was not declared in this scope
   cv::TermCriteria criteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 40, 0.001);
                             ^~~~~~~~~~~~~~~
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp:241:47: error: ‘CV_TERMCRIT_ITER’ was not declared in this scope
   cv::TermCriteria criteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 40, 0.001);
                                               ^~~~~~~~~~~~~~~~
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp: In static member function ‘static void VIO::UtilsOpenCV::MyGoodFeaturesToTrackSubPix(const cv::Mat&, const int&, const double&, double, const cv::Mat&, const int&, const bool&, const double&, std::pair<std::vector<cv::Point_<float> >, std::vector<double, std::allocator<double> > >*)’:
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp:288:55: error: ‘CV_THRESH_TOZERO’ was not declared in this scope
     cv::threshold(eig, eig, maxVal * qualityLevel, 0, CV_THRESH_TOZERO);
                                                       ^~~~~~~~~~~~~~~~
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp:400:31: error: ‘CV_TERMCRIT_EPS’ was not declared in this scope
     cv::TermCriteria criteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 40, 0.001);
                               ^~~~~~~~~~~~~~~
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp:400:49: error: ‘CV_TERMCRIT_ITER’ was not declared in this scope
     cv::TermCriteria criteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 40, 0.001);
                                                 ^~~~~~~~~~~~~~~~
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp: In static member function ‘static void VIO::UtilsOpenCV::PlainMatchTemplate(cv::Mat, cv::Mat, cv::Mat&)’:
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp:611:24: warning: comparison between signed and unsigned integer expressions [-Wsign-compare]
   for (size_t i = 0; i < result_rows; i++) {
                      ~~^~~~~~~~~~~~~
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp:612:26: warning: comparison between signed and unsigned integer expressions [-Wsign-compare]
     for (size_t j = 0; j < result_cols; j++) {
                        ~~^~~~~~~~~~~~~
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp: In static member function ‘static void VIO::UtilsOpenCV::DrawCirclesInPlace(cv::Mat&, const std::vector<cv::Point_<float> >&, const Scalar&, double, const std::vector<int>&, int)’:
/home/tonio/repos/Kimera-VIO/src/UtilsOpenCV.cpp:640:48: error: ‘CV_FONT_HERSHEY_COMPLEX’ was not declared in this scope
                   imagePoints[i] + textOffset, CV_FONT_HERSHEY_COMPLEX, 0.5,
                                                ^~~~~~~~~~~~~~~~~~~~~~~

Additional files:

  • OpenCV version used: 4.0.0
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Ubuntu 18.04
  • Did you change the source code? (yes / no): no

IMU Integration

I have a problem while integrating my sensor yaml files with Kimera-VIO as shown in the below text

No vio parameters specified, using default.
Applying IMU timestamp shift of: 3.59449e+246ns.
&&&&&&&&&&&&&&&&&&&& TRACKER PARAMETERS &&&&&&&&&&&&&&&&&&&&&&&&&&&
** Feature tracking parameters **
klt_win_size_: 24
klt_max_iter_: 30
klt_max_level_: 4
klt_eps_: 0.1
maxFeatureAge_: 15
** Feature detection parameters **
maxFeaturesPerFrame_: 800
quality_level_: 0.001
min_distance_: 20
block_size_: 3
use_harris_detector_: 0
k_: 0.04
** Sparse Stereo Matching parameters **
equalize_image_: 0
nominalBaseline_: 0.11
vision_sensor_type_: 0
toleranceTemplateMatching_: 0.15
templ_cols_: 101
templ_rows_: 11
stripe_extra_rows_: 0
minPointDist_: 0.5
maxPointDist_: 10
bidirectionalMatching_: 0
subpixelRefinementStereo_: 0
** Feature selection parameters **
featureSelectionCriterion_: 0
featureSelectionHorizon_: 3
featureSelectionNrCornersToSelect_: 600
featureSelectionImuRate_: 0.005
featureSelectionDefaultDepth_: 2
featureSelectionCosineNeighborhood_: 0.984808
featureSelectionUseLazyEvaluation_: 1
useSuccessProbabilities_: 1
** RANSAC parameters **
useRANSAC_: 1
minNrMonoInliers_: 10
minNrStereoInliers_: 5
ransac_threshold_mono_: 1e-06
ransac_threshold_stereo_: 1
ransac_use_1point_stereo_: 1
ransac_use_2point_mono_: 1
ransac_max_iterations_: 100
ransac_probability_: 0.995
ransac_randomize_: 0
** STEREO tracker parameters **
intra_keyframe_time_: 0.2
minNumberFeatures_: 0
useStereoTracking_: 1
** OTHER parameters **
disparityThreshold_: 0.5
&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&
LoopClosureDetector:: Loading vocabulary from ../vocabulary/ORBvoc.yml
Loaded vocabulary with 971815 visual words.
Spinning Visualizer.
Shutting down VIO pipeline once processing has finished.
Frontend launched (parallel_run set to 1).
------------------- Initialize Pipeline with frame k = 50--------------------
Spinning StereoFrontEnd.
getRectifiedImages: abnormal baseline: 0, nominalBaseline: 0.11(+/-10%)

Using Regular VIO with modality 0
[0, 0, 0]';isam_param
type: ISAM2GaussNewtonParams
wildfireThreshold: -1
relinearizeThreshold: 0.01
relinearizeSkip: 1
enableRelinearization: 1
evaluateNonlinearError: 0
factorization: CHOLESKY
cacheLinearizedFactors: 1
enableDetailedResults: 0
enablePartialRelinearizationCheck: 0
findUnusedFactorSlots: 1
Initial state seed:

  • Initial pose:
    |0.005, 5.4873e+247, 2.51834e-316|
    |0.133927, 6.52016e+252, 2.56383e-316|
    |1.61701, 1.60426e-316, 1.00444e-320|

[-nan, 0, 0]';

  • Initial vel: 4.94066e-324 000000000000 000000000000
  • Initial IMU bias: acc = [0, 0, 0]' gyro = [0, 0, 0]'

Indeterminant linear system detected while working near variable
8646911284551352320 (Symbol: x0).

Thrown when a linear system is ill-posed. The most common cause for this
error is having underconstrained variables. Mathematically, the system is
underdetermined. See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
ERROR: Variable has type 'x' and index 0
Smoother's factors:
[
size: 3

Factor 0: PriorFactor on x0
prior mean: R:
[
0.005 5.48729961e+247 2.51834192e-316;
0.13392721 6.52016458e+252 2.56383233e-316;
1.6170107 1.6042604e-316 1.00443546e-320
]
[-nan, 0, 0]'; noise model: Gaussian[
-nan -nan -nan -nan -nan -nan;
0 -nan -nan -nan -nan -nan;
0 0 -nan -nan -nan -nan;
0 0 0 -nan -nan -nan;
0 0 0 0 -nan -nan;
0 0 0 0 0 -nan
]

Factor 1: PriorFactor on v0
prior mean: [
4.94065646e-324;
0;
0
]
isotropic dim=3 sigma=0.001

Factor 2: PriorFactor on b0
prior mean: acc = [0, 0, 0]' gyro = [0, 0, 0]'
noise model: diagonal sigmas[0.1; 0.1; 0.1; 0.01; 0.01; 0.01];

]
State values
[
Values with 0 values:
]
=============== START:CATCHING EXCEPTION ===============
Nr of factors in graph (smoother getFactors): 3, with factors:
[

]
Nr of new factors to add: 0 with factors:
[
(slot # wrt to new_factors_tmp graph)

]
Nr deleted slots: 0, with slots:
[

]
Nr of values in state_ : 0, with keys:
[

]
Nr values in new_values_ : 0, with keys:
[

]
=============== END: CATCHING EXCEPTION ===============

Path planning and obstacle avoidance?

Great work, powerful tool, thanks for making it open source. Could you please outline how could this used for path planning and obstacle avoidance?
According to my modest knowledge voxblox uses ESDF which are a voxel grid where every point contains its Euclidean distance to the nearest obstacle. In voxblox, authors create ESDF from TSDF to be used for local and global path planning.

BEST REGARDS
thanks again

Support for an efficient Localization Mode

For scenarios where robots may return to, or continuously navigate, priorly explored environments, many SLAM pipelines are capable of loading/importing models of previous maped environments, e.g. a serialized pose graph, for pure localization purposes. For applications focused on navigation, rather than mere exploration, this offers a means to reduce computation overhead, as well as prior world map for global path planning.

LIDAR based pipelines, such as Slam Toolbox in 2D or Cartographer in 3D, often provide such importing of prior graphs and efficient localization mode features:

Localization

Localization mode consists of 3 things:

  • Loads existing serialized map into the node
  • Maintains a rolling buffer of recent scans in the pose-graph
  • After expiring from the buffer scans are removed and the underlying map is not affected

https://github.com/SteveMacenski/slam_toolbox#localization

Localization only

If you have a map you are happy with and want to reduce computations, you can use the localization-only mode of Cartographer which will run SLAM against the existing map and won’t build a new one. This is enabled by running cartographer_node with a -load_state_filename argument and by defining the following line in your lua config:

TRAJECTORY_BUILDER.pure_localization_trimmer = {
   max_submaps_to_keep = 3,
}

https://google-cartographer-ros.readthedocs.io/en/latest/going_further.html#localization-only
https://google-cartographer-ros.readthedocs.io/en/latest/assets_writer.html#exploiting-the-map-generated-by-cartographer-ros

I'm not as familiar with the internal architecture of Kimera-VIO, but was wondering if it would be possible to similarly load graph state from disk, and expose a parameter for trimming new pose, and landmark factors when operating under a localization mode runtime; similar to how Cartographer and SLAM Toolbox simply keep a rolling buffer of submaps/scans that are most recent to the current trajectory. I'm not sure how visual encoded landmarks could be retained, but am guessing there might already be some similar export/serialization function around for offline benchmarking.

VioBackEnd::addImuFactor norminal_rate usage inconsistent between comment and code

// 1/sqrt(nominalImuRate_) to discretize, then
// sqrt(pim_->deltaTij()/nominalImuRate_) to count the nr of measurements.
const double d = std::sqrt(pim.deltaTij()) / imu_params_.nominal_rate_;
Vector6 biasSigmas;
biasSigmas.head<3>().setConstant(d * imu_params_.acc_walk_);
biasSigmas.tail<3>().setConstant(d * imu_params_.gyro_walk_);

In the comment, nominalImuRate_ should add sqrt, but in the code when calculating the d, it does not use sqrt(). Since the nominal_rate_ is 1/imu_rate, it should mean deltaT between 2 continous imus. So the sqrt should be add when you calculate d. d should not have any unit since it is a ratio that will multiply on the imu_params_.acc_walk_. And based on the https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model the noise discrete model of gyroscope, we should not even use the nominal_rate right here, shouldn't it?

Out-door path failure

Description:
I am using ZED-2 Camera with its internal imu , and trying to record outdoor but the path is not correct

Command:

#TRACKER PARAMETERS
klt_win_size: 24
klt_max_iter: 30
klt_max_level: 4
klt_eps: 0.1
maxFeatureAge: 15
maxFeaturesPerFrame: 800  #it was 800
quality_level: 0.001
min_distance: 20
block_size: 3
use_harris_detector: 0
k: 0.04
equalizeImage: 0
nominalBaseline: 0.179622
toleranceTemplateMatching: 0.15
templ_cols: 101 #must be odd
templ_rows: 11
stripe_extra_rows: 0
minPointDist: 0.5
maxPointDist: 10
bidirectionalMatching: 0
subpixelRefinementStereo: 0
featureSelectionCriterion: 0  #(QUALITY, MIN_EIG, LOGDET, RANDOM)
featureSelectionHorizon: 3
featureSelectionNrCornersToSelect: 600
featureSelectionImuRate: 0.0025    #it was 0.005
featureSelectionDefaultDepth: 3
featureSelectionCosineNeighborhood: 0.984807753012208 # Rad
featureSelectionUseLazyEvaluation: 1
useSuccessProbabilities: 1
useRANSAC: 1
minNrMonoInliers: 10
minNrStereoInliers: 5
ransac_threshold_mono: 1e-06
ransac_threshold_stereo: 1
ransac_use_1point_stereo: 1
ransac_use_2point_mono: 1
ransac_max_iterations: 100
ransac_probability: 0.995
ransac_randomize: 0
intra_keyframe_time: 0.001 #it was 0.2
minNumberFeatures: 0
useStereoTracking: 1
display_time: 100
disparityThreshold: 0.2   #it was 0.5
--------------------------------------------------------------------------------------------------------

Console output:

I0316 17:37:10.589303  1896 VioBackEnd.cpp:1615]  =============== START:CATCHING EXCEPTION ===============
I0316 17:37:10.589303  1896 VioBackEnd.cpp:1643] Nr of factors in graph (graph before optimization): 4036, with factors:
I0316 17:37:10.589303  1896 VioBackEnd.cpp:1645] [
        Slot # 4035: Linear Container Factor:   Factor  b10 v10 x10 x11

I0316 17:37:10.590301  1896 VioBackEnd.cpp:1652]  ]
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1656] Nr of new factors to add: 196 with factors:
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1658] [
 (slot # wrt to new_factors_tmp graph)

I0316 17:37:10.590301  1896 VioBackEnd.cpp:1665]  ]
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1669] Nr deleted slots: 22, with slots:
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1671] [


I0316 17:37:10.590301  1896 VioBackEnd.cpp:1698]  ]
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1702] Nr of values in state_ : 69, with keys:
[
        b10 b11 b12 b13 b14 b15 b16 b17 b18 b19 b20 b21 b22 b23 b24 b25 b26 b27 b28 b29 b30 b31 b32 v10 v11 v12 v13 v14 v15 v16 v17 v18 v19 v20 v21 v22 v23 v24 v25 v26 v27 v28 v29 v30 v31 v32 x10 x11 x12 x13 x14 x15 x16 x17 x18 x19 x20 x21 x22 x23 x24 x25 x26 x27 x28 x29 x30 x31 x32
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1708]  ]
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1711] Nr values in new_values_ : 3, with keys:
[
         b33  v33  x33
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1719]  ]
I0316 17:37:10.590301  1896 VioBackEnd.cpp:1730]  =============== END: CATCHING EXCEPTION ===============

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used
  • GTSAM version used:
  • OpenGV version used:
  • OpenCV version used: type opencv_version
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Windows 10
  • Did you change the source code? (yes / no): no

Queue synchronizer error

Description:
I'm working on integrating Kimera into an MAV simulator. The simulator creates rectified stereo images and an IMU stream. I unfortunately can't share launch/param files due to confidentiality reasons, but they are basically Euroc's with a different camera/IMU model. I'm running through the ROS wrapper.

The sim is very slow in wall clock time, but uses sim_time to "speed up" to 60 Hz. Any ideas as to why I'm getting the queue synchronizer error below?

Command:

roslaunch kimera_vio_ros <launchfile>

Console output:

[ INFO] [1588266720.331173496]: Initializing pose graph visualizer
I0430 13:12:00.557873 15321 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0430 13:12:00.630167 15321 RosOnlineDataProvider.cpp:41] Waiting for ROS time to be valid... 
(Sim Time is enabled; run rosbag with --clock argument)
I0430 13:12:00.810081 15345 RosOnlineDataProvider.cpp:350] Spinning RosOnlineDataProvider.
I0430 13:12:00.810123 15346 Pipeline.h:174] Spinning Kimera-VIO.
I0430 13:12:00.810075 15321 KimeraVioRos.cpp:99] 
W0430 13:12:01.065454 15349 RosDataProviderInterface.cpp:118] Converting image...
W0430 13:12:01.336712 15346 DataProviderModule.cpp:115] Asking for data before start of IMU stream, from timestamp: 29444801089 to timestamp: 29460426094
I0430 13:12:01.346658 15345 RosOnlineDataProvider.cpp:383] Spinning RosOnlineDataProvider.
I0430 13:12:01.631211 15346 Pipeline.cpp:776] Frontend launched (parallel_run set to 1).
I0430 13:12:01.631243 15346 Pipeline.cpp:591] ------------------- Initialize Pipeline with frame k = 2--------------------
W0430 13:12:01.631251 15346 InitializationFromImu.cpp:26] InitializationFromImu: assumes that the vehicle is stationary and upright along some axis,and gravity vector is along a single axis!
I0430 13:12:01.704898 15346 Pipeline.cpp:300] Before launching threads.
I0430 13:12:01.704996 15346 Pipeline.cpp:805] Backend, mesher and visualizer launched (parallel_run set to 1).
I0430 13:12:01.705001 15346 Pipeline.cpp:302]  launching threads.
W0430 13:12:02.438673 15350 RosDataProviderInterface.cpp:118] Converting image...
W0430 13:12:03.792672 15350 RosDataProviderInterface.cpp:118] Converting image...
W0430 13:12:04.920267 15351 Tracker.cpp:578] 1-point RANSAC (voting) could not find a solution.
F0430 13:12:04.970415 15353 QueueSynchronizer.h:138] Check failed: timestamp == payload_timestamp (29678134497 vs. 29477092766) Syncing queue mesher_frontend in module Mesher failed;
 Could not retrieve exact timestamp requested: 
 - Requested timestamp: 29678134497
 - Actual timestamp:    29477092766
Reached max number of sync attempts: 10
*** Check failure stack trace: ***
    @     0x7fb145fceb0d  google::LogMessage::Fail()
    @     0x7fb145fd09b1  google::LogMessage::SendToLog()
    @     0x7fb145fce63d  google::LogMessage::Flush()
    @     0x7fb145fd1389  google::LogMessageFatal::~LogMessageFatal()
    @     0x7fb14579c81d  VIO::SimpleQueueSynchronizer<>::syncQueue()
    @     0x7fb13e97563e  VIO::MesherModule::getInputPacket()
    @     0x7fb13e97ad9f  VIO::PipelineModule<>::spin()
    @     0x7fb144c096df  (unknown)
    @     0x7fb14432b6db  start_thread
    @     0x7fb14466488f  clone

Please give also the following information:

  • SparkVio branch, tag or commit used: master
  • GTSAM version used:
  • OpenGV version used:
  • OpenCV version used:
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Ubuntu 18.04
  • Did you change the source code? (yes / no): no, except the launch file

Reduce the number of compiler warnings

Compiling the project generates a large number of compiler warnings, making it difficult to contribute while being careful not to introduce more warnings oneself or picking out compilation errors during development. The root causes for these warnings should be resolved as not to overwhelm contributors with walls of warnings in build logs and CI.

Add units to Jupyter notebook's plots

Currently, plots in the Jupyter notebooks in the scripts folder do not have units on their axes. It will be helpful to include units in the axes of the plots.

Rectified images failure

Description:
When using Rectified images and setting the flag ( --images_rectified="true" ) an error appeared and after debugging i concluded that the Camera matrix after rectification(P_) is empty
left_frame_.cam_param_.P_ = []
right_frame_.cam_param_.P_ = []
so , the function ( UtilsOpenCV::Cvmat2Cal3_S2 ) which convert camera matrix from OpenCv to gtsam throws an error .

and the two variable left_img_rectified_ , right_img_rectified_ , inside stereoframe.cpp file

if (is_rectified_) {
    left_img_rectified_ = left_frame_.img_;
    right_img_rectified_ = right_frame_.img_;

never used inside the if condition which means that i'm not benefit from rectified images !!!
Console output:

F0412 11:02:52.437469 13392 UtilsOpenCV.cpp:183] Check failed: M.rows == 3 (0 vs. 3)
*** Check failure stack trace: ***
    @   00007FFC79F95E35  public: void __cdecl google::LogMessage::Flush(void) __ptr64
    @   00007FFC79F94932  public: __cdecl google::LogMessageFatal::~LogMessageFatal(void) __ptr64
    @   00007FF6D7AFA13B  public: void __cdecl boost::serialization::singleton_module::unlock(void) __ptr64
    @   00007FF6D7B04D15  public: void __cdecl boost::serialization::singleton_module::unlock(void) __ptr64
    @   00007FF6D7AFF832  public: void __cdecl boost::serialization::singleton_module::unlock(void) __ptr64
    @   00007FF6D7B74263  public: void __cdecl boost::serialization::singleton_module::unlock(void) __ptr64
    @   00007FF6D7AEADC6  public: void __cdecl boost::serialization::singleton_module::unlock(void) __ptr64
    @   00007FF6D7ABBB0D  protected: __cdecl boost::serialization::singleton<class boost::serialization::extended_type_info_typeid<class cv::Point3_<float> > >::singleton<class boost::serialization::extended_type_info_typeid<class cv::Point3_<float> > >(void) __ptr64
    @   00007FF6D7ABCA03  protected: __cdecl boost::serialization::singleton<class boost::serialization::extended_type_info_typeid<class cv::Point3_<float> > >::singleton<class boost::serialization::extended_type_info_typeid<class cv::Point3_<float> > >(void) __ptr64
    @   00007FF6D7ABF80C  private: bool & __ptr64 __cdecl boost::serialization::singleton_module::get_lock(void) __ptr64
    @   00007FF6D7ABDB7D  protected: __cdecl boost::serialization::singleton<class boost::serialization::extended_type_info_typeid<class cv::Point3_<float> > >::singleton<class boost::serialization::extended_type_info_typeid<class cv::Point3_<float> > >(void) __ptr64
    @   00007FF6D7ABBBBE  protected: __cdecl boost::serialization::singleton<class boost::serialization::extended_type_info_typeid<class cv::Point3_<float> > >::singleton<class boost::serialization::extended_type_info_typeid<class cv::Point3_<float> > >(void) __ptr64
    @   00007FFC83E62AB4  int __cdecl Concurrency::details::_Schedule_chore(struct Concurrency::details::_Threadpool_chore * __ptr64)
    @   00007FFC99F4148C  RtlAcquireSRWLockExclusive
    @   00007FFC99F3FA19  RtlReleaseSRWLockExclusive
    @   00007FFC988A3034  BaseThreadInitThunk
    @   00007FFC99F91431  RtlUserThreadStart



  • OpenGV version used: 3.3.1
  • OpenCV version used: type opencv 3
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): windows 10
  • Did you change the source code? (yes / no): no

How to run in Kitti dataset

Hi authors,

Thank you, guys for awesome project.

I run Kimera-VIO in Euroc's dataset, everything is okay, but when run in Kitti dataset, PipelineModule stuck at Module: Visualizer - Spinning. Other spin modules didn't start.

I0310 17:10:02.398468 12352 KittiDataProvider.cpp:530] -------------------------------------------------------------
-------------------------------------------------------------
-------------------------------------------------------------
I0310 17:10:02.399873 12352 RegularVioBackEnd.cpp:113] Using Regular VIO backend.
I0310 17:10:02.402761 12352 LoopClosureDetector.cpp:98] LoopClosureDetector:: Loading vocabulary from ../vocabulary/ORBvoc.yml
I0310 17:10:10.057924 12352 LoopClosureDetector.cpp:101] Loaded vocabulary with 971815 visual words.
I0310 17:10:10.170249 12404 PipelineModule.h:163] Module: Data Provider - Spinning.
I0310 17:10:10.170296 12405 Pipeline.cpp:348] Shutting down VIO pipeline once processing has finished.
I0310 17:10:10.179666 12352 PipelineModule.h:163] Module: Visualizer - Spinning.

I tested the Kimera-VIO repository of @ToniRV , example demo works well in Kitti dataset.

Could you help me run the Kimera-VIO in Kitti dataset ? Many thanks in advance !

Regards,
Michael

Segmentation fault when running testKimeraVIO

Description:

Attempting to run testKimeraVIO will result in a segmentation fault.
This can be reproduced using the provided branch and Dockerfile

git clone https://github.com/ruffsl/Kimera-VIO.git -b focal
cd Kimera-VIO

export DOCKER_BUILDKIT=1
docker build \
  --tag spark/kimera_vio:focal \
  --progress=plain \
  --file focal.Dockerfile  .

Note the .repos files use for the workspace underlays:

https://github.com/ruffsl/Kimera-VIO/tree/focal/install

Command:

docker run -it --rm  spark/kimera_vio:focal bash
ln -s ../src/MIT-SPARK/Kimera-VIO/tests/ build/tests
cd build/kimera_vio/
./testKimeraVIO --gtest_output="xml:testresults.xml"

Console output:

[==========] Running 187 tests from 40 test suites.
[----------] Global test environment set-up.
[----------] 16 tests from VioPipelineFixture
[ RUN      ] VioPipelineFixture.OnlineSequentialStart
Segmentation fault (core dumped)

Additional files:

Same effect, but build with debug instead:

[==========] Running 187 tests from 40 test suites.
[----------] Global test environment set-up.
[----------] 16 tests from VioPipelineFixture
[ RUN      ] VioPipelineFixture.OnlineSequentialStart
I0513 14:57:43.480235    47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.480299    47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.495240    47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.496774    47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.496795    47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.496800    47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.496816    47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.496822    47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.496830    47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.496897    47 MesherModule.cpp:65] Shutting down queues for: Mesher
W0513 14:57:43.496984    47 Pipeline.cpp:884] No backend thread, not joining.
W0513 14:57:43.497002    47 Pipeline.cpp:884] No frontend thread, not joining.
W0513 14:57:43.497009    47 Pipeline.cpp:884] No mesher thread, not joining.
W0513 14:57:43.497014    47 Pipeline.cpp:884] No lcd thread, not joining.
W0513 14:57:43.497020    47 Pipeline.cpp:884] No visualizer thread, not joining.
I0513 14:57:43.497026    47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.497315    47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.497490    47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.498016    47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.498059    47 DataProviderInterface.cpp:31] Data provider destructor called.
I0513 14:57:43.498080    47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.499624    47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.499727    47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.499740    47 Pipeline.h:184] Spinning Kimera-VIO.
I0513 14:57:43.499799    47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.499809    47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.499814    47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.499821    47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.499828    47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.499840    47 MesherModule.cpp:65] Shutting down queues for: Mesher
I0513 14:57:43.499846    47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.499886    47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.499923    47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.500255    47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.500270    47 DataProviderInterface.cpp:31] Data provider destructor called.
[       OK ] VioPipelineFixture.OnlineSequentialStart (25 ms)
[ RUN      ] VioPipelineFixture.OnlineSequentialShutdown
I0513 14:57:43.501441    47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.501454    47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.502830    47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.502936    47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.502952    47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.502957    47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.502961    47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.502964    47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.502970    47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.502982    47 MesherModule.cpp:65] Shutting down queues for: Mesher
W0513 14:57:43.502991    47 Pipeline.cpp:884] No backend thread, not joining.
W0513 14:57:43.503001    47 Pipeline.cpp:884] No frontend thread, not joining.
W0513 14:57:43.503010    47 Pipeline.cpp:884] No mesher thread, not joining.
W0513 14:57:43.503016    47 Pipeline.cpp:884] No lcd thread, not joining.
W0513 14:57:43.503026    47 Pipeline.cpp:884] No visualizer thread, not joining.
I0513 14:57:43.503032    47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.503094    47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.503129    47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.503425    47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.503439    47 DataProviderInterface.cpp:31] Data provider destructor called.
I0513 14:57:43.503446    47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.504812    47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.504917    47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.505040    47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.505049    47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.505054    47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.505067    47 MesherModule.cpp:65] Shutting down queues for: Mesher
I0513 14:57:43.505074    47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.505080    47 Pipeline.h:184] Spinning Kimera-VIO.
I0513 14:57:43.505089    47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.505095    47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.505100    47 Pipeline.cpp:283] Manual shutdown was requested.
I0513 14:57:43.505131    47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.505167    47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.505477    47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.505491    47 DataProviderInterface.cpp:31] Data provider destructor called.
[       OK ] VioPipelineFixture.OnlineSequentialShutdown (5 ms)
[ RUN      ] VioPipelineFixture.OnlineSequentialSpinOnce
I0513 14:57:43.506578    47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.506589    47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.507920    47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.508038    47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.508054    47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.508059    47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.508064    47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.508069    47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.508074    47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.508085    47 MesherModule.cpp:65] Shutting down queues for: Mesher
W0513 14:57:43.508093    47 Pipeline.cpp:884] No backend thread, not joining.
W0513 14:57:43.508105    47 Pipeline.cpp:884] No frontend thread, not joining.
W0513 14:57:43.508112    47 Pipeline.cpp:884] No mesher thread, not joining.
W0513 14:57:43.508121    47 Pipeline.cpp:884] No lcd thread, not joining.
W0513 14:57:43.508131    47 Pipeline.cpp:884] No visualizer thread, not joining.
I0513 14:57:43.508141    47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.508183    47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.508221    47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.508517    47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.508532    47 DataProviderInterface.cpp:31] Data provider destructor called.
I0513 14:57:43.508538    47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.509769    47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.509874    47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.509889    47 EurocDataProvider.cpp:97] Parsing Euroc dataset...
Segmentation fault (core dumped)

Please give also the following information:

Why is biasAccOmegaInt so large?

Full disclosure I haven't actually tried out Kimera yet (nice work btw). But I was interested in understanding why here

combined_imu_params->biasAccOmegaInt = gtsam::I_6x6;

biasAccOmegaInt is set to such a large value when in the gtsam example it is set to 1e-5. So I've read that it models the covariance of the bias used during preintegration which would mean that you really don't trust the biases you are estimating on your IMU? Why is that?

Error with CMake version during build process

Description:

Command:

 catkin build --cmake-args -DCMAKE_BUILD_TYPE=Release -DGTSAM_USE_SYSTEM_EIGEN=ON

Console output:

Errors     << kimera_vio_ros:cmake /home/natsu/catkin_ws/logs/kimera_vio_ros/build.cmake.001.log            
CMake Error at /usr/share/cmake-3.5/Modules/CMakeFindDependencyMacro.cmake:45 (message):
  Invalid arguments to find_dependency
Call Stack (most recent call first):
  /home/natsu/catkin_ws/devel/lib/cmake/kimera_vio/kimera_vioConfig.cmake:14 (find_dependency)
  /home/natsu/catkin_ws/devel/share/catkin_simple/cmake/catkin_simple-extras.cmake:40 (find_package)
  CMakeLists.txt:16 (catkin_simple)


cd /home/natsu/catkin_ws/build/kimera_vio_ros; catkin build --get-env kimera_vio_ros | catkin env -si  /usr/bin/cmake /home/natsu/catkin_ws/src/Kimera-VIO-ROS --no-warn-unused-cli -DCATKIN_DEVEL_PREFIX=/home/natsu/catkin_ws/devel -DCMAKE_INSTALL_PREFIX=/home/natsu/catkin_ws/install -DCMAKE_BUILD_TYPE=Release -DCMAKE_BUILD_TYPE=Release -DGTSAM_USE_SYSTEM_EIGEN=ON; cd -
............................................................................................................
Failed     << kimera_vio_ros:cmake                         [ Exited with code 1 ]                           
Failed    <<< kimera_vio_ros                               [ 0.4 seconds ]                                  
[build] Summary: 13 of 14 packages succeeded.                                                               
[build]   Ignored:   None.                                                                                  
[build]   Warnings:  None.                                                                                  
[build]   Abandoned: None.                                                                                  
[build]   Failed:    1 packages failed.                                                                     
[build] Runtime: 5.1 seconds total. 
# remove this line and paste your console output HERE - no screenshots please

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used
  • GTSAM version used:
  • OpenGV version used:
  • OpenCV version used: type opencv_version
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10):
  • Did you change the source code? (yes / no):

Docker fails to build

Description:
I'm trying to follow the docker build instructions, and it fails on building the opengv libraries. I've reproduced this on both Windows 10 and MacOSX

Command:

docker build --rm -t kimera_vio -f ./scripts/docker/Dockerfile . 

Console output:

[ 39%] Building CXX object CMakeFiles/opengv.dir/src/absolute_pose/methods.cpp.o
CMakeFiles/opengv.dir/build.make:734: recipe for target 'CMakeFiles/opengv.dir/src/relative_pose/modules/main.cpp.o' failed
c++: internal compiler error: Killed (program cc1plus)
Please submit a full bug report,
with preprocessed source if appropriate.
See <file:///usr/share/doc/gcc-7/README.Bugs> for instructions.
make[2]: *** [CMakeFiles/opengv.dir/src/relative_pose/modules/main.cpp.o] Error 4
make[2]: *** Waiting for unfinished jobs....
CMakeFiles/Makefile2:409: recipe for target 'CMakeFiles/opengv.dir/all' failed
make[1]: *** [CMakeFiles/opengv.dir/all] Error 2
make: *** [all] Error 2
Makefile:140: recipe for target 'all' failed

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used
    Master/head as of 10/26
  • GTSAM version used:
  • OpenGV version used:
  • OpenCV version used: type opencv_version
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10):
    Windows 10, Mac OSX 10.14
  • Did you change the source code? (yes / no):
    No

Full Map

Is there any way to visualize and save the multi frame mesh of the map ?

Euroc example fails to start

Description:
It seems the script launching the Euroc example contains some unsupported flags. After removing the flags from the bash script, the example runs correctly.

Command:

# bash ./scripts/stereoVIOEuroc.bash -p /home/martino/Data/euroc/mav0/

Console output:


Using dataset at path: /home/martino/Data/euroc/mav0/
 Launching:

            ██╗  ██╗██╗███╗   ███╗███████╗██████╗  █████╗
            ██║ ██╔╝██║████╗ ████║██╔════╝██╔══██╗██╔══██╗
            █████╔╝ ██║██╔████╔██║█████╗  ██████╔╝███████║
            ██╔═██╗ ██║██║╚██╔╝██║██╔══╝  ██╔══██╗██╔══██║
            ██║  ██╗██║██║ ╚═╝ ██║███████╗██║  ██║██║  ██║
            ╚═╝  ╚═╝╚═╝╚═╝     ╚═╝╚══════╝╚═╝  ╚═╝╚═╝  ╚═╝

 
ERROR: unknown command line flag 'colorlogtostderr'
ERROR: unknown command line flag 'log_prefix'
ERROR: unknown command line flag 'logtostderr'
ERROR: unknown command line flag 'v'
ERROR: unknown command line flag 'vmodule'

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used: bceed72
  • GTSAM version used: 4.0.2
  • OpenGV version used: commit 306a54e
  • OpenCV version used: 3.4.7
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Arch Linux, kernel 4.19.95
  • Did you change the source code? (yes / no): no

Logger reports 10^9 Ransac iterations

Description:
I am integrating Kimera into a simulator. I examined the debug output using the Jupyter notebooks of Kimera-Evaluation. When I turn off 1point and 2point stereo ransac, the log shows a spike to 10^9 stereo ransac iterations. This is probably an error in the logging-- any ideas why this might be happening?

Command:

roslaunch kimera_vio_ros <launchfile>
jupyter notebook

With 1pt stereo and 2pt mono
Ransac Settings:

useRANSAC: 1
minNrMonoInliers: 10
minNrStereoInliers: 5
ransac_threshold_mono: 1e-06
ransac_threshold_stereo: 1
ransac_use_1point_stereo: 1
ransac_use_2point_mono: 1
ransac_max_iterations: 100
ransac_probability: 0.995
ransac_randomize: 0

Plot:
NormalRansacIters

Without 1pt stereo and 2pt mono
Ransac Settings:

useRANSAC: 1
minNrMonoInliers: 10
minNrStereoInliers: 5
ransac_threshold_mono: 1e-06
ransac_threshold_stereo: 1
ransac_use_1point_stereo: 0
ransac_use_2point_mono: 0
ransac_max_iterations: 100
ransac_probability: 0.995
ransac_randomize: 0

Plot:
LargeMonoRansacIterations

Please give also the following information:

  • SparkVio branch, tag or commit used: master
  • SparkVioRos branch, tag or commit used: Sequential rosbag (here)
  • GTSAM version used:
  • OpenGV version used:
  • OpenCV version used:
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Ubuntu 18.04
  • Did you change the source code? (yes / no): no

Kimera parameters

Dear Repository,
I want to experiment Kimera performance with different parameters and see the differences. Also, try to obtain the set of 3D landmarks generated this way. The problem is I don't know how to access this parameters. Can you guide me from where I should start in Kimera?

  • also I'm wondering how can I get point clouds of given frames in Kimera!

Thank you for your help in advance,
Rahim

Support for Ubuntu 20.04 LTS and OpenCV v4.2

With Ubuntu 20.04 LTS now shipping with OpenCV v4.2 , it would be nice update Kimera-VIO to support the latest long term support release of Ubuntu Focal and ROS releases Noetic and Foxy:

https://packages.ubuntu.com/focal/libopencv-dev

This should just evolve updating Kimera-VIO to transition it away from APIs that where deprecated in OpenCV v3 and removed in v4. From an initial look over, it seems that some of the c type headers will have to be explicitly imported, and switching to use the proper enum types for function arguments.

run erro

Description:
All the processes are successful according to your introduction, but they can't be operated. The data is also provided by you

Command:

./scripts/stereoVIOEuroc.bash

Console output:


Using dataset at path: /home/sun/MH_01_easy
 Launching:

            ██╗  ██╗██╗███╗   ███╗███████╗██████╗  █████╗
            ██║ ██╔╝██║████╗ ████║██╔════╝██╔══██╗██╔══██╗
            █████╔╝ ██║██╔████╔██║█████╗  ██████╔╝███████║
            ██╔═██╗ ██║██║╚██╔╝██║██╔══╝  ██╔══██╗██╔══██║
            ██║  ██╗██║██║ ╚═╝ ██║███████╗██║  ██║██║  ██║
            ╚═╝  ╚═╝╚═╝╚═╝     ╚═╝╚══════╝╚═╝  ╚═╝╚═╝  ╚═╝

 
Running dataset between frame 50 and frame 2000
reading camera: cam0
reading camera: cam1
nominal frame rate: 0.05
frame rate std: 0.0500068
frame rate maxMismatch: 0.0500001
Maximum measured rotation rate (norm):4.06396-Maximum measured acceleration (norm): 67.4671
Maximum ground truth velocity: 2.00535
Dataset name: MH_01_easy
-------------------------------------------------------------
------------------ ETHDatasetParser::print ------------------
-------------------------------------------------------------
Displaying info for dataset: /home/sun/MH_01_easy
camL_Pose_calR 
R:
[
 	    0.999997  -0.00231714 -0.000343393;
    	  0.00231207     0.999898   -0.0140907;
    	 0.000376008    0.0140898     0.999901
  ]

Left camera name: cam0, with params:
------------ CameraParams::print -------------
intrinsics_: 458.654000 , 457.296000 , 367.215000 , 248.375000 , 
body_Pose_cam_: 

|0.0148655, -0.999881, 0.0041403|
|0.999557, 0.0149672, 0.0257155|
|-0.0257744, 0.00375619, 0.999661|

[-0.0216401, -0.064677, 0.00981073]';

[0.110074, -0.000156612, 0.000889383]';
 gtsam calibration:
.K[
 	458.654       0 367.215;
    	      0 457.296 248.375;
    	      0       0       1
  ]

 gtsam calibration:
.k[-0.28340811; 0.07395907; 0.00019359; 1.76187114e-05];
frame_rate_: 0.05
image_size_: width= 752 height= 480
camera_matrix_: 
[458.654, 0, 367.215;
 0, 457.296, 248.375;
 0, 0, 1]
distortion_model_: radial-tangential
distortion_coeff_: 
[-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05]
R_rectify_: 
[]
undistRect_map_y_ too large to display (only created in StereoFrame)
P_: 
[]
------------ CameraImageLists::print -------------
image_folder_path: /home/sun/MH_01_easy/mav0/cam0
img_lists size: 3682

Right camera name: cam1, with params:
------------ CameraParams::print -------------
intrinsics_: 457.587000 , 456.134000 , 379.999000 , 255.238000 , 
body_Pose_cam_: 

|0.0125553, -0.999755, 0.0182238|
|0.999599, 0.0130119, 0.0251588|
|-0.0253898, 0.0179006, 0.999517|

[-0.0198436, 0.0453689, 0.00786212]';


 gtsam calibration:
.K[
 	457.587       0 379.999;
    	      0 456.134 255.238;
    	      0       0       1
  ]

 gtsam calibration:
.k[-0.28368365; 0.07451284; -0.00010473; -3.555907e-05];
frame_rate_: 0.05
image_size_: width= 752 height= 480
camera_matrix_: 
[457.587, 0, 379.999;
 0, 456.134, 255.238;
 0, 0, 1]
distortion_model_: radial-tangential
distortion_coeff_: 
[-0.28368365, 0.07451284, -0.00010473, -3.555907e-05]
R_rectify_: 
[]
undistRect_map_y_ too large to display (only created in StereoFrame)
P_: 
[]
------------ CameraImageLists::print -------------
image_folder_path: /home/sun/MH_01_easy/mav0/cam1
img_lists size: 3682
------------ GroundTruthData::print -------------
body_Pose_cam_: 
R:
[
 	1 0 0;
    	0 1 0;
    	0 0 1
  ]

 gt_rate: 0.005
nr of gtStates: 36382
------------ ImuData::print -------------

nominal_imu_rate: 0.005
imu_rate: 0.005
imu_rate_std: 0.00500007
imu_rate_maxMismatch: 0.00500019
nr of imu measurements: 36820
-------------------------------------------------------------
-------------------------------------------------------------
-------------------------------------------------------------
Applying IMU timestamp shift of: 1.99913e+161ns.
&&&&&&&&&&&&&&&&&&&& TRACKER PARAMETERS &&&&&&&&&&&&&&&&&&&&&&&&&&&
** Feature tracking parameters **
klt_win_size_: 24
klt_max_iter_: 30
klt_max_level_: 4
klt_eps_: 0.1
maxFeatureAge_: 15
** Feature detection parameters **
maxFeaturesPerFrame_: 800
quality_level_: 0.001
min_distance_: 20
block_size_: 3
use_harris_detector_: 0
k_: 0.04
** Sparse Stereo Matching parameters **
equalize_image_: 0
nominalBaseline_: 0.11
vision_sensor_type_: 0
toleranceTemplateMatching_: 0.15
templ_cols_: 101
templ_rows_: 11
stripe_extra_rows_: 0
minPointDist_: 0.5
maxPointDist_: 10
bidirectionalMatching_: 0
subpixelRefinementStereo_: 0
** Feature selection parameters **
featureSelectionCriterion_: 0
featureSelectionHorizon_: 3
featureSelectionNrCornersToSelect_: 600
featureSelectionImuRate_: 0.005
featureSelectionDefaultDepth_: 2
featureSelectionCosineNeighborhood_: 0.984808
featureSelectionUseLazyEvaluation_: 1
useSuccessProbabilities_: 1
** RANSAC parameters **
useRANSAC_: 1
minNrMonoInliers_: 10
minNrStereoInliers_: 5
ransac_threshold_mono_: 1e-06
ransac_threshold_stereo_: 1
ransac_use_1point_stereo_: 1
ransac_use_2point_mono_: 1
ransac_max_iterations_: 100
ransac_probability_: 0.995
ransac_randomize_: 0
** STEREO tracker parameters **
intra_keyframe_time_: 0.2
minNumberFeatures_: 0
useStereoTracking_: 1
** OTHER parameters **
disparityThreshold_: 0.5
&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&
Frontend running in sequential mode (parallel_run set to 0).
------------------- Initialize Pipeline with frame k = 50--------------------
ExtractCorners: no corner found in image.
 Using Normal VIO. 
[0, 0, 0]';isam_param
type:              ISAM2GaussNewtonParams
wildfireThreshold: -1
relinearizeThreshold:              0.01
relinearizeSkip:                   1
enableRelinearization:             1
evaluateNonlinearError:            0
factorization:                     CHOLESKY
cacheLinearizedFactors:            1
enableDetailedResults:             0
enablePartialRelinearizationCheck: 0
findUnusedFactorSlots:             1
Initial state seed: 
 - Initial pose: 
|-0.396892, 0.356007, -0.846014|
|0.173771, 0.934192, 0.311592|
|0.901268, -0.0233444, -0.432637|

[4.71169, -1.78947, 0.685225]';

 - Initial vel: -0.023791 -0.016973 00.091484
 - Initial IMU bias: acc = [-0.025266, 0.1367, 0.075598]' gyro = [-0.003172, 0.021267, 0.078502]'
Before launching threads.
Backend, mesher and visualizer running in sequential mode (parallel_run set to 0).
 launching threads.
Spinning StereoFrontEnd.
------------------- Processing frame k = 51--------------------
Current IMU Preintegration frequency: 256410 Hz. (39 us).
[sm::SampleConsensusModel::getSamples] Can not select 2 unique points out of 0!
[sm::RandomSampleConsensus::computeModel] No samples could be selected!
ExtractCorners: no corner found in image.
Keyframe 51 with: 0 smart measurements
Current Stereo FrontEnd (keyframe) frequency: 500 Hz. (2 ms).
Spinning VioBackEnd.
VIO: adding keyframe 1 at timestamp:1.40364e+09 (nsec).
Backend: Update IMU Bias.
Current Backend frequency: inf Hz. (0 ms).
Spinning Mesher.
Filter triangles with gradients is disabled.
Current Mesher frequency: inf Hz. (0 ms).
Spinning Visualizer.
terminate called after throwing an instance of 'cv::Exception'
  what():  OpenCV(3.4.6) /home/sun/lib/opencv-3.4.6/modules/imgproc/src/color.cpp:182: error: (-215:Assertion failed) !_src.empty() in function 'cvtColor'

./scripts/stereoVIOEuroc.bash: 行 120:  7834 已放弃               (核心已转储) ../build/stereoVIOEuroc --flagfile="../params/flags/stereoVIOEuroc.flags" --flagfile="../params/flags/Mesher.flags" --flagfile="../params/flags/VioBackEnd.flags" --flagfile="../params/flags/RegularVioBackEnd.flags" --flagfile="../params/flags/Visualizer3D.flags" --flagfile="../params/flags/EthParser.flags" --logtostderr=1 --colorlogtostderr=1 --log_prefix=0 --dataset_path="$DATASET_PATH" --vio_params_path="$VIO_PARAMS_PATH" --initial_k=50 --final_k=2000 --tracker_params_path="$TRACKER_PARAMS_PATH" --lcd_params_path="$LCD_PARAMS_PATH" --vocabulary_path="../vocabulary/ORBvoc.yml" --use_lcd="$USE_LCD" --v=0 --vmodule=VioBackEnd=0,RegularVioBackEnd=0,Mesher=0,StereoVisionFrontEnd=0 --backend_type="$BACKEND_TYPE" --parallel_run="$PARALLEL_RUN" --dataset_type="$DATASET_TYPE" --log_output="$LOG_OUTPUT" --output_path="../output_logs/"

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used
  • GTSAM version used: 4.0.0
  • OpenGV version used:
  • OpenCV version used: type opencv_version3.4.6
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Ubuntu 16.04
  • Did you change the source code? (yes / no): no

Error when running Kimera-VIO in Euroc's dataset

Description:

Command:

bash ./scripts/stereoVIOEuroc.bash -p "$HOME/Euroc/V1_01_easy"

Console output:

Using dataset at path: /home/kechengchen/Euroc/V1_01_easy
 Launching:

            ██╗  ██╗██╗███╗   ███╗███████╗██████╗  █████╗
            ██║ ██╔╝██║████╗ ████║██╔════╝██╔══██╗██╔══██╗
            █████╔╝ ██║██╔████╔██║█████╗  ██████╔╝███████║
            ██╔═██╗ ██║██║╚██╔╝██║██╔══╝  ██╔══██╗██╔══██║
            ██║  ██╗██║██║ ╚═╝ ██║███████╗██║  ██║██║  ██║
            ╚═╝  ╚═╝╚═╝╚═╝     ╚═╝╚══════╝╚═╝  ╚═╝╚═╝  ╚═╝

 
*** Error in `../build/stereoVIOEuroc': double free or corruption (out): 0x000000000192d540 ***
======= Backtrace: =========
/lib/x86_64-linux-gnu/libc.so.6(+0x777e5)[0x7efd9ee257e5]
/lib/x86_64-linux-gnu/libc.so.6(+0x8037a)[0x7efd9ee2e37a]
/lib/x86_64-linux-gnu/libc.so.6(cfree+0x4c)[0x7efd9ee3253c]
/usr/local/lib/libgtsam.so.4(_ZN5gtsam10noiseModel8Diagonal6SigmasERKN5Eigen6MatrixIdLin1ELi1ELi0ELin1ELi1EEEb+0x18d)[0x7efd9fb5fa5d]
/usr/local/lib/libgtsam.so.4(+0x113dad)[0x7efd9fa27dad]
/lib64/ld-linux-x86-64.so.2(+0x106ca)[0x7efda196e6ca]
/lib64/ld-linux-x86-64.so.2(+0x107db)[0x7efda196e7db]
/lib64/ld-linux-x86-64.so.2(+0xc6a)[0x7efda195ec6a]
======= Memory map: ========
00400000-00416000 r-xp 00000000 08:08 173546                             /home/kechengchen/Kimera-VIO/build/stereoVIOEuroc
00615000-00616000 r--p 00015000 08:08 173546                             /home/kechengchen/Kimera-VIO/build/stereoVIOEuroc
00616000-00617000 rw-p 00016000 08:08 173546                             /home/kechengchen/Kimera-VIO/build/stereoVIOEuroc
018c4000-01948000 rw-p 00000000 00:00 0                                  [heap]
7efd70000000-7efd70021000 rw-p 00000000 00:00 0 
7efd70021000-7efd74000000 ---p 00000000 00:00 0 
7efd753a1000-7efd755a1000 rw-p 00000000 00:00 0 
7efd755a1000-7efd76e57000 r-xp 00000000 08:07 666626                     /usr/lib/x86_64-linux-gnu/libicudata.so.55.1
7efd76e57000-7efd77056000 ---p 018b6000 08:07 666626                     /usr/lib/x86_64-linux-gnu/libicudata.so.55.1
7efd77056000-7efd77057000 r--p 018b5000 08:07 666626                     /usr/lib/x86_64-linux-gnu/libicudata.so.55.1
7efd77057000-7efd77058000 rw-p 018b6000 08:07 666626                     /usr/lib/x86_64-linux-gnu/libicudata.so.55.1
7efd77058000-7efd77061000 r-xp 00000000 08:07 1185238                    /lib/x86_64-linux-gnu/libcrypt-2.23.so
7efd77061000-7efd77260000 ---p 00009000 08:07 1185238                    /lib/x86_64-linux-gnu/libcrypt-2.23.so
7efd77260000-7efd77261000 r--p 00008000 08:07 1185238                    /lib/x86_64-linux-gnu/libcrypt-2.23.so
7efd77261000-7efd77262000 rw-p 00009000 08:07 1185238                    /lib/x86_64-linux-gnu/libcrypt-2.23.so
7efd77262000-7efd77290000 rw-p 00000000 00:00 0 
7efd77290000-7efd772d7000 r-xp 00000000 08:07 666607                     /usr/lib/x86_64-linux-gnu/libhx509.so.5.0.0
7efd772d7000-7efd774d6000 ---p 00047000 08:07 666607                     /usr/lib/x86_64-linux-gnu/libhx509.so.5.0.0
7efd774d6000-7efd774d8000 r--p 00046000 08:07 666607                     /usr/lib/x86_64-linux-gnu/libhx509.so.5.0.0
7efd774d8000-7efd774da000 rw-p 00048000 08:07 666607                     /usr/lib/x86_64-linux-gnu/libhx509.so.5.0.0
7efd774da000-7efd774db000 rw-p 00000000 00:00 0 
7efd774db000-7efd774e9000 r-xp 00000000 08:07 666589                     /usr/lib/x86_64-linux-gnu/libheimbase.so.1.0.0
7efd774e9000-7efd776e8000 ---p 0000e000 08:07 666589                     /usr/lib/x86_64-linux-gnu/libheimbase.so.1.0.0
7efd776e8000-7efd776e9000 r--p 0000d000 08:07 666589                     /usr/lib/x86_64-linux-gnu/libheimbase.so.1.0.0
7efd776e9000-7efd776ea000 rw-p 0000e000 08:07 666589                     /usr/lib/x86_64-linux-gnu/libheimbase.so.1.0.0
7efd776ea000-7efd77711000 r-xp 00000000 08:07 667270                     /usr/lib/x86_64-linux-gnu/libwind.so.0.0.0
7efd77711000-7efd77911000 ---p 00027000 08:07 667270                     /usr/lib/x86_64-linux-gnu/libwind.so.0.0.0
7efd77911000-7efd77912000 r--p 00027000 08:07 667270                     /usr/lib/x86_64-linux-gnu/libwind.so.0.0.0
7efd77912000-7efd77913000 rw-p 00028000 08:07 667270                     /usr/lib/x86_64-linux-gnu/libwind.so.0.0.0
7efd77913000-7efd7791c000 r-xp 00000000 08:07 666726                     /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1
7efd7791c000-7efd77b1b000 ---p 00009000 08:07 666726                     /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1
7efd77b1b000-7efd77b1c000 r--p 00008000 08:07 666726                     /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1
7efd77b1c000-7efd77b1d000 rw-p 00009000 08:07 666726                     /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1
7efd77b1d000-7efd77b3e000 r-xp 00000000 08:07 666708                     /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0
7efd77b3e000-7efd77d3d000 ---p 00021000 08:07 666708                     /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0
7efd77d3d000-7efd77d3e000 r--p 00020000 08:07 666708                     /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0
7efd77d3e000-7efd77d3f000 rw-p 00021000 08:07 666708                     /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0
7efd77d3f000-7efd77ebe000 r-xp 00000000 08:07 666640                     /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1
7efd77ebe000-7efd780be000 ---p 0017f000 08:07 666640                     /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1
7efd780be000-7efd780ce000 r--p 0017f000 08:07 666640                     /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1
7efd780ce000-7efd780cf000 rw-p 0018f000 08:07 666640                     /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1
7efd780cf000-7efd780d3000 rw-p 00000000 00:00 0 
7efd780d3000-7efd780e5000 r-xp 00000000 08:07 1185272                    /lib/x86_64-linux-gnu/libgpg-error.so.0.17.0
7efd780e5000-7efd782e5000 ---p 00012000 08:07 1185272                    /lib/x86_64-linux-gnu/libgpg-error.so.0.17.0
7efd782e5000-7efd782e6000 r--p 00012000 08:07 1185272                    /lib/x86_64-linux-gnu/libgpg-error.so.0.17.0
7efd782e6000-7efd782e7000 rw-p 00013000 08:07 1185272                    /lib/x86_64-linux-gnu/libgpg-error.so.0.17.0
7efd782e7000-7efd782ee000 r-xp 00000000 08:07 672642                     /usr/lib/x86_64-linux-gnu/libaec.so.0.0.3
7efd782ee000-7efd784ed000 ---p 00007000 08:07 672642                     /usr/lib/x86_64-linux-gnu/libaec.so.0.0.3
7efd784ed000-7efd784ee000 r--p 00006000 08:07 672642                     /usr/lib/x86_64-linux-gnu/libaec.so.0.0.3
7efd784ee000-7efd784ef000 rw-p 00007000 08:07 672642                     /usr/lib/x86_64-linux-gnu/libaec.so.0.0.3
7efd784ef000-7efd78504000 r-xp 00000000 08:07 667009                     /usr/lib/x86_64-linux-gnu/libroken.so.18.1.0
7efd78504000-7efd78703000 ---p 00015000 08:07 667009                     /usr/lib/x86_64-linux-gnu/libroken.so.18.1.0
7efd78703000-7efd78704000 r--p 00014000 08:07 667009                     /usr/lib/x86_64-linux-gnu/libroken.so.18.1.0
7efd78704000-7efd78705000 rw-p 00015000 08:07 667009                     /usr/lib/x86_64-linux-gnu/libroken.so.18.1.0
7efd78705000-7efd78735000 r-xp 00000000 08:07 666587                     /usr/lib/x86_64-linux-gnu/libhcrypto.so.4.1.0
7efd78735000-7efd78935000 ---p 00030000 08:07 666587                     /usr/lib/x86_64-linux-gnu/libhcrypto.so.4.1.0
7efd78935000-7efd78936000 r--p 00030000 08:07 666587                     /usr/lib/x86_64-linux-gnu/libhcrypto.so.4.1.0
7efd78936000-7efd78937000 rw-p 00031000 08:07 666587                     /usr/lib/x86_64-linux-gnu/libhcrypto.so.4.1.0
7efd78937000-7efd78938000 rw-p 00000000 00:00 0 
7efd78938000-7efd789d7000 r-xp 00000000 08:07 666024                     /usr/lib/x86_64-linux-gnu/libasn1.so.8.0.0
7efd789d7000-7efd78bd6000 ---p 0009f000 08:07 666024                     /usr/lib/x86_64-linux-gnu/libasn1.so.8.0.0
7efd78bd6000-7efd78bd7000 r--p 0009e000 08:07 666024                     /usr/lib/x86_64-linux-gnu/libasn1.so.8.0.0
7efd78bd7000-7efd78bda000 rw-p 0009f000 08:07 666024                     /usr/lib/x86_64-linux-gnu/libasn1.so.8.0.0
7efd78bda000-7efd78c5e000 r-xp 00000000 08:07 666694                     /usr/lib/x86_64-linux-gnu/libkrb5.so.26.0.0
7efd78c5e000-7efd78e5d000 ---p 00084000 08:07 666694                     /usr/lib/x86_64-linux-gnu/libkrb5.so.26.0.0
7efd78e5d000-7efd78e60000 r--p 00083000 08:07 666694                     /usr/lib/x86_64-linux-gnu/libkrb5.so.26.0.0
7efd78e60000-7efd78e63000 rw-p 00086000 08:07 666694                     /usr/lib/x86_64-linux-gnu/libkrb5.so.26.0.0
7efd78e63000-7efd78e64000 rw-p 00000000 00:00 0 
7efd78e64000-7efd78e6c000 r-xp 00000000 08:07 666591                     /usr/lib/x86_64-linux-gnu/libheimntlm.so.0.1.0
7efd78e6c000-7efd7906b000 ---p 00008000 08:07 666591                     /usr/lib/x86_64-linux-gnu/libheimntlm.so.0.1.0
7efd7906b000-7efd7906c000 r--p 00007000 08:07 666591                     /usr/lib/x86_64-linux-gnu/libheimntlm.so.0.1.0
7efd7906c000-7efd7906d000 rw-p 00008000 08:07 666591                     /usr/lib/x86_64-linux-gnu/libheimntlm.so.0.1.0
7efd7906d000-7efd79070000 r-xp 00000000 08:07 1185289                    /lib/x86_64-linux-gnu/libkeyutils.so.1.5
7efd79070000-7efd7926f000 ---p 00003000 08:07 1185289                    /lib/x86_64-linux-gnu/libkeyutils.so.1.5
7efd7926f000-7efd79270000 r--p 00002000 08:07 1185289                    /lib/x86_64-linux-gnu/libkeyutils.so.1.5
7efd79270000-7efd79271000 rw-p 00003000 08:07 1185289                    /lib/x86_64-linux-gnu/libkeyutils.so.1.5
7efd79271000-7efd79273000 r-xp 00000000 08:07 1185409                    /lib/x86_64-linux-gnu/libutil-2.23.so
7efd79273000-7efd79472000 ---p 00002000 08:07 1185409                    /lib/x86_64-linux-gnu/libutil-2.23.so
7efd79472000-7efd79473000 r--p 00001000 08:07 1185409                    /lib/x86_64-linux-gnu/libutil-2.23.so
7efd79473000-7efd79474000 rw-p 00002000 08:07 1185409                    /lib/x86_64-linux-gnu/libutil-2.23.so
7efd79474000-7efd794ad000 r-xp 00000000 08:07 682128                     /usr/lib/x86_64-linux-gnu/libhwloc.so.5.6.8
7efd794ad000-7efd796ac000 ---p 00039000 08:07 682128                     /usr/lib/x86_64-linux-gnu/libhwloc.so.5.6.8
7efd796ac000-7efd796ad000 r--p 00038000 08:07 682128                     /usr/lib/x86_64-linux-gnu/libhwloc.so.5.6.8
7efd796ad000-7efd796ae000 rw-p 00039000 08:07 682128                     /usr/lib/x86_64-linux-gnu/libhwloc.so.5.6.8
7efd796ae000-7efd796b4000 r-xp 00000000 08:07 666193                     /usr/lib/x86_64-linux-gnu/libdatrie.so.1.3.3
7efd796b4000-7efd798b4000 ---p 00006000 08:07 666193                     /usr/lib/x86_64-linux-gnu/libdatrie.so.1.3.3
7efd798b4000-7efd798b5000 r--p 00006000 08:07 666193                     /usr/lib/x86_64-linux-gnu/libdatrie.so.1.3.3
7efd798b5000-7efd798b6000 rw-p 00007000 08:07 666193                     /usr/lib/x86_64-linux-gnu/libdatrie.so.1.3.3
7efd798b6000-7efd798da000 r-xp 00000000 08:07 666497                     /usr/lib/x86_64-linux-gnu/libgraphite2.so.3.0.1
7efd798da000-7efd79ad9000 ---p 00024000 08:07 666497                     /usr/lib/x86_64-linux-gnu/libgraphite2.so.3.0.1
7efd79ad9000-7efd79adb000 r--p 00023000 08:07 666497                     /usr/lib/x86_64-linux-gnu/libgraphite2.so.3.0.1
7efd79adb000-7efd79adc000 rw-p 00025000 08:07 666497                     /usr/lib/x86_64-linux-gnu/libgraphite2.so.3.0.1
7efd79adc000-7efd79b57000 r-xp 00000000 08:07 666871                     /usr/lib/x86_64-linux-gnu/liborc-0.4.so.0.25.0
7efd79b57000-7efd79d56000 ---p 0007b000 08:07 666871                     /usr/lib/x86_64-linux-gnu/liborc-0.4.so.0.25.0
7efd79d56000-7efd79d58000 r--p 0007a000 08:07 666871                     /usr/lib/x86_64-linux-gnu/liborc-0.4.so.0.25.0
7efd79d58000-7efd79d5c000 rw-p 0007c000 08:07 666871                     /usr/lib/x86_64-linux-gnu/liborc-0.4.so.0.25.0
7efd79d5c000-7efd79d63000 r-xp 00000000 08:07 666865                     /usr/lib/x86_64-linux-gnu/libogg.so.0.8.2
7efd79d63000-7efd79f63000 ---p 00007000 08:07 666865                     /usr/lib/x86_64-linux-gnu/libogg.so.0.8.2
7efd79f63000-7efd79f64000 r--p 00007000 08:07 666865                     /usr/lib/x86_64-linux-gnu/libogg.so.0.8.2
7efd79f64000-7efd79f65000 rw-p 00008000 08:07 666865                     /usr/lib/x86_64-linux-gnu/libogg.so.0.8.2
7efd79f65000-7efd79f6f000 r-xp 00000000 08:07 666853                     /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0
7efd79f6f000-7efd7a16e000 ---p 0000a000 08:07 666853                     /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0
7efd7a16e000-7efd7a16f000 r--p 00009000 08:07 666853                     /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0
7efd7a16f000-7efd7a170000 rw-p 0000a000 08:07 666853                     /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0
7efd7a170000-7efd7a19e000 r-xp 00000000 08:07 672573                     /usr/lib/x86_64-linux-gnu/libsoxr.so.0.1.1
7efd7a19e000-7efd7a39d000 ---p 0002e000 08:07 672573                     /usr/lib/x86_64-linux-gnu/libsoxr.so.0.1.1
7efd7a39d000-7efd7a39f000 r--p 0002d000 08:07 672573                     /usr/lib/x86_64-linux-gnu/libsoxr.so.0.1.1
7efd7a39f000-7efd7a3a0000 rw-p 0002f000 08:07 672573                     /usr/lib/x86_64-linux-gnu/libsoxr.so.0.1.1
7efd7a3a0000-7efd7a3d5000 rw-p 00000000 00:00 0 
7efd7a3d5000-7efd7a3e6000 r-xp 00000000 08:07 667114                     /usr/lib/x86_64-linux-gnu/libtasn1.so.6.5.1
7efd7a3e6000-7efd7a5e6000 ---p 00011000 08:07 667114                     /usr/lib/x86_64-linux-gnu/libtasn1.so.6.5.1
7efd7a5e6000-7efd7a5e7000 r--p 00011000 08:07 667114                     /usr/lib/x86_64-linux-gnu/libtasn1.so.6.5.1
7efd7a5e7000-7efd7a5e8000 rw-p 00012000 08:07 667114                     /usr/lib/x86_64-linux-gnu/libtasn1.so.6.5.1
7efd7a5e8000-7efd7a641000 r-xp 00000000 08:07 666881                     /usr/lib/x86_64-linux-gnu/libp11-kit.so.0.1.0
7efd7a641000-7efd7a840000 ---p 00059000 08:07 666881                     /usr/lib/x86_64-linux-gnu/libp11-kit.so.0.1.0
7efd7a840000-7efd7a84a000 r--p 00058000 08:07 666881                     /usr/lib/x86_64-linux-gnu/libp11-kit.so.0.1.0
7efd7a84a000-7efd7a84c000 rw-p 00062000 08:07 666881                     /usr/lib/x86_64-linux-gnu/libp11-kit.so.0.1.0
7efd7a84c000-7efd7a9fd000 r-xp 00000000 08:07 655567                     /usr/lib/x86_64-linux-gnu/libxml2.so.2.9.3
7efd7a9fd000-7efd7abfc000 ---p 001b1000 08:07 655567                     /usr/lib/x86_64-linux-gnu/libxml2.so.2.9.3
7efd7abfc000-7efd7ac04000 r--p 001b0000 08:07 655567                     /usr/lib/x86_64-linux-gnu/libxml2.so.2.9.3
7efd7ac04000-7efd7ac06000 rw-p 001b8000 08:07 655567                     /usr/lib/x86_64-linux-gnu/libxml2.so.2.9.3
7efd7ac06000-7efd7ac07000 rw-p 00000000 00:00 0 
7efd7ac07000-7efd7ac86000 r-xp 00000000 08:07 666455                     /usr/lib/x86_64-linux-gnu/libgmp.so.10.3.0
7efd7ac86000-7efd7ae85000 ---p 0007f000 08:07 666455                     /usr/lib/x86_64-linux-gnu/libgmp.so.10.3.0
7efd7ae85000-7efd7ae86000 r--p 0007e000 08:07 666455                     /usr/lib/x86_64-linux-gnu/libgmp.so.10.3.0
7efd7ae86000-7efd7ae87000 rw-p 0007f000 08:07 666455                     /usr/lib/x86_64-linux-gnu/libgmp.so.10.3.0
7efd7ae87000-7efd7aeb9000 r-xp 00000000 08:07 666593                     /usr/lib/x86_64-linux-gnu/libhogweed.so.4.2
7efd7aeb9000-7efd7b0b8000 ---p 00032000 08:07 666593                     /usr/lib/x86_64-linux-gnu/libhogweed.so.4.2
7efd7b0b8000-7efd7b0b9000 r--p 00031000 08:07 666593                     /usr/lib/x86_64-linux-gnu/libhogweed.so.4.2
7efd7b0b9000-7efd7b0ba000 rw-p 00032000 08:07 666593                     /usr/lib/x86_64-linux-gnu/libhogweed.so.4.2
7efd7b0ba000-7efd7b191000 r-xp 00000000 08:07 1181487                    /lib/x86_64-linux-gnu/libgcrypt.so.20.0.5
7efd7b191000-7efd7b391000 ---p 000d7000 08:07 1181487                    /lib/x86_64-linux-gnu/libgcrypt.so.20.0.5
7efd7b391000-7efd7b392000 r--p 000d7000 08:07 1181487                    /lib/x86_64-linux-gnu/libgcrypt.so.20.0.5
7efd7b392000-7efd7b39a000 rw-p 000d8000 08:07 1181487                    /lib/x86_64-linux-gnu/libgcrypt.so.20.0.5
7efd7b39a000-7efd7b39b000 rw-p 00000000 00:00 0 
7efd7b39b000-7efd7b3cf000 r-xp 00000000 08:07 666818                     /usr/lib/x86_64-linux-gnu/libnettle.so.6.2
7efd7b3cf000-7efd7b5ce000 ---p 00034000 08:07 666818                     /usr/lib/x86_64-linux-gnu/libnettle.so.6.2
7efd7b5ce000-7efd7b5d0000 r--p 00033000 08:07 666818                     /usr/lib/x86_64-linux-gnu/libnettle.so.6.2
7efd7b5d0000-7efd7b5d1000 rw-p 00035000 08:07 666818                     /usr/lib/x86_64-linux-gnu/libnettle.so.6.2
7efd7b5d1000-7efd7b602000 r-xp 00000000 08:07 666642                     /usr/lib/x86_64-linux-gnu/libidn.so.11.6.15
7efd7b602000-7efd7b802000 ---p 00031000 08:07 666642                     /usr/lib/x86_64-linux-gnu/libidn.so.11.6.15
7efd7b802000-7efd7b803000 r--p 00031000 08:07 666642                     /usr/lib/x86_64-linux-gnu/libidn.so.11.6.15
7efd7b803000-7efd7b804000 rw-p 00032000 08:07 666642                     /usr/lib/x86_64-linux-gnu/libidn.so.11.6.15
7efd7b804000-7efd7b806000 r-xp 00000000 08:07 672644                     /usr/lib/x86_64-linux-gnu/libsz.so.2.0.1
7efd7b806000-7efd7ba05000 ---p 00002000 08:07 672644                     /usr/lib/x86_64-linux-gnu/libsz.so.2.0.1
7efd7ba05000-7efd7ba06000 r--p 00001000 08:07 672644                     /usr/lib/x86_64-linux-gnu/libsz.so.2.0.1
7efd7ba06000-7efd7ba07000 rw-p 00002000 08:07 672644                     /usr/lib/x86_64-linux-gnu/libsz.so.2.0.1
7efd7ba07000-7efd7ba44000 r-xp 00000000 08:07 666510                     /usr/lib/x86_64-linux-gnu/libgssapi.so.3.0.0
7efd7ba44000-7efd7bc44000 ---p 0003d000 08:07 666510                     /usr/lib/x86_64-linux-gnu/libgssapi.so.3.0.0
7efd7bc44000-7efd7bc45000 r--p 0003d000 08:07 666510                     /usr/lib/x86_64-linux-gnu/libgssapi.so.3.0.0
7efd7bc45000-7efd7bc47000 rw-p 0003e000 08:07 666510                     /usr/lib/x86_64-linux-gnu/libgssapi.so.3.0.0
7efd7bc47000-7efd7bc48000 rw-p 00000000 00:00 0 
7efd7bc48000-7efd7bc61000 r-xp 00000000 08:07 661511                     /usr/lib/x86_64-linux-gnu/libsasl2.so.2.0.25
7efd7bc61000-7efd7be61000 ---p 00019000 08:07 661511                     /usr/lib/x86_64-linux-gnu/libsasl2.so.2.0.25
7efd7be61000-7efd7be62000 r--p 00019000 08:07 661511                     /usr/lib/x86_64-linux-gnu/libsasl2.so.2.0.25
7efd7be62000-7efd7be63000 rw-p 0001a000 08:07 661511                     /usr/lib/x86_64-linux-gnu/libsasl2.so.2.0.25
7efd7be63000-7efd7be70000 r-xp 00000000 08:07 669766                     /usr/lib/x86_64-linux-gnu/liblber-2.4.so.2.10.5
7efd7be70000-7efd7c070000 ---p 0000d000 08:07 669766                     /usr/lib/x86_64-linux-gnu/liblber-2.4.so.2.10.5
7efd7c070000-7efd7c071000 r--p 0000d000 08:07 669766                     /usr/lib/x86_64-linux-gnu/liblber-2.4.so.2.10.5
7efd7c071000-7efd7c072000 rw-p 0000e000 08:07 669766                     /usr/lib/x86_64-linux-gnu/liblber-2.4.so.2.10.5
7efd7c072000-7efd7c07c000 r-xp 00000000 08:07 666698                     /usr/lib/x86_64-linux-gnu/libkrb5support.so.0.1
7efd7c07c000-7efd7c27b000 ---p 0000a000 08:07 666698                     /usr/lib/x86_64-linux-gnu/libkrb5support.so.0.1
7efd7c27b000-7efd7c27c000 r--p 00009000 08:07 666698                     /usr/lib/x86_64-linux-gnu/libkrb5support.so.0.1
7efd7c27c000-7efd7c27d000 rw-p 0000a000 08:07 666698                     /usr/lib/x86_64-linux-gnu/libkrb5support.so.0.1
7efd7c27d000-7efd7c280000 r-xp 00000000 08:07 1185225                    /lib/x86_64-linux-gnu/libcom_err.so.2.1
7efd7c280000-7efd7c47f000 ---p 00003000 08:07 1185225                    /lib/x86_64-linux-gnu/libcom_err.so.2.1
7efd7c47f000-7efd7c480000 r--p 00002000 08:07 1185225                    /lib/x86_64-linux-gnu/libcom_err.so.2.1
7efd7c480000-7efd7c481000 rw-p 00003000 08:07 1185225                    /lib/x86_64-linux-gnu/libcom_err.so.2.1
7efd7c481000-7efd7c4ad000 r-xp 00000000 08:07 666688                     /usr/lib/x86_64-linux-gnu/libk5crypto.so.3.1
7efd7c4ad000-7efd7c6ac000 ---p 0002c000 08:07 666688                     /usr/lib/x86_64-linux-gnu/libk5crypto.so.3.1
7efd7c6ac000-7efd7c6ae000 r--p 0002b000 08:07 666688                     /usr/lib/x86_64-linux-gnu/libk5crypto.so.3.1
7efd7c6ae000-7efd7c6af000 rw-p 0002d000 08:07 666688                     /usr/lib/x86_64-linux-gnu/libk5crypto.so.3.1
7efd7c6af000-7efd7c6b0000 rw-p 00000000 00:00 0 
7efd7c6b0000-7efd7c773000 r-xp 00000000 08:07 666696                     /usr/lib/x86_64-linux-gnu/libkrb5.so.3.3
7efd7c773000-7efd7c973000 ---p 000c3000 08:07 666696                     /usr/lib/x86_64-linux-gnu/libkrb5.so.3.3
7efd7c973000-7efd7c980000 r--p 000c3000 08:07 666696                     /usr/lib/x86_64-linux-gnu/libkrb5.so.3.3
7efd7c980000-7efd7c982000 rw-p 000d0000 08:07 666696                     /usr/lib/x86_64-linux-gnu/libkrb5.so.3.3
7efd7c982000-7efd7c986000 r-xp 00000000 08:07 1185236                    /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7efd7c986000-7efd7cb85000 ---p 00004000 08:07 1185236                    /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7efd7cb85000-7efd7cb86000 r--p 00003000 08:07 1185236                    /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7efd7cb86000-7efd7cb87000 rw-p 00004000 08:07 1185236                    /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7efd7cb87000-7efd7cc17000 r-xp 00000000 08:07 801061                     /usr/lib/openmpi/lib/libopen-pal.so.13.0.2
7efd7cc17000-7efd7ce17000 ---p 00090000 08:07 801061                     /usr/lib/openmpi/lib/libopen-pal.so.13.0.2
7efd7ce17000-7efd7ce1b000 r--p 00090000 08:07 801061                     /usr/lib/openmpi/lib/libopen-pal.so.13.0.2
7efd7ce1b000-7efd7ce1f000 rw-p 00094000 08:07 801061                     /usr/lib/openmpi/lib/libopen-pal.so.13.0.2
7efd7ce1f000-7efd7ce24000 rw-p 00000000 00:00 0 
7efd7ce24000-7efd7ce99000 r-xp 00000000 08:07 801057                     /usr/lib/openmpi/lib/libopen-rte.so.12.0.2
7efd7ce99000-7efd7d098000 ---p 00075000 08:07 801057                     /usr/lib/openmpi/lib/libopen-rte.so.12.0.2
7efd7d098000-7efd7d099000 r--p 00074000 08:07 801057                     /usr/lib/openmpi/lib/libopen-rte.so.12.0.2
7efd7d099000-7efd7d09c000 rw-p 00075000 08:07 801057                     /usr/lib/openmpi/lib/libopen-rte.so.12.0.2
7efd7d09c000-7efd7d09e000 rw-p 00000000 00:00 0 
7efd7d09e000-7efd7d0ab000 r-xp 00000000 08:07 682135                     /usr/lib/libibverbs.so.1.0.0
7efd7d0ab000-7efd7d2ab000 ---p 0000d000 08:07 682135                     /usr/lib/libibverbs.so.1.0.0
7efd7d2ab000-7efd7d2ac000 r--p 0000d000 08:07 682135                     /usr/lib/libibverbs.so.1.0.0
7efd7d2ac000-7efd7d2ad000 rw-p 0000e000 08:07 682135                     /usr/lib/libibverbs.so.1.0.0
7efd7d2ad000-7efd7d2b2000 r-xp 00000000 08:07 665943                     /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0
7efd7d2b2000-7efd7d4b1000 ---p 00005000 08:07 665943                     /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0
7efd7d4b1000-7efd7d4b2000 r--p 00004000 08:07 665943                     /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0
7efd7d4b2000-7efd7d4b3000 rw-p 00005000 08:07 665943                     /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0
7efd7d4b3000-7efd7d4b5000 r-xp 00000000 08:07 665932                     /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0
7efd7d4b5000-7efd7d6b5000 ---p 00002000 08:07 665932                     /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0
7efd7d6b5000-7efd7d6b6000 r--p 00002000 08:07 665932                     /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0
7efd7d6b6000-7efd7d6b7000 rw-p 00003000 08:07 665932                     /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0
7efd7d6b7000-7efd7d6bf000 r-xp 00000000 08:07 667126                     /usr/lib/x86_64-linux-gnu/libthai.so.0.2.4
7efd7d6bf000-7efd7d8be000 ---p 00008000 08:07 667126                     /usr/lib/x86_64-linux-gnu/libthai.so.0.2.4
7efd7d8be000-7efd7d8bf000 r--p 00007000 08:07 667126                     /usr/lib/x86_64-linux-gnu/libthai.so.0.2.4
7efd7d8bf000-7efd7d8c0000 rw-p 00008000 08:07 667126                     /usr/lib/x86_64-linux-gnu/libthai.so.0.2.4
7efd7d8c0000-7efd7d91c000 r-xp 00000000 08:07 666585                     /usr/lib/x86_64-linux-gnu/libharfbuzz.so.0.10000.1
7efd7d91c000-7efd7db1c000 ---p 0005c000 08:07 666585                     /usr/lib/x86_64-linux-gnu/libharfbuzz.so.0.10000.1
7efd7db1c000-7efd7db1d000 r--p 0005c000 08:07 666585                     /usr/lib/x86_64-linux-gnu/libharfbuzz.so.0.10000.1
7efd7db1d000-7efd7db1e000 rw-p 0005d000 08:07 666585                     /usr/lib/x86_64-linux-gnu/libharfbuzz.so.0.10000.1
7efd7db1e000-7efd7db35000 r-xp 00000000 08:07 1185380                    /lib/x86_64-linux-gnu/libresolv-2.23.so
7efd7db35000-7efd7dd35000 ---p 00017000 08:07 1185380                    /lib/x86_64-linux-gnu/libresolv-2.23.so
7efd7dd35000-7efd7dd36000 r--p 00017000 08:07 1185380                    /lib/x86_64-linux-gnu/libresolv-2.23.so
7efd7dd36000-7efd7dd37000 rw-p 00018000 08:07 1185380                    /lib/x86_64-linux-gnu/libresolv-2.23.so
7efd7dd37000-7efd7dd39000 rw-p 00000000 00:00 0 
7efd7dd39000-7efd7dd58000 r-xp 00000000 08:07 1185386                    /lib/x86_64-linux-gnu/libselinux.so.1
7efd7dd58000-7efd7df57000 ---p 0001f000 08:07 1185386                    /lib/x86_64-linux-gnu/libselinux.so.1
7efd7df57000-7efd7df58000 r--p 0001e000 08:07 1185386                    /lib/x86_64-linux-gnu/libselinux.so.1
7efd7df58000-7efd7df59000 rw-p 0001f000 08:07 1185386                    /lib/x86_64-linux-gnu/libselinux.so.1
7efd7df59000-7efd7df5b000 rw-p 00000000 00:00 0 
7efd7df5b000-7efd7df75000 r-xp 00000000 08:07 657562                     /usr/lib/x86_64-linux-gnu/libcrystalhd.so.3.6
7efd7df75000-7efd7e174000 ---p 0001a000 08:07 657562                     /usr/lib/x86_64-linux-gnu/libcrystalhd.so.3.6
7efd7e174000-7efd7e175000 r--p 00019000 08:07 657562                     /usr/lib/x86_64-linux-gnu/libcrystalhd.so.3.6
7efd7e175000-7efd7e176000 rw-p 0001a000 08:07 657562                     /usr/lib/x86_64-linux-gnu/libcrystalhd.so.3.6
7efd7e176000-7efd7e183000 r-xp 00000000 08:07 657578                     /usr/lib/x86_64-linux-gnu/libgsm.so.1.0.12
7efd7e183000-7efd7e382000 ---p 0000d000 08:07 657578                     /usr/lib/x86_64-linux-gnu/libgsm.so.1.0.12
7efd7e382000-7efd7e383000 r--p 0000c000 08:07 657578                     /usr/lib/x86_64-linux-gnu/libgsm.so.1.0.12
7efd7e383000-7efd7e384000 rw-p 0000d000 08:07 657578                     /usr/lib/x86_64-linux-gnu/libgsm.so.1.0.12
7efd7e384000-7efd7e3c9000 r-xp 00000000 08:07 672563                     /usr/lib/x86_64-linux-gnu/libmp3lame.so.0.0.0
7efd7e3c9000-7efd7e5c9000 ---p 00045000 08:07 672563                     /usr/lib/x86_64-linux-gnu/libmp3lame.so.0.0.0
7efd7e5c9000-7efd7e5ca000 r--p 00045000 08:07 672563                     /usr/lib/x86_64-linux-gnu/libmp3lame.so.0.0.0
7efd7e5ca000-7efd7e5cb000 rw-p 00046000 08:07 672563                     /usr/lib/x86_64-linux-gnu/libmp3lame.so.0.0.0
7efd7e5cb000-7efd7e5f9000 rw-p 00000000 00:00 0 
7efd7e5f9000-7efd7e61b000 r-xp 00000000 08:07 672566                     /usr/lib/x86_64-linux-gnu/libopenjpeg.so.1.5.2
7efd7e61b000-7efd7e81a000 ---p 00022000 08:07 672566                     /usr/lib/x86_64-linux-gnu/libopenjpeg.so.1.5.2
7efd7e81a000-7efd7e81b000 r--p 00021000 08:07 672566                     /usr/lib/x86_64-linux-gnu/libopenjpeg.so.1.5.2
7efd7e81b000-7efd7e81c000 rw-p 00022000 08:07 672566                     /usr/lib/x86_64-linux-gnu/libopenjpeg.so.1.5.2
7efd7e81c000-7efd7e865000 r-xp 00000000 08:07 666869                     /usr/lib/x86_64-linux-gnu/libopus.so.0.5.2
7efd7e865000-7efd7ea64000 ---p 00049000 08:07 666869                     /usr/lib/x86_64-linux-gnu/libopus.so.0.5.2
7efd7ea64000-7efd7ea65000 r--p 00048000 08:07 666869                     /usr/lib/x86_64-linux-gnu/libopus.so.0.5.2
7efd7ea65000-7efd7ea66000 rw-p 00049000 08:07 666869                     /usr/lib/x86_64-linux-gnu/libopus.so.0.5.2
7efd7ea66000-7efd7eb37000 r-xp 00000000 08:07 672183                     /usr/lib/x86_64-linux-gnu/libschroedinger-1.0.so.0.11.0
7efd7eb37000-7efd7ed37000 ---p 000d1000 08:07 672183                     /usr/lib/x86_64-linux-gnu/libschroedinger-1.0.so.0.11.0
7efd7ed37000-7efd7ed39000 r--p 000d1000 08:07 672183                     /usr/lib/x86_64-linux-gnu/libschroedinger-1.0.so.0.11.0
7efd7ed39000-7efd7ed3a000 rw-p 000d3000 08:07 672183                     /usr/lib/x86_64-linux-gnu/libschroedinger-1.0.so.0.11.0
7efd7ed3a000-7efd7ed3b000 rw-p 00000000 00:00 0 
7efd7ed3b000-7efd7ed47000 r-xp 00000000 08:07 672569                     /usr/lib/x86_64-linux-gnu/libshine.so.3.0.1
7efd7ed47000-7efd7ef46000 ---p 0000c000 08:07 672569                     /usr/lib/x86_64-linux-gnu/libshine.so.3.0.1
7efd7ef46000-7efd7ef47000 r--p 0000b000 08:07 672569                     /usr/lib/x86_64-linux-gnu/libshine.so.3.0.1
7efd7ef47000-7efd7ef48000 rw-p 0000c000 08:07 672569                     /usr/lib/x86_64-linux-gnu/libshine.so.3.0.1
7efd7ef48000-7efd7ef4f000 r-xp 00000000 08:07 672571                     /usr/lib/x86_64-linux-gnu/libsnappy.so.1.3.0
7efd7ef4f000-7efd7f14e000 ---p 00007000 08:07 672571                     /usr/lib/x86_64-linux-gnu/libsnappy.so.1.3.0
7efd7f14e000-7efd7f14f000 r--p 00006000 08:07 672571                     /usr/lib/x86_64-linux-gnu/libsnappy.so.1.3.0
7efd7f14f000-7efd7f150000 rw-p 00007000 08:07 672571                     /usr/lib/x86_64-linux-gnu/libsnappy.so.1.3.0
7efd7f150000-7efd7f167000 r-xp 00000000 08:07 667091                     /usr/lib/x86_64-linux-gnu/libspeex.so.1.5.0
7efd7f167000-7efd7f367000 ---p 00017000 08:07 667091                     /usr/lib/x86_64-linux-gnu/libspeex.so.1.5.0
7efd7f367000-7efd7f368000 r--p 00017000 08:07 667091                     /usr/lib/x86_64-linux-gnu/libspeex.so.1.5.0
7efd7f368000-7efd7f369000 rw-p 00018000 08:07 667091                     /usr/lib/x86_64-linux-gnu/libspeex.so.1.5.0
7efd7f369000-7efd7f382000 r-xp 00000000 08:07 667130                     /usr/lib/x86_64-linux-gnu/libtheoradec.so.1.1.4
7efd7f382000-7efd7f581000 ---p 00019000 08:07 667130                     /usr/lib/x86_64-linux-gnu/libtheoradec.so.1.1.4
7efd7f581000-7efd7f582000 r--p 00018000 08:07 667130                     /usr/lib/x86_64-linux-gnu/libtheoradec.so.1.1.4
7efd7f582000-7efd7f583000 rw-p 00019000 08:07 667130                     /usr/lib/x86_64-linux-gnu/libtheoradec.so.1.1.4
7efd7f583000-7efd7f5c1000 r-xp 00000000 08:07 667132                     /usr/lib/x86_64-linux-gnu/libtheoraenc.so.1.1.2
7efd7f5c1000-7efd7f7c0000 ---p 0003e000 08:07 667132                     /usr/lib/x86_64-linux-gnu/libtheoraenc.so.1.1.2
7efd7f7c0000-7efd7f7c1000 r--p 0003d000 08:07 667132                     /usr/lib/x86_64-linux-gnu/libtheoraenc.so.1.1.2
7efd7f7c1000-7efd7f7c2000 rw-p 0003e000 08:07 667132                     /usr/lib/x86_64-linux-gnu/libtheoraenc.so.1.1.2
7efd7f7c2000-7efd7f7e0000 r-xp 00000000 08:07 672577                     /usr/lib/x86_64-linux-gnu/libtwolame.so.0.0.0
7efd7f7e0000-7efd7f9df000 ---p 0001e000 08:07 672577                     /usr/lib/x86_64-linux-gnu/libtwolame.so.0.0.0
7efd7f9df000-7efd7f9e0000 r--p 0001d000 08:07 672577                     /usr/lib/x86_64-linux-gnu/libtwolame.so.0.0.0
7efd7f9e0000-7efd7f9e1000 rw-p 0001e000 08:07 672577                     /usr/lib/x86_64-linux-gnu/libtwolame.so.0.0.0
7efd7f9e1000-7efd7f9e5000 rw-p 00000000 00:00 0 
7efd7f9e5000-7efd7fa0f000 r-xp 00000000 08:07 667229                     /usr/lib/x86_64-linux-gnu/libvorbis.so.0.4.8
7efd7fa0f000-7efd7fc0e000 ---p 0002a000 08:07 667229                     /usr/lib/x86_64-linux-gnu/libvorbis.so.0.4.8
7efd7fc0e000-7efd7fc0f000 r--p 00029000 08:07 667229                     /usr/lib/x86_64-linux-gnu/libvorbis.so.0.4.8
7efd7fc0f000-7efd7fc10000 rw-p 0002a000 08:07 667229                     /usr/lib/x86_64-linux-gnu/libvorbis.so.0.4.8
7efd7fc10000-7efd7fc9d000 r-xp 00000000 08:07 667231                     /usr/lib/x86_64-linux-gnu/libvorbisenc.so.2.0.11
7efd7fc9d000-7efd7fe9c000 ---p 0008d000 08:07 667231                     /usr/lib/x86_64-linux-gnu/libvorbisenc.so.2.0.11
7efd7fe9c000-7efd7feb8000 r--p 0008c000 08:07 667231                     /usr/lib/x86_64-linux-gnu/libvorbisenc.so.2.0.11
7efd7feb8000-7efd7feb9000 rw-p 000a8000 08:07 667231                     /usr/lib/x86_64-linux-gnu/libvorbisenc.so.2.0.11
7efd7feb9000-7efd800d8000 r-xp 00000000 08:07 660824                     /usr/lib/x86_64-linux-gnu/libvpx.so.3.0.0
7efd800d8000-7efd802d7000 ---p 0021f000 08:07 660824                     /usr/lib/x86_64-linux-gnu/libvpx.so.3.0.0
7efd802d7000-7efd802d9000 r--p 0021e000 08:07 660824                     /usr/lib/x86_64-linux-gnu/libvpx.so.3.0.0
7efd802d9000-7efd802da000 rw-p 00220000 08:07 660824                     /usr/lib/x86_64-linux-gnu/libvpx.so.3.0.0
7efd802da000-7efd802dd000 rw-p 00000000 00:00 0 
7efd802dd000-7efd80305000 r-xp 00000000 08:07 667242                     /usr/lib/x86_64-linux-gnu/libwavpack.so.1.1.7
7efd80305000-7efd80504000 ---p 00028000 08:07 667242                     /usr/lib/x86_64-linux-gnu/libwavpack.so.1.1.7
7efd80504000-7efd80505000 r--p 00027000 08:07 667242                     /usr/lib/x86_64-linux-gnu/libwavpack.so.1.1.7
7efd80505000-7efd80506000 rw-p 00028000 08:07 667242                     /usr/lib/x86_64-linux-gnu/libwavpack.so.1.1.7
7efd80506000-7efd8062e000 r-xp 00000000 08:07 672583                     /usr/lib/x86_64-linux-gnu/libx264.so.148
7efd8062e000-7efd8082d000 ---p 00128000 08:07 672583                     /usr/lib/x86_64-linux-gnu/libx264.so.148
7efd8082d000-7efd8082e000 r--p 00127000 08:07 672583                     /usr/lib/x86_64-linux-gnu/libx264.so.148
7efd8082e000-7efd8082f000 rw-p 00128000 08:07 672583                     /usr/lib/x86_64-linux-gnu/libx264.so.148
7efd8082f000-7efd808aa000 rw-p 00000000 00:00 0 
7efd808aa000-7efd812b7000 r-xp 00000000 08:07 672584                     /usr/lib/x86_64-linux-gnu/libx265.so.79
7efd812b7000-7efd814b6000 ---p 00a0d000 08:07 672584                     /usr/lib/x86_64-linux-gnu/libx265.so.79
7efd814b6000-7efd814b9000 r--p 00a0c000 08:07 672584                     /usr/lib/x86_64-linux-gnu/libx265.so.79
7efd814b9000-7efd814bc000 rw-p 00a0f000 08:07 672584                     /usr/lib/x86_64-linux-gnu/libx265.so.79
7efd814bc000-7efd814c9000 rw-p 00000000 00:00 0 
7efd814c9000-7efd8156a000 r-xp 00000000 08:07 672585                     /usr/lib/x86_64-linux-gnu/libxvidcore.so.4.3
7efd8156a000-7efd81769000 ---p 000a1000 08:07 672585                     /usr/lib/x86_64-linux-gnu/libxvidcore.so.4.3
7efd81769000-7efd8176a000 r--p 000a0000 08:07 672585                     /usr/lib/x86_64-linux-gnu/libxvidcore.so.4.3
7efd8176a000-7efd81774000 rw-p 000a1000 08:07 672585                     /usr/lib/x86_64-linux-gnu/libxvidcore.so.4.3
7efd81774000-7efd817dd000 rw-p 00000000 00:00 0 
7efd817dd000-7efd81854000 r-xp 00000000 08:07 672587                     /usr/lib/x86_64-linux-gnu/libzvbi.so.0.13.2
7efd81854000-7efd81a53000 ---p 00077000 08:07 672587                     /usr/lib/x86_64-linux-gnu/libzvbi.so.0.13.2
7efd81a53000-7efd81a5c000 r--p 00076000 08:07 672587                     /usr/lib/x86_64-linux-gnu/libzvbi.so.0.13.2
7efd81a5c000-7efd81a68000 rw-p 0007f000 08:07 672587                     /usr/lib/x86_64-linux-gnu/libzvbi.so.0.13.2
7efd81a68000-7efd81a83000 r-xp 00000000 08:07 672579                     /usr/lib/x86_64-linux-gnu/libva.so.1.3900.0
7efd81a83000-7efd81c82000 ---p 0001b000 08:07 672579                     /usr/lib/x86_64-linux-gnu/libva.so.1.3900.0
7efd81c82000-7efd81c83000 r--p 0001a000 08:07 672579                     /usr/lib/x86_64-linux-gnu/libva.so.1.3900.0
7efd81c83000-7efd81c84000 rw-p 0001b000 08:07 672579                     /usr/lib/x86_64-linux-gnu/libva.so.1.3900.0
7efd81c84000-7efd81c9e000 r-xp 00000000 08:07 672575                     /usr/lib/x86_64-linux-gnu/libswresample-ffmpeg.so.1.2.101
7efd81c9e000-7efd81e9e000 ---p 0001a000 08:07 672575                     /usr/lib/x86_64-linux-gnu/libswresample-ffmpeg.so.1.2.101
7efd81e9e000-7efd81ea0000 r--p 0001a000 08:07 672575                     /usr/lib/x86_64-linux-gnu/libswresample-ffmpeg.so.1.2.101
7efd81ea0000-7efd81ea1000 rw-p 0001c000 08:07 672575                     /usr/lib/x86_64-linux-gnu/libswresample-ffmpeg.so.1.2.101
7efd81ea1000-7efd81eb0000 r-xp 00000000 08:07 1186766                    /lib/x86_64-linux-gnu/libbz2.so.1.0.4
7efd81eb0000-7efd820af000 ---p 0000f000 08:07 1186766                    /lib/x86_64-linux-gnu/libbz2.so.1.0.4
7efd820af000-7efd820b0000 r--p 0000e000 08:07 1186766                    /lib/x86_64-linux-gnu/libbz2.so.1.0.4
7efd820b0000-7efd820b1000 rw-p 0000f000 08:07 1186766                    /lib/x86_64-linux-gnu/libbz2.so.1.0.4
7efd820b1000-7efd821d4000 r-xp 00000000 08:07 664853                     /usr/lib/x86_64-linux-gnu/libgnutls.so.30.6.2
7efd821d4000-7efd823d3000 ---p 00123000 08:07 664853                     /usr/lib/x86_64-linux-gnu/libgnutls.so.30.6.2
7efd823d3000-7efd823de000 r--p 00122000 08:07 664853                     /usr/lib/x86_64-linux-gnu/libgnutls.so.30.6.2
7efd823de000-7efd823e0000 rw-p 0012d000 08:07 664853                     /usr/lib/x86_64-linux-gnu/libgnutls.so.30.6.2
7efd823e0000-7efd823e1000 rw-p 00000000 00:00 0 
7efd823e1000-7efd82428000 r-xp 00000000 08:07 672593                     /usr/lib/x86_64-linux-gnu/libbluray.so.1.9.2
7efd82428000-7efd82627000 ---p 00047000 08:07 672593                     /usr/lib/x86_64-linux-gnu/libbluray.so.1.9.2
7efd82627000-7efd82629000 r--p 00046000 08:07 672593                     /usr/lib/x86_64-linux-gnu/libbluray.so.1.9.2
7efd82629000-7efd8262a000 rw-p 00048000 08:07 672593                     /usr/lib/x86_64-linux-gnu/libbluray.so.1.9.2
7efd8262a000-7efd82674000 r-xp 00000000 08:07 672595                     /usr/lib/x86_64-linux-gnu/libgme.so.0.6.0
7efd82674000-7efd82874000 ---p 0004a000 08:07 672595                     /usr/lib/x86_64-linux-gnu/libgme.so.0.6.0
7efd82874000-7efd82877000 r--p 0004a000 08:07 672595                     /usr/lib/x86_64-linux-gnu/libgme.so.0.6.0
7efd82877000-7efd82878000 rw-p 0004d000 08:07 672595                     /usr/lib/x86_64-linux-gnu/libgme.so.0.6.0
7efd82878000-7efd828c2000 r-xp 00000000 08:07 672597                     /usr/lib/x86_64-linux-gnu/libmodplug.so.1.0.0
7efd828c2000-7efd82ac2000 ---p 0004a000 08:07 672597                     /usr/lib/x86_64-linux-gnu/libmodplug.so.1.0.0
7efd82ac2000-7efd82ac3000 r--p 0004a000 08:07 672597                     /usr/lib/x86_64-linux-gnu/libmodplug.so.1.0.0
7efd82ac3000-7efd82ac4000 rw-p 0004b000 08:07 672597                     /usr/lib/x86_64-linux-gnu/libmodplug.so.1.0.0
7efd82ac4000-7efd82c03000 rw-p 00000000 00:00 0 
7efd82c03000-7efd82c1e000 r-xp 00000000 08:07 667017                     /usr/lib/x86_64-linux-gnu/librtmp.so.1
7efd82c1e000-7efd82e1d000 ---p 0001b000 08:07 667017                     /usr/lib/x86_64-linux-gnu/librtmp.so.1
7efd82e1d000-7efd82e1e000 r--p 0001a000 08:07 667017                     /usr/lib/x86_64-linux-gnu/librtmp.so.1
7efd82e1e000-7efd82e1f000 rw-p 0001b000 08:07 667017                     /usr/lib/x86_64-linux-gnu/librtmp.so.1
7efd82e1f000-7efd82e67000 r-xp 00000000 08:07 672599                     /usr/lib/x86_64-linux-gnu/libssh-gcrypt.so.4.4.1
7efd82e67000-7efd83067000 ---p 00048000 08:07 672599                     /usr/lib/x86_64-linux-gnu/libssh-gcrypt.so.4.4.1
7efd83067000-7efd83068000 r--p 00048000 08:07 672599                     /usr/lib/x86_64-linux-gnu/libssh-gcrypt.so.4.4.1
7efd83068000-7efd83069000 rw-p 00049000 08:07 672599                     /usr/lib/x86_64-linux-gnu/libssh-gcrypt.so.4.4.1
7efd83069000-7efd830d3000 r-xp 00000000 08:07 667892                     /usr/lib/x86_64-linux-gnu/libcurl-gnutls.so.4.4.0
7efd830d3000-7efd832d2000 ---p 0006a000 08:07 667892                     /usr/lib/x86_64-linux-gnu/libcurl-gnutls.so.4.4.0
7efd832d2000-7efd832d5000 r--p 00069000 08:07 667892                     /usr/lib/x86_64-linux-gnu/libcurl-gnutls.so.4.4.0
7efd832d5000-7efd832d6000 rw-p 0006c000 08:07 667892                     /usr/lib/x86_64-linux-gnu/libcurl-gnutls.so.4.4.0
7efd832d6000-7efd8356a000 r-xp 00000000 08:07 672647                     /usr/lib/x86_64-linux-gnu/libhdf5_serial.so.10.1.0
7efd8356a000-7efd83769000 ---p 00294000 08:07 672647                     /usr/lib/x86_64-linux-gnu/libhdf5_serial.so.10.1.0
7efd83769000-7efd8376e000 r--p 00293000 08:07 672647                     /usr/lib/x86_64-linux-gnu/libhdf5_serial.so.10.1.0
7efd8376e000-7efd83773000 rw-p 00298000 08:07 672647                     /usr/lib/x86_64-linux-gnu/libhdf5_serial.so.10.1.0
7efd83773000-7efd83774000 rw-p 00000000 00:00 0 
7efd83774000-7efd83792000 r-xp 00000000 08:07 672649                     /usr/lib/x86_64-linux-gnu/libhdf5_serial_hl.so.10.0.2
7efd83792000-7efd83991000 ---p 0001e000 08:07 672649                     /usr/lib/x86_64-linux-gnu/libhdf5_serial_hl.so.10.0.2
7efd83991000-7efd83992000 r--p 0001d000 08:07 672649                     /usr/lib/x86_64-linux-gnu/libhdf5_serial_hl.so.10.0.2
7efd83992000-7efd83993000 rw-p 0001e000 08:07 672649                     /usr/lib/x86_64-linux-gnu/libhdf5_serial_hl.so.10.0.2
7efd83993000-7efd83994000 rw-p 00000000 00:00 0 
7efd83994000-7efd839e1000 r-xp 00000000 08:07 669767                     /usr/lib/x86_64-linux-gnu/libldap_r-2.4.so.2.10.5
7efd839e1000-7efd83be0000 ---p 0004d000 08:07 669767                     /usr/lib/x86_64-linux-gnu/libldap_r-2.4.so.2.10.5
7efd83be0000-7efd83be2000 r--p 0004c000 08:07 669767                     /usr/lib/x86_64-linux-gnu/libldap_r-2.4.so.2.10.5
7efd83be2000-7efd83be3000 rw-p 0004e000 08:07 669767                     /usr/lib/x86_64-linux-gnu/libldap_r-2.4.so.2.10.5
7efd83be3000-7efd83be5000 rw-p 00000000 00:00 0 
7efd83be5000-7efd83c2c000 r-xp 00000000 08:07 666512                     /usr/lib/x86_64-linux-gnu/libgssapi_krb5.so.2.2
7efd83c2c000-7efd83e2b000 ---p 00047000 08:07 666512                     /usr/lib/x86_64-linux-gnu/libgssapi_krb5.so.2.2
7efd83e2b000-7efd83e2d000 r--p 00046000 08:07 666512                     /usr/lib/x86_64-linux-gnu/libgssapi_krb5.so.2.2
7efd83e2d000-7efd83e2f000 rw-p 00048000 08:07 666512                     /usr/lib/x86_64-linux-gnu/libgssapi_krb5.so.2.2
7efd83e2f000-7efd8404a000 r-xp 00000000 08:07 1185165                    /lib/x86_64-linux-gnu/libcrypto.so.1.0.0
7efd8404a000-7efd84249000 ---p 0021b000 08:07 1185165                    /lib/x86_64-linux-gnu/libcrypto.so.1.0.0
7efd84249000-7efd84265000 r--p 0021a000 08:07 1185165                    /lib/x86_64-linux-gnu/libcrypto.so.1.0.0
7efd84265000-7efd84271000 rw-p 00236000 08:07 1185165                    /lib/x86_64-linux-gnu/libcrypto.so.1.0.0
7efd84271000-7efd84274000 rw-p 00000000 00:00 0 
7efd84274000-7efd842d2000 r-xp 00000000 08:07 1185166                    /lib/x86_64-linux-gnu/libssl.so.1.0.0
7efd842d2000-7efd844d2000 ---p 0005e000 08:07 1185166                    /lib/x86_64-linux-gnu/libssl.so.1.0.0
7efd844d2000-7efd844d6000 r--p 0005e000 08:07 1185166                    /lib/x86_64-linux-gnu/libssl.so.1.0.0
7efd844d6000-7efd844dd000 rw-p 00062000 08:07 1185166                    /lib/x86_64-linux-gnu/libssl.so.1.0.0
7efd844dd000-7efd844f3000 r-xp 00000000 08:07 665796                     /usr/lib/x86_64-linux-gnu/libICE.so.6.3.0
7efd844f3000-7efd846f2000 ---p 00016000 08:07 665796                     /usr/lib/x86_64-linux-gnu/libICE.so.6.3.0
7efd846f2000-7efd846f3000 r--p 00015000 08:07 665796                     /usr/lib/x86_64-linux-gnu/libICE.so.6.3.0
7efd846f3000-7efd846f4000 rw-p 00016000 08:07 665796                     /usr/lib/x86_64-linux-gnu/libICE.so.6.3.0
7efd846f4000-7efd846f7000 rw-p 00000000 00:00 0 
7efd846f7000-7efd846fe000 r-xp 00000000 08:07 665918                     /usr/lib/x86_64-linux-gnu/libSM.so.6.0.1
7efd846fe000-7efd848fd000 ---p 00007000 08:07 665918                     /usr/lib/x86_64-linux-gnu/libSM.so.6.0.1
7efd848fd000-7efd848fe000 r--p 00006000 08:07 665918                     /usr/lib/x86_64-linux-gnu/libSM.so.6.0.1
7efd848fe000-7efd848ff000 rw-p 00007000 08:07 665918                     /usr/lib/x86_64-linux-gnu/libSM.so.6.0.1
7efd848ff000-7efd84916000 r-xp 00000000 08:07 666048                     /usr/lib/x86_64-linux-gnu/libaudio.so.2.4
7efd84916000-7efd84b16000 ---p 00017000 08:07 666048                     /usr/lib/x86_64-linux-gnu/libaudio.so.2.4
7efd84b16000-7efd84b17000 r--p 00017000 08:07 666048                     /usr/lib/x86_64-linux-gnu/libaudio.so.2.4
7efd84b17000-7efd84b18000 rw-p 00018000 08:07 666048                     /usr/lib/x86_64-linux-gnu/libaudio.so.2.4
7efd84b18000-7efd84b28000 r-xp 00000000 08:07 666244                     /usr/lib/x86_64-linux-gnu/libdrm.so.2.4.0
7efd84b28000-7efd84d28000 ---p 00010000 08:07 666244                     /usr/lib/x86_64-linux-gnu/libdrm.so.2.4.0
7efd84d28000-7efd84d29000 r--p 00010000 08:07 666244                     /usr/lib/x86_64-linux-gnu/libdrm.so.2.4.0
7efd84d29000-7efd84d2a000 rw-p 00011000 08:07 666244                     /usr/lib/x86_64-linux-gnu/libdrm.so.2.4.0
7efd84d2a000-7efd84d2f000 r-xp 00000000 08:07 665983                     /usr/lib/x86_64-linux-gnu/libXxf86vm.so.1.0.0
7efd84d2f000-7efd84f2e000 ---p 00005000 08:07 665983                     /usr/lib/x86_64-linux-gnu/libXxf86vm.so.1.0.0
7efd84f2e000-7efd84f2f000 r--p 00004000 08:07 665983                     /usr/lib/x86_64-linux-gnu/libXxf86vm.so.1.0.0
7efd84f2f000-7efd84f30000 rw-p 00005000 08:07 665983                     /usr/lib/x86_64-linux-gnu/libXxf86vm.so.1.0.0
7efd84f30000-7efd84f34000 r-xp 00000000 08:07 667324                     /usr/lib/x86_64-linux-gnu/libxcb-dri2.so.0.0.0
7efd84f34000-7efd85133000 ---p 00004000 08:07 667324                     /usr/lib/x86_64-linux-gnu/libxcb-dri2.so.0.0.0
7efd85133000-7efd85134000 r--p 00003000 08:07 667324                     /usr/lib/x86_64-linux-gnu/libxcb-dri2.so.0.0.0
7efd85134000-7efd85135000 rw-p 00004000 08:07 667324                     /usr/lib/x86_64-linux-gnu/libxcb-dri2.so.0.0.0
7efd85135000-7efd8514c000 r-xp 00000000 08:07 667328                     /usr/lib/x86_64-linux-gnu/libxcb-glx.so.0.0.0
7efd8514c000-7efd8534b000 ---p 00017000 08:07 667328                     /usr/lib/x86_64-linux-gnu/libxcb-glx.so.0.0.0
7efd8534b000-7efd8534d000 r--p 00016000 08:07 667328                     /usr/lib/x86_64-linux-gnu/libxcb-glx.so.0.0.0
7efd8534d000-7efd8534e000 rw-p 00018000 08:07 667328                     /usr/lib/x86_64-linux-gnu/libxcb-glx.so.0.0.0
7efd8534e000-7efd8534f000 r-xp 00000000 08:07 665926                     /usr/lib/x86_64-linux-gnu/libX11-xcb.so.1.0.0
7efd8534f000-7efd8554e000 ---p 00001000 08:07 665926                     /usr/lib/x86_64-linux-gnu/libX11-xcb.so.1.0.0
7efd8554e000-7efd8554f000 r--p 00000000 08:07 665926                     /usr/lib/x86_64-linux-gnu/libX11-xcb.so.1.0.0
7efd8554f000-7efd85550000 rw-p 00001000 08:07 665926                     /usr/lib/x86_64-linux-gnu/libX11-xcb.so.1.0.0
7efd85550000-7efd8557c000 r-xp 00000000 08:07 666445                     /usr/lib/x86_64-linux-gnu/libglapi.so.0.0.0
7efd8557c000-7efd8577b000 ---p 0002c000 08:07 666445                     /usr/lib/x86_64-linux-gnu/libglapi.so.0.0.0
7efd8577b000-7efd8577f000 r--p 0002b000 08:07 666445                     /usr/lib/x86_64-linux-gnu/libglapi.so.0.0.0
7efd8577f000-7efd85780000 rw-p 0002f000 08:07 666445                     /usr/lib/x86_64-linux-gnu/libglapi.so.0.0.0
7efd85780000-7efd85781000 rw-p 00000000 00:00 0 
7efd85781000-7efd85782000 r-xp 00000000 08:07 667368                     /usr/lib/x86_64-linux-gnu/libxshmfence.so.1.0.0
7efd85782000-7efd85982000 ---p 00001000 08:07 667368                     /usr/lib/x86_64-linux-gnu/libxshmfence.so.1.0.0
7efd85982000-7efd85983000 r--p 00001000 08:07 667368                     /usr/lib/x86_64-linux-gnu/libxshmfence.so.1.0.0
7efd85983000-7efd85984000 rw-p 00002000 08:07 667368                     /usr/lib/x86_64-linux-gnu/libxshmfence.so.1.0.0
7efd85984000-7efd85989000 r-xp 00000000 08:07 667348                     /usr/lib/x86_64-linux-gnu/libxcb-sync.so.1.0.0
7efd85989000-7efd85b89000 ---p 00005000 08:07 667348                     /usr/lib/x86_64-linux-gnu/libxcb-sync.so.1.0.0
7efd85b89000-7efd85b8a000 r--p 00005000 08:07 667348                     /usr/lib/x86_64-linux-gnu/libxcb-sync.so.1.0.0
7efd85b8a000-7efd85b8b000 rw-p 00006000 08:07 667348                     /usr/lib/x86_64-linux-gnu/libxcb-sync.so.1.0.0
7efd85b8b000-7efd85b8d000 r-xp 00000000 08:07 667336                     /usr/lib/x86_64-linux-gnu/libxcb-present.so.0.0.0
7efd85b8d000-7efd85d8c000 ---p 00002000 08:07 667336                     /usr/lib/x86_64-linux-gnu/libxcb-present.so.0.0.0
7efd85d8c000-7efd85d8d000 r--p 00001000 08:07 667336                     /usr/lib/x86_64-linux-gnu/libxcb-present.so.0.0.0
7efd85d8d000-7efd85d8e000 rw-p 00002000 08:07 667336                     /usr/lib/x86_64-linux-gnu/libxcb-present.so.0.0.0
7efd85d8e000-7efd85d90000 r-xp 00000000 08:07 667326                     /usr/lib/x86_64-linux-gnu/libxcb-dri3.so.0.0.0
7efd85d90000-7efd85f8f000 ---p 00002000 08:07 667326                     /usr/lib/x86_64-linux-gnu/libxcb-dri3.so.0.0.0
7efd85f8f000-7efd85f90000 r--p 00001000 08:07 667326                     /usr/lib/x86_64-linux-gnu/libxcb-dri3.so.0.0.0
7efd85f90000-7efd85f91000 rw-p 00002000 08:07 667326                     /usr/lib/x86_64-linux-gnu/libxcb-dri3.so.0.0.0
7efd85f91000-7efd86043000 r-xp 00000000 08:07 801054                     /usr/lib/openmpi/lib/libmpi.so.12.0.2
7efd86043000-7efd86243000 ---p 000b2000 08:07 801054                     /usr/lib/openmpi/lib/libmpi.so.12.0.2
7efd86243000-7efd86244000 r--p 000b2000 08:07 801054                     /usr/lib/openmpi/lib/libmpi.so.12.0.2
7efd86244000-7efd86254000 rw-p 000b3000 08:07 801054                     /usr/lib/openmpi/lib/libmpi.so.12.0.2
7efd86254000-7efd86267000 rw-p 00000000 00:00 0 
7efd86267000-7efd8627f000 r-xp 00000000 08:07 801045                     /usr/lib/openmpi/lib/libmpi_cxx.so.1.1.3
7efd8627f000-7efd8647f000 ---p 00018000 08:07 801045                     /usr/lib/openmpi/lib/libmpi_cxx.so.1.1.3
7efd8647f000-7efd86481000 r--p 00018000 08:07 801045                     /usr/lib/openmpi/lib/libmpi_cxx.so.1.1.3
7efd86481000-7efd86482000 rw-p 0001a000 08:07 801045                     /usr/lib/openmpi/lib/libmpi_cxx.so.1.1.3
7efd86482000-7efd864b0000 r-xp 00000000 08:07 671316                     /usr/lib/libCosmo.so.5.10.1
7efd864b0000-7efd866af000 ---p 0002e000 08:07 671316                     /usr/lib/libCosmo.so.5.10.1
7efd866af000-7efd866b1000 r--p 0002d000 08:07 671316                     /usr/lib/libCosmo.so.5.10.1
7efd866b1000-7efd866b2000 rw-p 0002f000 08:07 671316                     /usr/lib/libCosmo.so.5.10.1
7efd866b2000-7efd866db000 r-xp 00000000 08:07 660055                     /usr/lib/libVPIC.so.5.10.1
7efd866db000-7efd868da000 ---p 00029000 08:07 660055                     /usr/lib/libVPIC.so.5.10.1
7efd868da000-7efd868dc000 r--p 00028000 08:07 660055                     /usr/lib/libVPIC.so.5.10.1
7efd868dc000-7efd868dd000 rw-p 0002a000 08:07 660055                     /usr/lib/libVPIC.so.5.10.1
7efd868dd000-7efd868e2000 r-xp 00000000 08:07 665806                     /usr/lib/x86_64-linux-gnu/libIlmThread-2_2.so.12.0.0
7efd868e2000-7efd86ae2000 ---p 00005000 08:07 665806                     /usr/lib/x86_64-linux-gnu/libIlmThread-2_2.so.12.0.0
7efd86ae2000-7efd86ae3000 r--p 00005000 08:07 665806                     /usr/lib/x86_64-linux-gnu/libIlmThread-2_2.so.12.0.0
7efd86ae3000-7efd86ae4000 rw-p 00006000 08:07 665806                     /usr/lib/x86_64-linux-gnu/libIlmThread-2_2.so.12.0.0
7efd86ae4000-7efd86aff000 r-xp 00000000 08:07 665798                     /usr/lib/x86_64-linux-gnu/libIex-2_2.so.12.0.0
7efd86aff000-7efd86cfe000 ---p 0001b000 08:07 665798                     /usr/lib/x86_64-linux-gnu/libIex-2_2.so.12.0.0
7efd86cfe000-7efd86d01000 r--p 0001a000 08:07 665798                     /usr/lib/x86_64-linux-gnu/libIex-2_2.so.12.0.0
7efd86d01000-7efd86d02000 rw-p 0001d000 08:07 665798                     /usr/lib/x86_64-linux-gnu/libIex-2_2.so.12.0.0
7efd86d02000-7efd86d0d000 r-xp 00000000 08:07 666680                     /usr/lib/x86_64-linux-gnu/libjbig.so.0
7efd86d0d000-7efd86f0c000 ---p 0000b000 08:07 666680                     /usr/lib/x86_64-linux-gnu/libjbig.so.0
7efd86f0c000-7efd86f0d000 r--p 0000a000 08:07 666680                     /usr/lib/x86_64-linux-gnu/libjbig.so.0
7efd86f0d000-7efd86f10000 rw-p 0000b000 08:07 666680                     /usr/lib/x86_64-linux-gnu/libjbig.so.0
7efd86f10000-7efd86f31000 r-xp 00000000 08:07 1185295                    /lib/x86_64-linux-gnu/liblzma.so.5.0.0
7efd86f31000-7efd87130000 ---p 00021000 08:07 1185295                    /lib/x86_64-linux-gnu/liblzma.so.5.0.0
7efd87130000-7efd87131000 r--p 00020000 08:07 1185295                    /lib/x86_64-linux-gnu/liblzma.so.5.0.0
7efd87131000-7efd87132000 rw-p 00021000 08:07 1185295                    /lib/x86_64-linux-gnu/liblzma.so.5.0.0
7efd87132000-7efd871a0000 r-xp 00000000 08:07 1185357                    /lib/x86_64-linux-gnu/libpcre.so.3.13.2
7efd871a0000-7efd873a0000 ---p 0006e000 08:07 1185357                    /lib/x86_64-linux-gnu/libpcre.so.3.13.2
7efd873a0000-7efd873a1000 r--p 0006e000 08:07 1185357                    /lib/x86_64-linux-gnu/libpcre.so.3.13.2
7efd873a1000-7efd873a2000 rw-p 0006f000 08:07 1185357                    /lib/x86_64-linux-gnu/libpcre.so.3.13.2
7efd873a2000-7efd873a9000 r-xp 00000000 08:07 666322                     /usr/lib/x86_64-linux-gnu/libffi.so.6.0.4
7efd873a9000-7efd875a8000 ---p 00007000 08:07 666322                     /usr/lib/x86_64-linux-gnu/libffi.so.6.0.4
7efd875a8000-7efd875a9000 r--p 00006000 08:07 666322                     /usr/lib/x86_64-linux-gnu/libffi.so.6.0.4
7efd875a9000-7efd875aa000 rw-p 00007000 08:07 666322                     /usr/lib/x86_64-linux-gnu/libffi.so.6.0.4
7efd875aa000-7efd875cb000 r-xp 00000000 08:07 667356                     /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0
7efd875cb000-7efd877ca000 ---p 00021000 08:07 667356                     /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0
7efd877ca000-7efd877cb000 r--p 00020000 08:07 667356                     /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0
7efd877cb000-7efd877cc000 rw-p 00021000 08:07 667356                     /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0
7efd877cc000-7efd877d4000 r-xp 00000000 08:07 667342                     /usr/lib/x86_64-linux-gnu/libxcb-render.so.0.0.0
7efd877d4000-7efd879d4000 ---p 00008000 08:07 667342                     /usr/lib/x86_64-linux-gnu/libxcb-render.so.0.0.0
7efd879d4000-7efd879d5000 r--p 00008000 08:07 667342                     /usr/lib/x86_64-linux-gnu/libxcb-render.so.0.0.0
7efd879d5000-7efd879d6000 rw-p 00009000 08:07 667342                     /usr/lib/x86_64-linux-gnu/libxcb-render.so.0.0.0
7efd879d6000-7efd879d8000 r-xp 00000000 08:07 667346                     /usr/lib/x86_64-linux-gnu/libxcb-shm.so.0.0.0
7efd879d8000-7efd87bd8000 ---p 00002000 08:07 667346                     /usr/lib/x86_64-linux-gnu/libxcb-shm.so.0.0.0
7efd87bd8000-7efd87bd9000 r--p 00002000 08:07 667346                     /usr/lib/x86_64-linux-gnu/libxcb-shm.so.0.0.0
7efd87bd9000-7efd87bda000 rw-p 00003000 08:07 667346                     /usr/lib/x86_64-linux-gnu/libxcb-shm.so.0.0.0
7efd87bda000-7efd87c79000 r-xp 00000000 08:07 666921                     /usr/lib/x86_64-linux-gnu/libpixman-1.so.0.33.6
7efd87c79000-7efd87e79000 ---p 0009f000 08:07 666921                     /usr/lib/x86_64-linux-gnu/libpixman-1.so.0.33.6
7efd87e79000-7efd87e81000 r--p 0009f000 08:07 666921                     /usr/lib/x86_64-linux-gnu/libpixman-1.so.0.33.6
7efd87e81000-7efd87e82000 rw-p 000a7000 08:07 666921                     /usr/lib/x86_64-linux-gnu/libpixman-1.so.0.33.6
7efd87e82000-7efd87e93000 r-xp 00000000 08:07 665945                     /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0
7efd87e93000-7efd88092000 ---p 00011000 08:07 665945                     /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0
7efd88092000-7efd88093000 r--p 00010000 08:07 665945                     /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0
7efd88093000-7efd88094000 rw-p 00011000 08:07 665945                     /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0
7efd88094000-7efd88096000 r-xp 00000000 08:07 665941                     /usr/lib/x86_64-linux-gnu/libXdamage.so.1.1.0
7efd88096000-7efd88295000 ---p 00002000 08:07 665941                     /usr/lib/x86_64-linux-gnu/libXdamage.so.1.1.0
7efd88295000-7efd88296000 r--p 00001000 08:07 665941                     /usr/lib/x86_64-linux-gnu/libXdamage.so.1.1.0
7efd88296000-7efd88297000 rw-p 00002000 08:07 665941                     /usr/lib/x86_64-linux-gnu/libXdamage.so.1.1.0
7efd88297000-7efd88299000 r-xp 00000000 08:07 665937                     /usr/lib/x86_64-linux-gnu/libXcomposite.so.1.0.0
7efd88299000-7efd88498000 ---p 00002000 08:07 665937                     /usr/lib/x86_64-linux-gnu/libXcomposite.so.1.0.0
7efd88498000-7efd88499000 r--p 00001000 08:07 665937                     /usr/lib/x86_64-linux-gnu/libXcomposite.so.1.0.0
7efd88499000-7efd8849a000 rw-p 00002000 08:07 665937                     /usr/lib/x86_64-linux-gnu/libXcomposite.so.1.0.0
7efd8849a000-7efd884a3000 r-xp 00000000 08:07 665939                     /usr/lib/x86_64-linux-gnu/libXcursor.so.1.0.2
7efd884a3000-7efd886a2000 ---p 00009000 08:07 665939                     /usr/lib/x86_64-linux-gnu/libXcursor.so.1.0.2
7efd886a2000-7efd886a3000 r--p 00008000 08:07 665939                     /usr/lib/x86_64-linux-gnu/libXcursor.so.1.0.2
7efd886a3000-7efd886a4000 rw-p 00009000 08:07 665939                     /usr/lib/x86_64-linux-gnu/libXcursor.so.1.0.2
7efd886a4000-7efd886ae000 r-xp 00000000 08:07 665965                     /usr/lib/x86_64-linux-gnu/libXrandr.so.2.2.0
7efd886ae000-7efd888ad000 ---p 0000a000 08:07 665965                     /usr/lib/x86_64-linux-gnu/libXrandr.so.2.2.0
7efd888ad000-7efd888ae000 r--p 00009000 08:07 665965                     /usr/lib/x86_64-linux-gnu/libXrandr.so.2.2.0
7efd888ae000-7efd888af000 rw-p 0000a000 08:07 665965                     /usr/lib/x86_64-linux-gnu/libXrandr.so.2.2.0
7efd888af000-7efd888be000 r-xp 00000000 08:07 665955                     /usr/lib/x86_64-linux-gnu/libXi.so.6.1.0
7efd888be000-7efd88abd000 ---p 0000f000 08:07 665955                     /usr/lib/x86_64-linux-gnu/libXi.so.6.1.0
7efd88abd000-7efd88abe000 r--p 0000e000 08:07 665955                     /usr/lib/x86_64-linux-gnu/libXi.so.6.1.0
7efd88abe000-7efd88abf000 rw-p 0000f000 08:07 665955                     /usr/lib/x86_64-linux-gnu/libXi.so.6.1.0
7efd88abf000-7efd88ac1000 r-xp 00000000 08:07 665957                     /usr/lib/x86_64-linux-gnu/libXinerama.so.1.0.0
7efd88ac1000-7efd88cc0000 ---p 00002000 08:07 665957                     /usr/lib/x86_64-linux-gnu/libXinerama.so.1.0.0
7efd88cc0000-7efd88cc1000 r--p 00001000 08:07 665957                     /usr/lib/x86_64-linux-gnu/libXinerama.so.1.0.0
7efd88cc1000-7efd88cc2000 rw-p 00002000 08:07 665957                     /usr/lib/x86_64-linux-gnu/libXinerama.so.1.0.0
7efd88cc2000-7efd88ccb000 r-xp 00000000 08:07 665967                     /usr/lib/x86_64-linux-gnu/libXrender.so.1.3.0
7efd88ccb000-7efd88eca000 ---p 00009000 08:07 665967                     /usr/lib/x86_64-linux-gnu/libXrender.so.1.3.0
7efd88eca000-7efd88ecb000 r--p 00008000 08:07 665967                     /usr/lib/x86_64-linux-gnu/libXrender.so.1.3.0
7efd88ecb000-7efd88ecc000 rw-p 00009000 08:07 665967                     /usr/lib/x86_64-linux-gnu/libXrender.so.1.3.0
7efd88ecc000-7efd88f09000 r-xp 00000000 08:07 666336                     /usr/lib/x86_64-linux-gnu/libfontconfig.so.1.9.0
7efd88f09000-7efd89108000 ---p 0003d000 08:07 666336                     /usr/lib/x86_64-linux-gnu/libfontconfig.so.1.9.0
7efd89108000-7efd8910a000 r--p 0003c000 08:07 666336                     /usr/lib/x86_64-linux-gnu/libfontconfig.so.1.9.0
7efd8910a000-7efd8910f000 rw-p 0003e000 08:07 666336                     /usr/lib/x86_64-linux-gnu/libfontconfig.so.1.9.0
7efd8910f000-7efd89158000 r-xp 00000000 08:07 666891                     /usr/lib/x86_64-linux-gnu/libpango-1.0.so.0.3800.1
7efd89158000-7efd89358000 ---p 00049000 08:07 666891                     /usr/lib/x86_64-linux-gnu/libpango-1.0.so.0.3800.1
7efd89358000-7efd8935a000 r--p 00049000 08:07 666891                     /usr/lib/x86_64-linux-gnu/libpango-1.0.so.0.3800.1
7efd8935a000-7efd8935b000 rw-p 0004b000 08:07 666891                     /usr/lib/x86_64-linux-gnu/libpango-1.0.so.0.3800.1
7efd8935b000-7efd8936f000 r-xp 00000000 08:07 666895                     /usr/lib/x86_64-linux-gnu/libpangoft2-1.0.so.0.3800.1
7efd8936f000-7efd8956f000 ---p 00014000 08:07 666895                     /usr/lib/x86_64-linux-gnu/libpangoft2-1.0.so.0.3800.1
7efd8956f000-7efd89570000 r--p 00014000 08:07 666895                     /usr/lib/x86_64-linux-gnu/libpangoft2-1.0.so.0.3800.1
7efd89570000-7efd89571000 rw-p 00015000 08:07 666895                     /usr/lib/x86_64-linux-gnu/libpangoft2-1.0.so.0.3800.1
7efd89571000-7efd896f1000 r-xp 00000000 08:07 655647                     /usr/lib/x86_64-linux-gnu/libgio-2.0.so.0.4800.2
7efd896f1000-7efd898f1000 ---p 00180000 08:07 655647                     /usr/lib/x86_64-linux-gnu/libgio-2.0.so.0.4800.2
7efd898f1000-7efd898f5000 r--p 00180000 08:07 655647                     /usr/lib/x86_64-linux-gnu/libgio-2.0.so.0.4800.2
7efd898f5000-7efd898f7000 rw-p 00184000 08:07 655647                     /usr/lib/x86_64-linux-gnu/libgio-2.0.so.0.4800.2
7efd898f7000-7efd898f9000 rw-p 00000000 00:00 0 
7efd898f9000-7efd8991b000 r-xp 00000000 08:07 666038                     /usr/lib/x86_64-linux-gnu/libatk-1.0.so.0.21809.1
7efd8991b000-7efd89b1a000 ---p 00022000 08:07 666038                     /usr/lib/x86_64-linux-gnu/libatk-1.0.so.0.21809.1
7efd89b1a000-7efd89b1d000 r--p 00021000 08:07 666038                     /usr/lib/x86_64-linux-gnu/libatk-1.0.so.0.21809.1
7efd89b1d000-7efd89b1e000 rw-p 00024000 08:07 666038                     /usr/lib/x86_64-linux-gnu/libatk-1.0.so.0.21809.1
7efd89b1e000-7efd89b23000 r-xp 00000000 08:07 665947                     /usr/lib/x86_64-linux-gnu/libXfixes.so.3.1.0
7efd89b23000-7efd89d22000 ---p 00005000 08:07 665947                     /usr/lib/x86_64-linux-gnu/libXfixes.so.3.1.0
7efd89d22000-7efd89d23000 r--p 00004000 08:07 665947                     /usr/lib/x86_64-linux-gnu/libXfixes.so.3.1.0
7efd89d23000-7efd89d24000 rw-p 00005000 08:07 665947                     /usr/lib/x86_64-linux-gnu/libXfixes.so.3.1.0
7efd89d24000-7efd89d30000 r-xp 00000000 08:07 666893                     /usr/lib/x86_64-linux-gnu/libpangocairo-1.0.so.0.3800.1
7efd89d30000-7efd89f2f000 ---p 0000c000 08:07 666893                     /usr/lib/x86_64-linux-gnu/libpangocairo-1.0.so.0.3800.1
7efd89f2f000-7efd89f30000 r--p 0000b000 08:07 666893                     /usr/lib/x86_64-linux-gnu/libpangocairo-1.0.so.0.3800.1
7efd89f30000-7efd89f31000 rw-p 0000c000 08:07 666893                     /usr/lib/x86_64-linux-gnu/libpangocairo-1.0.so.0.3800.1
7efd89f31000-7efd89f34000 r-xp 00000000 08:07 655645                     /usr/lib/x86_64-linux-gnu/libgmodule-2.0.so.0.4800.2
7efd89f34000-7efd8a133000 ---p 00003000 08:07 655645                     /usr/lib/x86_64-linux-gnu/libgmodule-2.0.so.0.4800.2
7efd8a133000-7efd8a134000 r--p 00002000 08:07 655645                     /usr/lib/x86_64-linux-gnu/libgmodule-2.0.so.0.4800.2
7efd8a134000-7efd8a135000 rw-p 00003000 08:07 655645                     /usr/lib/x86_64-linux-gnu/libgmodule-2.0.so.0.4800.2
7efd8a135000-7efd8a1ba000 r-xp 00000000 08:07 673105                     /usr/lib/x86_64-linux-gnu/libswscale-ffmpeg.so.3.1.101
7efd8a1ba000-7efd8a3b9000 ---p 00085000 08:07 673105                     /usr/lib/x86_64-linux-gnu/libswscale-ffmpeg.so.3.1.101
7efd8a3b9000-7efd8a3bb000 r--p 00084000 08:07 673105                     /usr/lib/x86_64-linux-gnu/libswscale-ffmpeg.so.3.1.101
7efd8a3bb000-7efd8a3bc000 rw-p 00086000 08:07 673105                     /usr/lib/x86_64-linux-gnu/libswscale-ffmpeg.so.3.1.101
7efd8a3bc000-7efd8a3c4000 rw-p 00000000 00:00 0 
7efd8a3c4000-7efd8a41a000 r-xp 00000000 08:07 672561                     /usr/lib/x86_64-linux-gnu/libavutil-ffmpeg.so.54.31.100
7efd8a41a000-7efd8a619000 ---p 00056000 08:07 672561                     /usr/lib/x86_64-linux-gnu/libavutil-ffmpeg.so.54.31.100
7efd8a619000-7efd8a61f000 r--p 00055000 08:07 672561                     /usr/lib/x86_64-linux-gnu/libavutil-ffmpeg.so.54.31.100
7efd8a61f000-7efd8a620000 rw-p 0005b000 08:07 672561                     /usr/lib/x86_64-linux-gnu/libavutil-ffmpeg.so.54.31.100
7efd8a620000-7efd8a633000 rw-p 00000000 00:00 0 
7efd8a633000-7efd8b164000 r-xp 00000000 08:07 672591                     /usr/lib/x86_64-linux-gnu/libavcodec-ffmpeg.so.56.60.100
7efd8b164000-7efd8b363000 ---p 00b31000 08:07 672591                     /usr/lib/x86_64-linux-gnu/libavcodec-ffmpeg.so.56.60.100
7efd8b363000-7efd8b38e000 r--p 00b30000 08:07 672591                     /usr/lib/x86_64-linux-gnu/libavcodec-ffmpeg.so.56.60.100
7efd8b38e000-7efd8b3b1000 rw-p 00b5b000 08:07 672591                     /usr/lib/x86_64-linux-gnu/libavcodec-ffmpeg.so.56.60.100
7efd8b3b1000-7efd8ba64000 rw-p 00000000 00:00 0 
7efd8ba64000-7efd8bc3a000 r-xp 00000000 08:07 672603                     /usr/lib/x86_64-linux-gnu/libavformat-ffmpeg.so.56.40.101
7efd8bc3a000-7efd8be3a000 ---p 001d6000 08:07 672603                     /usr/lib/x86_64-linux-gnu/libavformat-ffmpeg.so.56.40.101
7efd8be3a000-7efd8be4e000 r--p 001d6000 08:07 672603                     /usr/lib/x86_64-linux-gnu/libavformat-ffmpeg.so.56.40.101
7efd8be4e000-7efd8be63000 rw-p 001ea000 08:07 672603                     /usr/lib/x86_64-linux-gnu/libavformat-ffmpeg.so.56.40.101
7efd8be63000-7efd8be89000 r-xp 00000000 08:07 1185170                    /lib/x86_64-linux-gnu/libexpat.so.1.6.0
7efd8be89000-7efd8c089000 ---p 00026000 08:07 1185170                    /lib/x86_64-linux-gnu/libexpat.so.1.6.0
7efd8c089000-7efd8c08b000 r--p 00026000 08:07 1185170                    /lib/x86_64-linux-gnu/libexpat.so.1.6.0
7efd8c08b000-7efd8c08c000 rw-p 00028000 08:07 1185170                    /lib/x86_64-linux-gnu/libexpat.so.1.6.0
7efd8c08c000-7efd8c15c000 r-xp 00000000 08:07 664481                     /usr/lib/x86_64-linux-gnu/libsqlite3.so.0.8.6
7efd8c15c000-7efd8c35b000 ---p 000d0000 08:07 664481                     /usr/lib/x86_64-linux-gnu/libsqlite3.so.0.8.6
7efd8c35b000-7efd8c35e000 r--p 000cf000 08:07 664481                     /usr/lib/x86_64-linux-gnu/libsqlite3.so.0.8.6
7efd8c35e000-7efd8c360000 rw-p 000d2000 08:07 664481                     /usr/lib/x86_64-linux-gnu/libsqlite3.so.0.8.6
7efd8c360000-7efd8c361000 rw-p 00000000 00:00 0 
7efd8c361000-7efd8c3ff000 r-xp 00000000 08:07 659455                     /usr/lib/libvtkmetaio.so.5.10.1
7efd8c3ff000-7efd8c5ff000 ---p 0009e000 08:07 659455                     /usr/lib/libvtkmetaio.so.5.10.1
7efd8c5ff000-7efd8c601000 r--p 0009e000 08:07 659455                     /usr/lib/libvtkmetaio.so.5.10.1
7efd8c601000-7efd8c602000 rw-p 000a0000 08:07 659455                     /usr/lib/libvtkmetaio.so.5.10.1
7efd8c602000-7efd8c60e000 r-xp 00000000 08:07 660056                     /usr/lib/libLSDyna.so.5.10.1
7efd8c60e000-7efd8c80e000 ---p 0000c000 08:07 660056                     /usr/lib/libLSDyna.so.5.10.1
7efd8c80e000-7efd8c80f000 r--p 0000c000 08:07 660056                     /usr/lib/libLSDyna.so.5.10.1
7efd8c80f000-7efd8c810000 rw-p 0000d000 08:07 660056                     /usr/lib/libLSDyna.so.5.10.1
7efd8c810000-7efd8c82c000 r-xp 00000000 08:07 684256                     /usr/lib/x86_64-linux-gnu/libnetcdf_c++.so.4.2.0
7efd8c82c000-7efd8ca2b000 ---p 0001c000 08:07 684256                     /usr/lib/x86_64-linux-gnu/libnetcdf_c++.so.4.2.0
7efd8ca2b000-7efd8ca2c000 r--p 0001b000 08:07 684256                     /usr/lib/x86_64-linux-gnu/libnetcdf_c++.so.4.2.0
7efd8ca2c000-7efd8ca2d000 rw-p 0001c000 08:07 684256                     /usr/lib/x86_64-linux-gnu/libnetcdf_c++.so.4.2.0
7efd8ca2d000-7efd8cb31000 r-xp 00000000 08:07 672668                     /usr/lib/x86_64-linux-gnu/libnetcdf.so.11.0.0
7efd8cb31000-7efd8cd31000 ---p 00104000 08:07 672668                     /usr/lib/x86_64-linux-gnu/libnetcdf.so.11.0.0
7efd8cd31000-7efd8cd7f000 r--p 00104000 08:07 672668                     /usr/lib/x86_64-linux-gnu/libnetcdf.so.11.0.0
7efd8cd7f000-7efd8cd81000 rw-p 00152000 08:07 672668                     /usr/lib/x86_64-linux-gnu/libnetcdf.so.11.0.0
7efd8cd81000-7efd8fd90000 rw-p 00000000 00:00 0 
7efd8fd90000-7efd8fdae000 r-xp 00000000 08:07 659453                     /usr/lib/libvtkDICOMParser.so.5.10.1
7efd8fdae000-7efd8ffad000 ---p 0001e000 08:07 659453                     /usr/lib/libvtkDICOMParser.so.5.10.1
7efd8ffad000-7efd8ffae000 r--p 0001d000 08:07 659453                     /usr/lib/libvtkDICOMParser.so.5.10.1
7efd8ffae000-7efd8ffaf000 rw-p 0001e000 08:07 659453                     /usr/lib/libvtkDICOMParser.so.5.10.1
7efd8ffaf000-7efd902eb000 r-xp 00000000 08:07 672666                     /usr/lib/x86_64-linux-gnu/libmysqlclient.so.20.3.16
7efd902eb000-7efd904ea000 ---p 0033c000 08:07 672666                     /usr/lib/x86_64-linux-gnu/libmysqlclient.so.20.3.16
7efd904ea000-7efd904ee000 r--p 0033b000 08:07 672666                     /usr/lib/x86_64-linux-gnu/libmysqlclient.so.20.3.16
7efd904ee000-7efd90560000 rw-p 0033f000 08:07 672666                     /usr/lib/x86_64-linux-gnu/libmysqlclient.so.20.3.16
7efd90560000-7efd90566000 rw-p 00000000 00:00 0 
7efd90566000-7efd90592000 r-xp 00000000 08:07 672726                     /usr/lib/x86_64-linux-gnu/libpq.so.5.8
7efd90592000-7efd90792000 ---p 0002c000 08:07 672726                     /usr/lib/x86_64-linux-gnu/libpq.so.5.8
7efd90792000-7efd90795000 r--p 0002c000 08:07 672726                     /usr/lib/x86_64-linux-gnu/libpq.so.5.8
7efd90795000-7efd90796000 rw-p 0002f000 08:07 672726                     /usr/lib/x86_64-linux-gnu/libpq.so.5.8
7efd90796000-7efd907c8000 r-xp 00000000 08:07 659463                     /usr/lib/libvtkverdict.so.5.10.1
7efd907c8000-7efd909c7000 ---p 00032000 08:07 659463                     /usr/lib/libvtkverdict.so.5.10.1
7efd909c7000-7efd909c8000 r--p 00031000 08:07 659463                     /usr/lib/libvtkverdict.so.5.10.1
7efd909c8000-7efd909c9000 rw-p 00032000 08:07 659463                     /usr/lib/libvtkverdict.so.5.10.1
7efd909c9000-7efd909cd000 rw-p 00000000 00:00 0 
7efd909cd000-7efd90a71000 r-xp 00000000 08:07 657599                     /usr/lib/x86_64-linux-gnu/libfreetype.so.6.12.1
7efd90a71000-7efd90c70000 ---p 000a4000 08:07 657599                     /usr/lib/x86_64-linux-gnu/libfreetype.so.6.12.1
7efd90c70000-7efd90c76000 r--p 000a3000 08:07 657599                     /usr/lib/x86_64-linux-gnu/libfreetype.so.6.12.1
7efd90c76000-7efd90c77000 rw-p 000a9000 08:07 657599                     /usr/lib/x86_64-linux-gnu/libfreetype.so.6.12.1
7efd90c77000-7efd90dac000 r-xp 00000000 08:07 665928                     /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0
7efd90dac000-7efd90fac000 ---p 00135000 08:07 665928                     /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0
7efd90fac000-7efd90fad000 r--p 00135000 08:07 665928                     /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0
7efd90fad000-7efd90fb1000 rw-p 00136000 08:07 665928                     /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0
7efd90fb1000-7efd91013000 r-xp 00000000 08:07 665971                     /usr/lib/x86_64-linux-gnu/libXt.so.6.0.0
7efd91013000-7efd91213000 ---p 00062000 08:07 665971                     /usr/lib/x86_64-linux-gnu/libXt.so.6.0.0
7efd91213000-7efd91214000 r--p 00062000 08:07 665971                     /usr/lib/x86_64-linux-gnu/libXt.so.6.0.0
7efd91214000-7efd91219000 rw-p 00063000 08:07 665971                     /usr/lib/x86_64-linux-gnu/libXt.so.6.0.0
7efd91219000-7efd9121a000 rw-p 00000000 00:00 0 
7efd9121a000-7efd9122c000 r-xp 00000000 08:07 684120                     /usr/lib/libgl2ps.so.0.0.0
7efd9122c000-7efd9142b000 ---p 00012000 08:07 684120                     /usr/lib/libgl2ps.so.0.0.0
7efd9142b000-7efd9142c000 r--p 00011000 08:07 684120                     /usr/lib/libgl2ps.so.0.0.0
7efd9142c000-7efd9142d000 rw-p 00012000 08:07 684120                     /usr/lib/libgl2ps.so.0.0.0
7efd9142d000-7efd91714000 r-xp 00000000 08:07 665892                     /usr/lib/x86_64-linux-gnu/libQtCore.so.4.8.7
7efd91714000-7efd91914000 ---p 002e7000 08:07 665892                     /usr/lib/x86_64-linux-gnu/libQtCore.so.4.8.7
7efd91914000-7efd9191e000 r--p 002e7000 08:07 665892                     /usr/lib/x86_64-linux-gnu/libQtCore.so.4.8.7
7efd9191e000-7efd9191f000 rw-p 002f1000 08:07 665892                     /usr/lib/x86_64-linux-gnu/libQtCore.so.4.8.7
7efd9191f000-7efd91920000 rw-p 00000000 00:00 0 
7efd91920000-7efd923cc000 r-xp 00000000 08:07 665901                     /usr/lib/x86_64-linux-gnu/libQtGui.so.4.8.7
7efd923cc000-7efd925cb000 ---p 00aac000 08:07 665901                     /usr/lib/x86_64-linux-gnu/libQtGui.so.4.8.7
7efd925cb000-7efd92609000 r--p 00aab000 08:07 665901                     /usr/lib/x86_64-linux-gnu/libQtGui.so.4.8.7
7efd92609000-7efd92610000 rw-p 00ae9000 08:07 665901                     /usr/lib/x86_64-linux-gnu/libQtGui.so.4.8.7
7efd92610000-7efd92614000 rw-p 00000000 00:00 0 
7efd92614000-7efd9261e000 r-xp 00000000 08:07 671313                     /usr/lib/libvtkftgl.so.5.10.1
7efd9261e000-7efd9281d000 ---p 0000a000 08:07 671313                     /usr/lib/libvtkftgl.so.5.10.1
7efd9281d000-7efd9281e000 r--p 00009000 08:07 671313                     /usr/lib/libvtkftgl.so.5.10.1
7efd9281e000-7efd9281f000 rw-p 0000a000 08:07 671313                     /usr/lib/libvtkftgl.so.5.10.1
7efd9281f000-7efd9285d000 r-xp 00000000 08:07 666014                     /usr/lib/libvtksys.so.5.10.1
7efd9285d000-7efd92a5c000 ---p 0003e000 08:07 666014                     /usr/lib/libvtksys.so.5.10.1
7efd92a5c000-7efd92a5d000 r--p 0003d000 08:07 666014                     /usr/lib/libvtksys.so.5.10.1
7efd92a5d000-7efd92a5e000 rw-p 0003e000 08:07 666014                     /usr/lib/libvtksys.so.5.10.1
7efd92a5e000-7efd92ace000 r-xp 00000000 08:07 921324                     /usr/lib/x86_64-linux-gnu/mesa/libGL.so.1.2.0
7efd92ace000-7efd92ccd000 ---p 00070000 08:07 921324                     /usr/lib/x86_64-linux-gnu/mesa/libGL.so.1.2.0
7efd92ccd000-7efd92cd0000 r--p 0006f000 08:07 921324                     /usr/lib/x86_64-linux-gnu/mesa/libGL.so.1.2.0
7efd92cd0000-7efd92cd1000 rw-p 00072000 08:07 921324                     /usr/lib/x86_64-linux-gnu/mesa/libGL.so.1.2.0
7efd92cd1000-7efd92cd2000 rw-p 00000000 00:00 0 
7efd92cd2000-7efd92d19000 r-xp 00000000 08:07 659457                     /usr/lib/libvtkexoIIc.so.5.10.1
7efd92d19000-7efd92f18000 ---p 00047000 08:07 659457                     /usr/lib/libvtkexoIIc.so.5.10.1
7efd92f18000-7efd92f19000 r--p 00046000 08:07 659457                     /usr/lib/libvtkexoIIc.so.5.10.1
7efd92f19000-7efd92f1a000 rw-p 00047000 08:07 659457                     /usr/lib/libvtkexoIIc.so.5.10.1
7efd92f1a000-7efd930fa000 r-xp 00000000 08:07 660057                     /usr/lib/libvtkParallel.so.5.10.1
7efd930fa000-7efd932fa000 ---p 001e0000 08:07 660057                     /usr/lib/libvtkParallel.so.5.10.1
7efd932fa000-7efd9330a000 r--p 001e0000 08:07 660057                     /usr/lib/libvtkParallel.so.5.10.1
7efd9330a000-7efd9330d000 rw-p 001f0000 08:07 660057                     /usr/lib/libvtkParallel.so.5.10.1
7efd9330d000-7efd9330e000 rw-p 00000000 00:00 0 
7efd9330e000-7efd93314000 r-xp 00000000 08:07 682096                     /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0
7efd93314000-7efd93514000 ---p 00006000 08:07 682096                     /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0
7efd93514000-7efd93515000 r--p 00006000 08:07 682096                     /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0
7efd93515000-7efd93516000 rw-p 00007000 08:07 682096                     /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0
7efd93516000-7efd93558000 r-xp 00000000 08:07 665792                     /usr/lib/x86_64-linux-gnu/libHalf.so.12.0.0
7efd93558000-7efd93757000 ---p 00042000 08:07 665792                     /usr/lib/x86_64-linux-gnu/libHalf.so.12.0.0
7efd93757000-7efd93758000 r--p 00041000 08:07 665792                     /usr/lib/x86_64-linux-gnu/libHalf.so.12.0.0
7efd93758000-7efd93759000 rw-p 00042000 08:07 665792                     /usr/lib/x86_64-linux-gnu/libHalf.so.12.0.0
7efd93759000-7efd93924000 r-xp 00000000 08:07 660832                     /usr/lib/x86_64-linux-gnu/libIlmImf-2_2.so.22.0.0
7efd93924000-7efd93b23000 ---p 001cb000 08:07 660832                     /usr/lib/x86_64-linux-gnu/libIlmImf-2_2.so.22.0.0
7efd93b23000-7efd93b26000 r--p 001ca000 08:07 660832                     /usr/lib/x86_64-linux-gnu/libIlmImf-2_2.so.22.0.0
7efd93b26000-7efd93c27000 rw-p 001cd000 08:07 660832                     /usr/lib/x86_64-linux-gnu/libIlmImf-2_2.so.22.0.0
7efd93c27000-7efd93c28000 rw-p 00000000 00:00 0 
7efd93c28000-7efd93c72000 r-xp 00000000 08:07 666677                     /usr/lib/x86_64-linux-gnu/libjasper.so.1.0.0
7efd93c72000-7efd93e71000 ---p 0004a000 08:07 666677                     /usr/lib/x86_64-linux-gnu/libjasper.so.1.0.0
7efd93e71000-7efd93e72000 r--p 00049000 08:07 666677                     /usr/lib/x86_64-linux-gnu/libjasper.so.1.0.0
7efd93e72000-7efd93e76000 rw-p 0004a000 08:07 666677                     /usr/lib/x86_64-linux-gnu/libjasper.so.1.0.0
7efd93e76000-7efd93e7d000 rw-p 00000000 00:00 0 
7efd93e7d000-7efd93eee000 r-xp 00000000 08:07 657570                     /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4
7efd93eee000-7efd940ee000 ---p 00071000 08:07 657570                     /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4
7efd940ee000-7efd940ef000 r--p 00071000 08:07 657570                     /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4
7efd940ef000-7efd940f2000 rw-p 00072000 08:07 657570                     /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4
7efd940f2000-7efd94116000 r-xp 00000000 08:07 1185369                    /lib/x86_64-linux-gnu/libpng12.so.0.54.0
7efd94116000-7efd94315000 ---p 00024000 08:07 1185369                    /lib/x86_64-linux-gnu/libpng12.so.0.54.0
7efd94315000-7efd94316000 r--p 00023000 08:07 1185369                    /lib/x86_64-linux-gnu/libpng12.so.0.54.0
7efd94316000-7efd94317000 rw-p 00024000 08:07 1185369                    /lib/x86_64-linux-gnu/libpng12.so.0.54.0
7efd94317000-7efd94370000 r-xp 00000000 08:07 667256                     /usr/lib/x86_64-linux-gnu/libwebp.so.5.0.4
7efd94370000-7efd94570000 ---p 00059000 08:07 667256                     /usr/lib/x86_64-linux-gnu/libwebp.so.5.0.4
7efd94570000-7efd94571000 r--p 00059000 08:07 667256                     /usr/lib/x86_64-linux-gnu/libwebp.so.5.0.4
7efd94571000-7efd94573000 rw-p 0005a000 08:07 667256                     /usr/lib/x86_64-linux-gnu/libwebp.so.5.0.4
7efd94573000-7efd945ca000 r-xp 00000000 08:07 657582                     /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2
7efd945ca000-7efd947ca000 ---p 00057000 08:07 657582                     /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2
7efd947ca000-7efd947cb000 r--p 00057000 08:07 657582                     /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2
7efd947cb000-7efd947cc000 rw-p 00058000 08:07 657582                     /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2
7efd947cc000-7efd948db000 r-xp 00000000 08:07 1185113                    /lib/x86_64-linux-gnu/libglib-2.0.so.0.4800.2
7efd948db000-7efd94ada000 ---p 0010f000 08:07 1185113                    /lib/x86_64-linux-gnu/libglib-2.0.so.0.4800.2
7efd94ada000-7efd94adb000 r--p 0010e000 08:07 1185113                    /lib/x86_64-linux-gnu/libglib-2.0.so.0.4800.2
7efd94adb000-7efd94adc000 rw-p 0010f000 08:07 1185113                    /lib/x86_64-linux-gnu/libglib-2.0.so.0.4800.2
7efd94adc000-7efd94add000 rw-p 00000000 00:00 0 
7efd94add000-7efd94b2f000 r-xp 00000000 08:07 655643                     /usr/lib/x86_64-linux-gnu/libgobject-2.0.so.0.4800.2
7efd94b2f000-7efd94d2e000 ---p 00052000 08:07 655643                     /usr/lib/x86_64-linux-gnu/libgobject-2.0.so.0.4800.2
7efd94d2e000-7efd94d2f000 r--p 00051000 08:07 655643                     /usr/lib/x86_64-linux-gnu/libgobject-2.0.so.0.4800.2
7efd94d2f000-7efd94d30000 rw-p 00052000 08:07 655643                     /usr/lib/x86_64-linux-gnu/libgobject-2.0.so.0.4800.2
7efd94d30000-7efd94d51000 r-xp 00000000 08:07 657573                     /usr/lib/x86_64-linux-gnu/libgdk_pixbuf-2./scripts/stereoVIOEuroc.bash: line 137: 14665 Aborted                 (core dumped) $BUILD_PATH/stereoVIOEuroc --dataset_type="$DATASET_TYPE" --dataset_path="$DATASET_PATH" --initial_k=50 --final_k=2000 --backend_type="$BACKEND_TYPE" --left_cam_params_path="$PARAMS_PATH/LeftCameraParams.yaml" --right_cam_params_path="$PARAMS_PATH/RightCameraParams.yaml" --imu_params_path="$PARAMS_PATH/ImuParams.yaml" --backend_params_path="$PARAMS_PATH/regularVioParameters.yaml" --frontend_params_path="$PARAMS_PATH/trackerParameters.yaml" --use_lcd="$USE_LCD" --lcd_params_path="$PARAMS_PATH/LCDParameters.yaml" --vocabulary_path="$VOCABULARY_PATH/ORBvoc.yml" --flagfile="$PARAMS_PATH/flags/stereoVIOEuroc.flags" --flagfile="$PARAMS_PATH/flags/Mesher.flags" --flagfile="$PARAMS_PATH/flags/VioBackEnd.flags" --flagfile="$PARAMS_PATH/flags/RegularVioBackEnd.flags" --flagfile="$PARAMS_PATH/flags/Visualizer3D.flags" --parallel_run="$PARALLEL_RUN" --logtostderr=1 --colorlogtostderr=1 --log_prefix=1 --v=0 --vmodule=Pipeline*=00 --log_output="$LOG_OUTPUT" --save_frontend_images=1 --visualize_frontend_images=1 --output_path="$OUTPUT_PATH"

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used
  • GTSAM version used: 4.0
  • OpenGV version used: 1.0
  • OpenCV version used: 3.3.1
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Ubuntu 16.04
  • Did you change the source code? (yes / no): no

Number of distortion_coefficients

I have calibrated my camera with distortion_model : "radial-tangential" using kalibr .I found that the number of distortion_coefficients you used inside calibration is 4 parameters ,However the output number from kalibr is 5 parameters for the same distortion_model .Plz advise

Seek for your help!

I want to know which version should I used. because I have mistake when i build Kimera-VIO.
/usr/local/include/gtsam/base/Vector.h:72:1: error: static assertion failed: Error: GTSAM was built against a different version of Eigen.

Exporting 3D world model

Many downstream robotic applications are not only reliant on the current pose estimate provided, but also world model collected by SLAM pipelines. This is relevant for planning domains such as in navigation stacks, but also exploration mapping techniques as well, e.g. frontier expansion.

Conventionally, exporting a SLAM framework's internal world representation often consists of projections into discretized occupancy models, either 2D maps or 3D or voxel grids, probabilistic or discrete depending upon application requirements or information available from internal world representation. Such projections could be computed online at runtime or offline ex post facto.

A LIDAR based pipelines, such as Cartographer, Slam Toolbox, often provide such online and offline methods.

Subscribe for Online

https://google-cartographer-ros.readthedocs.io/en/latest/assets_writer.html#exploiting-the-map-generated-by-cartographer-ros

Occupancy grid Node

The occupancy_grid_node listens to the submaps published by SLAM, builds an ROS occupancy_grid out of them and publishes it. This tool is useful to keep old nodes that require a single monolithic map to work happy until new nav stacks can deal with Cartographer’s submaps directly.
https://google-cartographer-ros.readthedocs.io/en/latest/ros_api.html#occupancy-grid-node

Published topics

map nav_msgs/OccupancyGrid occupancy grid representation of the pose-graph at map_update_interval frequency

https://github.com/SteveMacenski/slam_toolbox#published-topics

Export for Offline

Pbstream Map Publisher Node

The pbstream_map_publisher is a simple node that creates a static occupancy grid out of a serialized Cartographer state (pbstream format). It is an efficient alternative to the occupancy grid node if live updates are not important.
https://google-cartographer-ros.readthedocs.io/en/latest/ros_api.html#pbstream-map-publisher-node

Exposed Services

Topic Type Description
/slam_toolbox/deserialize_map slam_toolbox/DeserializePoseGraph Load a saved serialized pose-graph files from disk
/slam_toolbox/dynamic_map nav_msgs/OccupancyGrid Request the current state of the pose-graph as an occupancy grid
/slam_toolbox/save_map slam_toolbox/SaveMap Save the map image file of the pose-graph that is useable for display or AMCL localization. It is a simple wrapper on map_server/map_saver but is useful.
/slam_toolbox/serialize_map slam_toolbox/SerializePoseGraph Save the map pose-graph and datathat is useable for continued mapping, slam_toolbox localization, offline manipulation, and more

https://github.com/SteveMacenski/slam_toolbox/blob/eloquent-devel/README.md#exposed-services

That said, we could also see how to adjust navigation2 to deal with Kimera_VIO's world representation directly, but I think support exporting for conventional volumetric occupancy model could benefit for legacy or traditional planning approaches. A related discussion ticket about using mesh models directly for navigation: ros-planning/navigation2#1461

Related:

Support for d435 + T265

Hi, I would ask support for Realsense d435 plus T265 combo. It is due to it is the most powerful solution for VIO,VSLAM from Intel. Te main reason is that this combo apart to improve the performance over a d435i alone, it would release to the computer of a big part of the computing load, allowing the implementation of your software on smaller robots.
I dont know if your software as already a total or partial suport to this combo, maybe via external odometry msg, I couldnt find any mention to that feature.
Thank you

Build Failure without fatal error

Description:
Hello, I am trying to install Kimera-VIO in Mac Mojave. I installed all of lastest dependents. But when I run 'make -j4' for Kimera-VIO, the process terminate without fatal error.

Command:

cd Kimera-VIO
mkdir build
cd build
cmake ..
make -j4

Console output:


[  2%] Built target gtest
[  3%] Building CXX object CMakeFiles/kimera_vio.dir/src/dataprovider/KittiDataProvider.cpp.o
[  4%] Building CXX object CMakeFiles/kimera_vio.dir/src/frontend/StereoImuSyncPacket.cpp.o
[  6%] Building CXX object CMakeFiles/kimera_vio.dir/src/frontend/StereoVisionFrontEnd.cpp.o
[  7%] Building CXX object CMakeFiles/kimera_vio.dir/src/frontend/VisionFrontEndModule.cpp.o
In file included from /usr/local/include/Kimera-VIO/src/frontend/VisionFrontEndModule.cpp:15:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/VisionFrontEndModule.h:17:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd-definitions.h:19:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/Tracker.h:32:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/FeatureSelector.h:33:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEndParams.h:30:
/usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface-definitions.h:74:16: warning: 
      'VIO::VioNavStateTimestamped::equals' hides overloaded virtual function
      [-Woverloaded-virtual]
  virtual bool equals(const VioNavStateTimestamped& rhs) const;
               ^
/usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface-definitions.h:54:16: note: 
      hidden overloaded virtual function 'VIO::VioNavState::equals' declared
      here: type mismatch at 1st parameter ('const VIO::VioNavState &' vs 'const
      VIO::VioNavStateTimestamped &')
  virtual bool equals(const VioNavState& rhs) const;
               ^
In file included from /usr/local/include/Kimera-VIO/src/frontend/VisionFrontEndModule.cpp:15:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/VisionFrontEndModule.h:17:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd-definitions.h:19:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/Tracker.h:32:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/FeatureSelector.h:36:
/usr/local/include/Kimera-VIO/include/kimera-vio/frontend/VioFrontEndParams.h:41:9: warning: 
      field 'featureSelectionHorizon_' will be initialized after field
      'featureSelectionNrCornersToSelect_' [-Wreorder]
        featureSelectionHorizon_(3),  // in seconds
        ^
In file included from /usr/local/include/Kimera-VIO/src/frontend/StereoVisionFrontEnd.cpp:16:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd.h:27:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEnd-definitions.h:29:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd-definitions.h:19:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/Tracker.h:32:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/FeatureSelector.h:33:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEndParams.h:30:
/usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface-definitions.h:74:16: warning: 
      'VIO::VioNavStateTimestamped::equals' hides overloaded virtual function
      [-Woverloaded-virtual]
  virtual bool equals(const VioNavStateTimestamped& rhs) const;
               ^
/usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface-definitions.h:54:16: note: 
      hidden overloaded virtual function 'VIO::VioNavState::equals' declared
      here: type mismatch at 1st parameter ('const VIO::VioNavState &' vs 'const
      VIO::VioNavStateTimestamped &')
  virtual bool equals(const VioNavState& rhs) const;
               ^
In file included from /usr/local/include/Kimera-VIO/src/frontend/StereoVisionFrontEnd.cpp:16:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd.h:27:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEnd-definitions.h:29:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd-definitions.h:19:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/Tracker.h:32:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/FeatureSelector.h:36:
/usr/local/include/Kimera-VIO/include/kimera-vio/frontend/VioFrontEndParams.h:41:9: warning: 
      field 'featureSelectionHorizon_' will be initialized after field
      'featureSelectionNrCornersToSelect_' [-Wreorder]
        featureSelectionHorizon_(3),  // in seconds
        ^
In file included from /usr/local/include/Kimera-VIO/src/dataprovider/KittiDataProvider.cpp:15:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/KittiDataProvider.h:21:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface.h:21:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoImuSyncPacket.h:22:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEnd-definitions.h:29:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd-definitions.h:19:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/Tracker.h:32:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/FeatureSelector.h:33:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEndParams.h:30:
/usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface-definitions.h:74:16: warning: 
      'VIO::VioNavStateTimestamped::equals' hides overloaded virtual function
      [-Woverloaded-virtual]
  virtual bool equals(const VioNavStateTimestamped& rhs) const;
               ^
/usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface-definitions.h:54:16: note: 
      hidden overloaded virtual function 'VIO::VioNavState::equals' declared
      here: type mismatch at 1st parameter ('const VIO::VioNavState &' vs 'const
      VIO::VioNavStateTimestamped &')
  virtual bool equals(const VioNavState& rhs) const;
               ^
In file included from /usr/local/include/Kimera-VIO/src/frontend/StereoImuSyncPacket.cpp:17:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoImuSyncPacket.h:22:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEnd-definitions.h:29:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd-definitions.h:19:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/Tracker.h:32:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/FeatureSelector.h:33:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEndParams.h:30:
/usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface-definitions.h:74:16: warning: 
      'VIO::VioNavStateTimestamped::equals' hides overloaded virtual function
      [-Woverloaded-virtual]
  virtual bool equals(const VioNavStateTimestamped& rhs) const;
               ^
/usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface-definitions.h:54:16: note: 
      hidden overloaded virtual function 'VIO::VioNavState::equals' declared
      here: type mismatch at 1st parameter ('const VIO::VioNavState &' vs 'const
      VIO::VioNavStateTimestamped &')
  virtual bool equals(const VioNavState& rhs) const;
               ^
In file included from /usr/local/include/Kimera-VIO/src/dataprovider/KittiDataProvider.cpp:15:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/KittiDataProvider.h:21:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/dataprovider/DataProviderInterface.h:21:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoImuSyncPacket.h:22:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEnd-definitions.h:29:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd-definitions.h:19:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/Tracker.h:32:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/FeatureSelector.h:36:
/usr/local/include/Kimera-VIO/include/kimera-vio/frontend/VioFrontEndParams.h:41:9: warning: 
      field 'featureSelectionHorizon_' will be initialized after field
      'featureSelectionNrCornersToSelect_' [-Wreorder]
        featureSelectionHorizon_(3),  // in seconds
        ^
In file included from /usr/local/include/Kimera-VIO/src/frontend/StereoImuSyncPacket.cpp:17:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoImuSyncPacket.h:22:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/backend/VioBackEnd-definitions.h:29:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd-definitions.h:19:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/Tracker.h:32:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/FeatureSelector.h:36:
/usr/local/include/Kimera-VIO/include/kimera-vio/frontend/VioFrontEndParams.h:41:9: warning: 
      field 'featureSelectionHorizon_' will be initialized after field
      'featureSelectionNrCornersToSelect_' [-Wreorder]
        featureSelectionHorizon_(3),  // in seconds
        ^
/usr/local/include/Kimera-VIO/src/dataprovider/KittiDataProvider.cpp:45:38: error: 
      use of undeclared identifier 'CV_LOAD_IMAGE_UNCHANGED'
  cv::Mat img = cv::imread(img_name, CV_LOAD_IMAGE_UNCHANGED);
                                     ^
/usr/local/include/Kimera-VIO/src/dataprovider/KittiDataProvider.cpp:62:31: warning: 
      unused variable 'stereo_matching_params' [-Wunused-variable]
  const StereoMatchingParams& stereo_matching_params =
                              ^
/usr/local/include/Kimera-VIO/src/dataprovider/KittiDataProvider.cpp:60:16: warning: 
      unused variable 'number_of_images' [-Wunused-variable]
  const size_t number_of_images = kitti_data_.getNumberOfImages();
               ^
4 warnings and 1 error generated.
make[2]: *** [CMakeFiles/kimera_vio.dir/src/dataprovider/KittiDataProvider.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
In file included from /usr/local/include/Kimera-VIO/src/frontend/VisionFrontEndModule.cpp:15:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/VisionFrontEndModule.h:18:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd.h:36:
/usr/local/include/Kimera-VIO/include/kimera-vio/logging/Logger.h:30:13: warning: 
      unused function 'OpenFile' [-Wunused-function]
static void OpenFile(const std::string& output_filename,
            ^
In file included from /usr/local/include/Kimera-VIO/src/frontend/StereoVisionFrontEnd.cpp:16:
In file included from /usr/local/include/Kimera-VIO/include/kimera-vio/frontend/StereoVisionFrontEnd.h:36:
/usr/local/include/Kimera-VIO/include/kimera-vio/logging/Logger.h:30:13: warning: 
      unused function 'OpenFile' [-Wunused-function]
static void OpenFile(const std::string& output_filename,
            ^
3 warnings generated.
2 warnings generated.
3 warnings generated.
make[1]: *** [CMakeFiles/kimera_vio.dir/all] Error 2
make: *** [all] Error 2

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used
  • GTSAM version used:
  • OpenGV version used:
  • OpenCV version used: type opencv_version
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10):
  • Did you change the source code? (yes / no):

Error when using LoopClosureDetector

Description:
I managed to make Kimera-VIO work without LCD on Euroc Dataset. However I cannot use LCD (see terminal log bellow).
I precise that I am new at using SLAM algorithms and Linux OS, I would be glad if I can have explanations as detailed as possible.

Command:

ubuntu@ubuntu-VirtualBox:~/Kimera-VIO$ ./scripts/stereoVIOEuroc.bash -lcd

Dataset's path is written in the .bash file

Console output:`


ubuntu@ubuntu-VirtualBox:~/Kimera-VIO$ ./scripts/stereoVIOEuroc.bash -lcd
Run VIO with LoopClosureDetector!
Launching:

           ██╗  ██╗██╗███╗   ███╗███████╗██████╗  █████╗
           ██║ ██╔╝██║████╗ ████║██╔════╝██╔══██╗██╔══██╗
           █████╔╝ ██║██╔████╔██║█████╗  ██████╔╝███████║
           ██╔═██╗ ██║██║╚██╔╝██║██╔══╝  ██╔══██╗██╔══██║
           ██║  ██╗██║██║ ╚═╝ ██║███████╗██║  ██║██║  ██║
           ╚═╝  ╚═╝╚═╝╚═╝     ╚═╝╚══════╝╚═╝  ╚═╝╚═╝  ╚═╝


I0424 10:11:30.855521  4462 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0424 10:11:30.858707  4462 PipelineModule.h:422] MISO Pipeline Module: Display has no output queue registered.
I0424 10:11:30.858834  4462 LoopClosureDetector.cpp:98] LoopClosureDetector:: Loading vocabulary from ../vocabulary/ORBvoc.yml
OpenCV Error: Parsing error (../vocabulary/ORBvoc.yml(1303847): Too long string or a last string w/o newline) in icvYMLSkipSpaces, file /home/ubuntu/library/opencv/modules/core/src/persistence.cpp, line 1316
terminate called after throwing an instance of 'cv::Exception'
 what():  /home/ubuntu/library/opencv/modules/core/src/persistence.cpp:1316: error: (-212) ../vocabulary/ORBvoc.yml(1303847): Too long string or a last string w/o newline in function icvYMLSkipSpaces

./scripts/stereoVIOEuroc.bash : ligne 108 :  4462 Abandon                 (core dumped) $BUILD_PATH/stereoVIOEuroc --dataset_type="$DATASET_TYPE" --dataset_path="$DATASET_PATH" --initial_k=50 --final_k=2000 --params_folder_path="$PARAMS_PATH" --use_lcd="$USE_LCD" --vocabulary_path="$VOCABULARY_PATH/ORBvoc.yml" --flagfile="$PARAMS_PATH/flags/stereoVIOEuroc.flags" --flagfile="$PARAMS_PATH/flags/Mesher.flags" --flagfile="$PARAMS_PATH/flags/VioBackEnd.flags" --flagfile="$PARAMS_PATH/flags/RegularVioBackEnd.flags" --flagfile="$PARAMS_PATH/flags/Visualizer3D.flags" --logtostderr=1 --colorlogtostderr=1 --log_prefix=1 --v=0 --vmodule=Pipeline*=00 --log_output="$LOG_OUTPUT" --save_frontend_images=1 --visualize_frontend_images=1 --output_path="$OUTPUT_PATH"

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used
  • GTSAM version used: 4
  • OpenGV version used: 1.0
  • OpenCV version used: 3.3.1
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Ubuntu 18.04 (virtual machine hosted on Windows 10)
  • Did you change the source code? (yes / no): no

Infinite loop when no IMU data between two frames

Description:

As firsted pointed out in MIT-SPARK/Kimera-VIO-ROS2#5 (comment) , it seems the Kimera-VIO is liable to fall into an infinite loop when no IMU data between two frames is received. Such can occur when IMU messages are lost or dropped by the middleware QoS, or when the sample rates from the IMU and Stereo frames happened to alias such that two Stereo frames are timestamped between two consecutively received IMU samples.

Command:

See launch command and context from linked PR:

ros2 launch kimera_vio_ros kimera_ros_realsense.launch.xml 

MIT-SPARK/Kimera-VIO-ROS2#5 (comment)

Console output:

$ ros2 launch kimera_vio_ros kimera_ros_realsense.launch.xml 
[INFO] [launch]: All log files can be found below /home/ruffsl/.ros/log/2020-03-06-11-59-33-116779-cog-rw07-6169
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [kimera_vio_ros-1]: process started with pid [6180]
[kimera_vio_ros-1] I0306 11:59:33.421044  6180 CameraParams.cpp:31] Parsing camera parameters for: left_cam
[kimera_vio_ros-1] I0306 11:59:33.582267  6180 CameraParams.cpp:31] Parsing camera parameters for: right_cam
[kimera_vio_ros-1] I0306 11:59:33.582564  6180 DataProviderInterface.cpp:96] Running dataset between frame 50 and frame 10000
[kimera_vio_ros-1] I0306 11:59:33.589473  6180 RegularVioBackEnd.cpp:113] Using Regular VIO backend.
[kimera_vio_ros-1] I0306 11:59:33.596930  6194 PipelineModule.h:163] Module: Data Provider - Spinning.
[kimera_vio_ros-1] W0306 11:59:33.672981  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673069  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673132  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673167  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673197  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673235  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673280  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673322  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673369  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673408  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936
[kimera_vio_ros-1] W0306 11:59:33.673439  6194 DataProviderModule.cpp:97] No IMU data from last frame timestamp: 1583524773595843072 to timestamp: 1583524773629287936

The infinite looping is encountered most of the time, but something one can get lucky with the race condition and avoid it for a few seconds:

$ ros2 launch kimera_vio_ros kimera_ros_realsense.launch.xml 
[INFO] [launch]: All log files can be found below /home/ruffsl/.ros/log/2020-03-06-11-44-36-116764-cog-rw07-4477
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [kimera_vio_ros-1]: process started with pid [4490]
[kimera_vio_ros-1] I0306 11:44:36.403184  4490 CameraParams.cpp:31] Parsing camera parameters for: left_cam
[kimera_vio_ros-1] I0306 11:44:36.537226  4490 CameraParams.cpp:31] Parsing camera parameters for: right_cam
[kimera_vio_ros-1] I0306 11:44:36.537469  4490 DataProviderInterface.cpp:96] Running dataset between frame 50 and frame 10000
[kimera_vio_ros-1] I0306 11:44:36.542948  4490 RegularVioBackEnd.cpp:113] Using Regular VIO backend.
[kimera_vio_ros-1] I0306 11:44:36.551772  4504 PipelineModule.h:163] Module: Data Provider - Spinning.
[kimera_vio_ros-1] I0306 11:44:36.733357  4504 Pipeline.cpp:780] Frontend launched (parallel_run set to 1).
[kimera_vio_ros-1] I0306 11:44:36.733377  4544 PipelineModule.h:163] Module: VioFrontEnd - Spinning.
[kimera_vio_ros-1] I0306 11:44:36.733757  4504 Pipeline.cpp:511] ------------------- Initialize Pipeline with frame k = 1--------------------
[kimera_vio_ros-1] W0306 11:44:36.733768  4504 InitializationFromImu.cpp:26] InitializationFromImu: assumes that the vehicle is stationary and upright along some axis,and gravity vector is along a single axis!
[kimera_vio_ros-1] I0306 11:44:36.802474  4504 VioBackEnd.cpp:217] Initial state seed: 
[kimera_vio_ros-1]  - Initial pose: 
[kimera_vio_ros-1] |0.999984, -0.0027797, 0.0049191|
[kimera_vio_ros-1] |-0.0027797, 0.515936, 0.856622|
[kimera_vio_ros-1] |-0.0049191, -0.856622, 0.51592|
[kimera_vio_ros-1] 
[kimera_vio_ros-1] [0, 0, 0]';
[kimera_vio_ros-1] 
[kimera_vio_ros-1]  - Initial vel: 0 0 0
[kimera_vio_ros-1]  - Initial IMU bias: acc = [-0.00123735, -0.215474, 0.129774]' gyro = [-0.00703574, -2.63912e-05, 6.80661e-06]'
[kimera_vio_ros-1] I0306 11:44:36.807591  4504 Pipeline.cpp:288] Before launching threads.
[kimera_vio_ros-1] I0306 11:44:36.807698  4504 Pipeline.cpp:809] Backend, mesher and visualizer launched (parallel_run set to 1).
[kimera_vio_ros-1] I0306 11:44:36.807705  4504 Pipeline.cpp:290]  launching threads.
[kimera_vio_ros-1] I0306 11:44:36.807698  4564 PipelineModule.h:163] Module: VioBackEnd - Spinning.
[kimera_vio_ros-1] I0306 11:44:36.807870  4565 PipelineModule.h:163] Module: MesherModule - Spinning.
[kimera_vio_ros-1] I0306 11:44:36.814316  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 2--------------------
[kimera_vio_ros-1] W0306 11:44:36.824456  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 100 Hz. (10 ms).
[kimera_vio_ros-1] I0306 11:44:36.824506  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 3--------------------
[kimera_vio_ros-1] W0306 11:44:36.831315  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 166.667 Hz. (6 ms).
[kimera_vio_ros-1] I0306 11:44:36.831351  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 4--------------------
[kimera_vio_ros-1] W0306 11:44:36.835386  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 250 Hz. (4 ms).
[kimera_vio_ros-1] I0306 11:44:36.960853  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 5--------------------
[kimera_vio_ros-1] I0306 11:44:37.008589  4544 StereoVisionFrontEnd.cpp:124] Keyframe 5 with: 443 smart measurements
[kimera_vio_ros-1] W0306 11:44:37.008661  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 21.2766 Hz. (47 ms).
[kimera_vio_ros-1] I0306 11:44:37.008683  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 6--------------------
[kimera_vio_ros-1] I0306 11:44:37.008906  4564 RegularVioBackEnd.cpp:211] Tracker has a LOW_DISPARITY status.
[kimera_vio_ros-1] W0306 11:44:37.010509  4565 Mesher.cpp:1283] Missing landmark information to build 3D Mesh.
[kimera_vio_ros-1] W0306 11:44:37.010524  4564 PipelineModule.h:186] Module: VioBackEnd - frequency: 1000 Hz. (1 ms).
[kimera_vio_ros-1] W0306 11:44:37.013517  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 250 Hz. (4 ms).
[kimera_vio_ros-1] W0306 11:44:37.014544  4565 PipelineModule.h:186] Module: MesherModule - frequency: 250 Hz. (4 ms).
[kimera_vio_ros-1] I0306 11:44:37.026594  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 7--------------------
[kimera_vio_ros-1] W0306 11:44:37.033161  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 166.667 Hz. (6 ms).
[kimera_vio_ros-1] I0306 11:44:37.061677  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 8--------------------
[kimera_vio_ros-1] W0306 11:44:37.068816  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 142.857 Hz. (7 ms).
[kimera_vio_ros-1] I0306 11:44:37.126309  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 9--------------------
[kimera_vio_ros-1] W0306 11:44:37.130944  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 250 Hz. (4 ms).
[kimera_vio_ros-1] I0306 11:44:37.156752  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 10--------------------
[kimera_vio_ros-1] W0306 11:44:37.161860  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.191395  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 11--------------------
[kimera_vio_ros-1] I0306 11:44:37.227880  4544 StereoVisionFrontEnd.cpp:124] Keyframe 11 with: 507 smart measurements
[kimera_vio_ros-1] W0306 11:44:37.227944  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 27.7778 Hz. (36 ms).
[kimera_vio_ros-1] I0306 11:44:37.227962  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 12--------------------
[kimera_vio_ros-1] I0306 11:44:37.228159  4564 RegularVioBackEnd.cpp:211] Tracker has a LOW_DISPARITY status.
[kimera_vio_ros-1] W0306 11:44:37.230064  4565 Mesher.cpp:1283] Missing landmark information to build 3D Mesh.
[kimera_vio_ros-1] W0306 11:44:37.230144  4564 PipelineModule.h:186] Module: VioBackEnd - frequency: 500 Hz. (2 ms).
[kimera_vio_ros-1] W0306 11:44:37.232029  4565 PipelineModule.h:186] Module: MesherModule - frequency: 1000 Hz. (1 ms).
[kimera_vio_ros-1] W0306 11:44:37.232172  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 250 Hz. (4 ms).
[kimera_vio_ros-1] I0306 11:44:37.256656  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 13--------------------
[kimera_vio_ros-1] W0306 11:44:37.262290  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.292416  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 14--------------------
[kimera_vio_ros-1] W0306 11:44:37.297888  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.327052  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 15--------------------
[kimera_vio_ros-1] W0306 11:44:37.332326  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.361037  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 16--------------------
[kimera_vio_ros-1] W0306 11:44:37.366055  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.395197  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 17--------------------
[kimera_vio_ros-1] W0306 11:44:37.402889  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 142.857 Hz. (7 ms).
[kimera_vio_ros-1] I0306 11:44:37.463069  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 18--------------------
[kimera_vio_ros-1] I0306 11:44:37.509714  4544 StereoVisionFrontEnd.cpp:124] Keyframe 18 with: 467 smart measurements
[kimera_vio_ros-1] W0306 11:44:37.509785  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 21.7391 Hz. (46 ms).
[kimera_vio_ros-1] I0306 11:44:37.510071  4564 RegularVioBackEnd.cpp:211] Tracker has a LOW_DISPARITY status.
[kimera_vio_ros-1] W0306 11:44:37.512203  4565 Mesher.cpp:1283] Missing landmark information to build 3D Mesh.
[kimera_vio_ros-1] W0306 11:44:37.512255  4564 PipelineModule.h:186] Module: VioBackEnd - frequency: 500 Hz. (2 ms).
[kimera_vio_ros-1] W0306 11:44:37.515733  4565 PipelineModule.h:186] Module: MesherModule - frequency: 333.333 Hz. (3 ms).
[kimera_vio_ros-1] I0306 11:44:37.526648  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 19--------------------
[kimera_vio_ros-1] W0306 11:44:37.531821  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.560017  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 20--------------------
[kimera_vio_ros-1] W0306 11:44:37.565753  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.592141  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 21--------------------
[kimera_vio_ros-1] W0306 11:44:37.597502  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.628166  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 22--------------------
[kimera_vio_ros-1] W0306 11:44:37.634687  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 166.667 Hz. (6 ms).
[kimera_vio_ros-1] I0306 11:44:37.656633  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 23--------------------
[kimera_vio_ros-1] W0306 11:44:37.661800  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 200 Hz. (5 ms).
[kimera_vio_ros-1] I0306 11:44:37.689841  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 24--------------------
[kimera_vio_ros-1] I0306 11:44:37.730131  4544 StereoVisionFrontEnd.cpp:124] Keyframe 24 with: 461 smart measurements
[kimera_vio_ros-1] W0306 11:44:37.730195  4544 PipelineModule.h:186] Module: VioFrontEnd - frequency: 25 Hz. (40 ms).
[kimera_vio_ros-1] I0306 11:44:37.730213  4544 StereoVisionFrontEnd.cpp:62] ------------------- Processing frame k = 25--------------------

Additional files:

For reference, I'm using an updated realsense package for ROS2:
https://github.com/ruffsl/ros2_intel_realsense/tree/devel
(The repo's devel branch includes a Dockerfile for how to build)
And the Kimera-VIO-ROS2 branch for the current work in progress PR:
MIT-SPARK/Kimera-VIO-ROS2#5

  • OS: Ubuntu 18.04
  • Kimera-VIO: bceed72
  • Downstream Libraries: See .repo files in respective fork/repo
  • Source code changed: yes
  • Just trivial build system fixes
  • master...ruffsl:patch-3

Nominal baseline parameter is redundant

Description:

The nominalBaseline parameter in the trackerParameters.yml files is redundant since we already have the extrinsics in the camera parameter yaml files.

Dataset to test loopclosures

I've been experimenting with Kimera and while the state estimation works great I was wondering how I could best test the loop closure detection and PGO. As when I run Kimera (I use the ROS Wrapper) with the euroc dataset and verbosity set to print out loop closures it doesn't seem to find any. Is there any dataset available to test this better or a publicly recommended dataset that I could use?

Due to the current lockdown situation I'm in testing with real sensors is not possible for a while :)

No loop closure detected

I have looked at all issues but I could not find a related one. When I run with loop closure detection enabled, it does not detect any loops. I uploaded the output_lcd_status.csv file. I do not know if I am doing something wrong. Can you please help me?

Command: bash ./scripts/stereoVIOEuroc.bash -p ~/EuRoC/V1_01_easy/ -lcd -log

output_lcd_status.csv.zip

Tracking features in valid pixels only after rectification

Description:
Currently, Kimera-VIO detects features in all pixels of the image after rectification. However, for stereo cameras with non-standard configurations, the valid pixels after rectification will only occupy a limited region of the entire frame.

Potential Solution:
Obtain the valid ROI output from the stereoRectify function of OpenCV: https://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html#stereorectify.
However, for fisheye cameras, we might need to do something different since the stereoRectify function does not return ROI: https://docs.opencv.org/3.4/db/d58/group__calib3d__fisheye.html#gac1af58774006689056b0f2ef1db55ecc

Scale Drift optimization

I have tested the estimated trajectory compared to the ground-truth data using
[https://github.com/uzh-rpg/rpg_trajectory_evaluation] analysis tool before and after the modification of the code and I have noticed that the scale drift err has increased as described in the attached files
kimera_estimated_trajs
scale_drift

make error

Thank you for your good work and I am very interested in it. I download your code and install it, but an error encountered.

CMake Error at /usr/local/share/cmake-3.14/Modules/GoogleTestAddTests.cmake:40 (message):
Error running test executable.

Path: '/home/SENSETIME/chenchang1/test/Kimera-VIO/build/testSparkVio'
Result: Segmentation fault
Output:

CMakeFiles/testSparkVio.dir/build.make:524: recipe for target 'testSparkVio' failed
make[2]: *** [testSparkVio] Error 1
make[2]: *** Deleting file 'testSparkVio'
CMakeFiles/Makefile2:267: recipe for target 'CMakeFiles/testSparkVio.dir/all' failed
make[1]: *** [CMakeFiles/testSparkVio.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2

I tried cmake3.10 and cmake3.14, but this error is still on. Could you help me solve it? Sincerely.

Steep feature dropoff every maxFeatureAge

Description:
I was examining the Jupyter notebooks in Kimera-Evaluation when I noticed something strange. The feature count hovers around 300, then has periodic dips to as low as 100 features. After doing a little sleuthing, I discovered that these dips happen every maxFeatureAge number of keyframes, regardless of other factors. I suspect that when you initialize many features at once (like on startup or after a period of motion blur), they all expire at once and must be replaced. I suspect that the only features still being tracked at that point are ones generated from motion-- old features falling out of frame and being replaced by new ones.

Command:

roslaunch kimera_vio_ros <offline launch file>
jupyter notebook

Additional files:
Here are the feature graphs for a maxFeatureAge of 25, varying the intra_keyframe_time. Note that the periodic spikes always coincide with a multiple of 25 keyframes.
intra_keyframe_time = 0.2
TrackerSpikes02Keyframe
intra_keyframe_time = 0.12
TrackerSpikes012Keyframe
intra_keyframe_time = 0.1
SpikesWith01Keyframe
intra_keyframe_time = 0.05
TrackerSpikes005Keyframe

Console output:
I also ran the same inputs, but online. Here's a sample of the timing output. Note the huge disparity between max and average time-- I suspect this is because every maxFeatureAge of keyframes, a large number of features die off and must be recomputed.

-----------                        #	Hz	(avg     +- std    )	[min,max]
Data Provider [ms]            	      0	
IMU Preintegration Timing [us]	    661	29.0218	(70.9395 +- 31.0521)	[25,400]
Mesher [ms]                   	     56	2.48127	(0 +- 0)	[0,0]
VioBackEnd [ms]               	     56	2.48136	(48.125 +- 32.0806)	[1,154]
VioFrontEnd [ms]              	    660	28.8361	(27.3697 +- 29.9491)	[5,163]

Please give also the following information:

  • SparkVio branch, tag or commit used: master
  • SparkVioRos branch, tag or commit used: sequential rosbag
  • GTSAM version used:
  • OpenGV version used:
  • OpenCV version used:
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Ubuntu 18.04
  • Did you change the source code? (yes / no): yes, extra launchfile and for online changed publishing rate

Kimera's coordinate frame

What coordinate frame does Kimera use? Traditionally, ROS uses a standard X-Forward, Y-Left and Z-Up or NWU system of reference for robot body frames and X-Right, Y-Down and Z-Forward system of reference for camera frames.

It seems Kimera splits the difference with X-Right, Y-Forward, Z-Up.

compile error about DBoW2, KimeraRPGO.

Description:
I encontered two errors. The first one is at cmake stage, the second one is at make stage.

Command 1:

# in directory Kimera-VIO/build, I ran command:
cmake ..

Console output 1:


CMake Warning at CMakeLists.txt:29 (find_package):
  By not providing "FindDBoW2.cmake" in CMAKE_MODULE_PATH this project has
  asked CMake to find a package configuration file provided by "DBoW2", but
  CMake did not find one.

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

    DBoW2Config.cmake
    dbow2-config.cmake

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


CMake Warning at CMakeLists.txt:35 (find_package):
  By not providing "FindKimeraRPGO.cmake" in CMAKE_MODULE_PATH this project
  has asked CMake to find a package configuration file provided by
  "KimeraRPGO", but CMake did not find one.

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

    KimeraRPGOConfig.cmake
    kimerarpgo-config.cmake

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

Command 2:

# in directory Kimera-VIO/build, I ran command:
make -j2

Console output 2:

[ 49%] Building CXX object CMakeFiles/KimeraVIO.dir/src/utils/ThreadsafeImuBuffer.cpp.o
[ 50%] Building CXX object CMakeFiles/KimeraVIO.dir/src/utils/Statistics.cpp.o
[ 51%] Building CXX object CMakeFiles/KimeraVIO.dir/src/pipeline/Pipeline.cpp.o
In file included from /home/xs/Desktop/opensource/Kimera-VIO/include/kimera-vio/pipeline/Pipeline.h:30:0,
                 from /home/xs/Desktop/opensource/Kimera-VIO/src/pipeline/Pipeline.cpp:15:
/home/xs/Desktop/opensource/Kimera-VIO/include/kimera-vio/loopclosure/LoopClosureDetector.h:27:25: fatal error: DBoW2/DBoW2.h: No such file or directory
compilation terminated.
CMakeFiles/KimeraVIO.dir/build.make:662: recipe for target 'CMakeFiles/KimeraVIO.dir/src/pipeline/Pipeline.cpp.o' failed
make[2]: *** [CMakeFiles/KimeraVIO.dir/src/pipeline/Pipeline.cpp.o] Error 1
CMakeFiles/Makefile2:597: recipe for target 'CMakeFiles/KimeraVIO.dir/all' failed
make[1]: *** [CMakeFiles/KimeraVIO.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2

Additional files:
Please attach all the files needed to reproduce the error.

Please give also the following information:

  • SparkVio branch, tag or commit used: branch master SHA: 80e2605
  • GTSAM version used: master
  • OpenGV version used: master SHA: 306a54e6c6b94e2048f820cdf77ef5281d4b48ad
  • OpenCV version used: type 3.3.1
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): Ubuntu 16.04
  • Did you change the source code? (yes / no): no

TBB Warnings and Compilation Error

Description:
First off, I'd like to thank you guys for creating an amazing piece of software in the VIO realm, truly amazing work and I hope it gets used more. I maintain the ArchLinux package here for this codebase, and recently the build started failing. This is due to a compilation error with one of the tests files: testMesher.cpp. Also with an updated version of TBB, tbb/mutex.h has been deprecated. If this can be fixed as well, it would be nice to stop seeing such a cluttered build output. Having the build be fixed so ArchLinux users can start using this project again would be great.

Command:

make

Console output:


[ 80%] Building CXX object CMakeFiles/testKimeraVIO.dir/tests/testParallelPlaneRegularTangentSpaceFactor.cpp.o
In file included from /usr/include/gtsam/geometry/Unit3.h:36,
                 from /usr/include/gtsam/geometry/Rot3.h:25,
                 from /usr/include/gtsam/geometry/OrientedPlane3.h:23,
                 from /home/acxz/.cache/yay/kimera-vio/src/Kimera-VIO-5.0/tests/testParallelPlaneRegularBasicFactor.cpp:25:
/usr/include/tbb/mutex.h:21:140: note: #pragma message: TBB Warning: tbb/mutex.h is deprecated. For details, please see Deprecated Features appendix in the TBB reference manual.
   21 | #pragma message("TBB Warning: tbb/mutex.h is deprecated. For details, please see Deprecated Features appendix in the TBB reference manual.")
      |                                                                                                                                            ^
In file included from /usr/include/gtsam/base/types.h:31,
                 from /usr/include/gtsam/inference/Key.h:25,
                 from /usr/include/gtsam/linear/Scatter.h:22,
                 from /usr/include/gtsam/linear/VectorValues.h:20,
                 from /usr/include/gtsam/base/numericalDerivative.h:31,
                 from /home/acxz/.cache/yay/kimera-vio/src/Kimera-VIO-5.0/tests/testParallelPlaneRegularTangentSpaceFactor.cpp:21:
/usr/include/tbb/task_scheduler_init.h:21:154: note: #pragma message: TBB Warning: tbb/task_scheduler_init.h is deprecated. For details, please see Deprecated Features appendix in the TBB reference manual.
   21 | #pragma message("TBB Warning: tbb/task_scheduler_init.h is deprecated. For details, please see Deprecated Features appendix in the TBB reference manual.")
      |                                                                                                                                                          ^
/home/acxz/.cache/yay/kimera-vio/src/Kimera-VIO-5.0/tests/testMesher.cpp:25:15: error: expected constructor, destructor, or type conversion before ‘(’ token
   25 | DECLARE_string(test_data_path);
      |               ^
/home/acxz/.cache/yay/kimera-vio/src/Kimera-VIO-5.0/tests/testMesher.cpp: In constructor ‘VIO::MesherFixture::MesherFixture()’:
/home/acxz/.cache/yay/kimera-vio/src/Kimera-VIO-5.0/tests/testMesher.cpp:38:29: error: ‘FLAGS_test_data_path’ was not declared in this scope
   38 |     img_name_ = std::string(FLAGS_test_data_path) + "/chessboard_small.png";
      |                             ^~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/gtsam/geometry/Unit3.h:36,
                 from /usr/include/gtsam/geometry/Rot3.h:25,
                 from /usr/include/gtsam/geometry/OrientedPlane3.h:23,
                 from /home/acxz/.cache/yay/kimera-vio/src/Kimera-VIO-5.0/tests/testParallelPlaneRegularTangentSpaceFactor.cpp:25:
/usr/include/tbb/mutex.h:21:140: note: #pragma message: TBB Warning: tbb/mutex.h is deprecated. For details, please see Deprecated Features appendix in the TBB reference manual.
   21 | #pragma message("TBB Warning: tbb/mutex.h is deprecated. For details, please see Deprecated Features appendix in the TBB reference manual.")
      |                       

Additional files:
None needed.

Please give also the following information:

  • SparkVio branch, tag or commit used: 5.0
  • GTSAM version used: 4.0.2
  • OpenGV version used: Master branch, following commit at time of testing
  • OpenCV version used: 4.2.0
  • Operating system and version (e.g. Ubuntu 16.04 or Windows 10): ArchLinux
  • Did you change the source code? (yes / no): no

Support for non-identity T_BS IMU extrinsics

In robotics, sensors are often calibrated with respect to a base_link reference frame, relative to chassis of the robot platform. These extrinsics are often practically captured via a TF tree:

http://wiki.ros.org/tf2

For single sensor devices, such as like a free handed visual inertial camera, assuming the IMU sensor to be this base frame for the entire robot platform can be a reasonable choice. However, for larger platforms where the sensors are mounted onto robotic extremities, such as pan tilting heads, or kinematic arms, such assumptions in using the IMU as the base_link reference frame are no longer practical. I'd like to suggest supporting non-identity IMU extrinsics to better leverage the use of TF trees to initialize and/or update sensor extrinsics for tracking generalizable base_link reference frame.

This could allow ROS wrappers set the imu and stereo frame extrinsics using the most recent TF as published by calibrated URDFs, or sensor drivers that are most aware of the sensor hardware.

It looks like the ImuParams for the IMU front end checks to ensure the IMU is chosen as the body frame

std::vector<double> vector_pose;
yaml_parser.getNestedYamlParam("T_BS", "data", &vector_pose);
const gtsam::Pose3& body_Pose_cam =
UtilsOpenCV::poseVectorToGtsamPose3(vector_pose);
// Sanity check: IMU is usually chosen as the body frame.
LOG_IF(FATAL, !body_Pose_cam.equals(gtsam::Pose3()))
<< "parseImuData: we expected identity body_Pose_cam_: is everything ok?";

From the snippet above, it also looks like the Pose3 body_Pose_cam variable parsed from the IMU config remains un-used in the rest of the pipeline.

Loop closure detector related segmentation fault

Description:

When I running "stereoVIOEuroc.bash", everything is OK. After a while, a segmentation fault occured when vio-system processing the frame in sequence "Euroc/V1_01_easy" and "Euroc/V2_01_easy". (Other sequences have not been tested)

I thought it's related the Euroc-datasets I used, but the problem remains after I used your version of Euroc-datasets. Then I checked the information in the core file and found that this problem is related to the thread of loop closure detector (See "Key messages in core file" for details).

Well, I have changed the parameter --use_lcd and --parallel_run (i.e., parameter USE_LCD and PARALLEL_RUN in "stereoVIOEuroc.bash") and some things looks different:

--use_lcd --parallel_run vio-system result
0 0 Normal termination.
0 1 Segmentation fault.
1 0 Normal Termination but errors received during running.*
1 1 Normal Termination but errors received during running.*

* Error message: "LoopClosureDetector: No output callback registered. Either register a callback or disable LCD with flag use_lcd=false."

I have no idea about it. It will take me a long time to read and analyse source codes ... Could you please help me to solve this problem? I would appreciate it. O(≧▽≦)O

Command:

${MY_CODE_DIR}/Kimera/comments/Kimera-VIO/scripts$ ./stereoVIOEuroc.bash

Parameters in stereoVIOEuroc.bash:

DATASET_PATH="${My_Datasets_DIR}/Kimera_EuRoc/V1_01_easy"

# Specify: 1 to use Regular VIO, 0 to use Normal VIO with default parameters.
USE_REGULAR_VIO=0

# Specify: 0 to run on EuRoC data, 1 to run on Kitti
DATASET_TYPE=0

# Specify: 1 to run pipeline in parallel mode, 0 to run sequentially.
PARALLEL_RUN=1

# Specify: 1 to enable the LoopClosureDetector, 0 to not.
USE_LCD=0

# Specify: 1 to enable logging of output files, 0 to not.
LOG_OUTPUT=1

Console output:

...
------------------- Processing frame k = 1999--------------------
VIO: adding keyframe 487 at timestamp:1.40372e+09 (nsec).
Current IMU Preintegration frequency: 192308 Hz. (52 us).
VIO: adding between 
[0.0542361722, 0.102485067, 0.0950404991]';R:
[
            0.999910075    -0.013402216 -0.000472217364;
           0.0133991652     0.999892464  -0.00596017296;
         0.000552046109   0.00595330967     0.999982127
  ]
Current Stereo FrontEnd frequency: 166.667 Hz. (6 ms).
Current Visualizer frequency: 27.027 Hz. (37 ms).
Hessian stats: ===========
rows: 390
nrElementsInMatrix_: 152100
nrZeroElementsInMatrix_: 120294
Backend: Update IMU Bias.
Current Backend frequency: 15.3846 Hz. (65 ms).
createMesh2D - error, keypoint out of image frame.
createMesh2D - error, keypoint out of image frame.
createMesh2D - error, keypoint out of image frame.
Current Mesher frequency: 90.9091 Hz. (11 ms).
Current Visualizer frequency: 35.7143 Hz. (28 ms).
./stereoVIOEuroc.bash: line 123: 23505 Segmentation fault      (core dumped) ../build/stereoVIOEuroc --flagfile="../params/flags/stereoVIOEuroc.flags" --flagfile="../params/flags/Mesher.flags" --flagfile="../params/flags/VioBackEnd.flags" --flagfile="../params/flags/RegularVioBackEnd.flags" --flagfile="../params/flags/Visualizer3D.flags" --flagfile="../params/flags/EthParser.flags" --logtostderr=1 --colorlogtostderr=1 --log_prefix=0 --dataset_path="$DATASET_PATH" --vio_params_path="$VIO_PARAMS_PATH" --initial_k=50 --final_k=2000 --tracker_params_path="$TRACKER_PARAMS_PATH" --lcd_params_path="$LCD_PARAMS_PATH" --vocabulary_path="../vocabulary/ORBvoc.yml" --use_lcd="$USE_LCD" --v=0 --vmodule=VioBackEnd=0,RegularVioBackEnd=0,Mesher=0,StereoVisionFrontEnd=0 --backend_type="$BACKEND_TYPE" --parallel_run="$PARALLEL_RUN" --dataset_type="$DATASET_TYPE" --log_output="$LOG_OUTPUT" --output_path="../output_logs/"

Key messages in core file:

...
[New LWP 22455]
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
Core was generated by `../build/stereoVIOEuroc --flagfile=../params/flags/stereoVIOEuroc.flags --flagf'.
Program terminated with signal SIGSEGV, Segmentation fault.
#0  0x00007f044e642b75 in std::__atomic_base<bool>::load (__m=std::memory_order_seq_cst, this=<optimized out>) at /usr/include/c++/7/bits/atomic_base.h:396
396             return __atomic_load_n(&_M_i, __m);
[Current thread is 1 (Thread 0x7f03ebfff700 (LWP 22447))]
(gdb) up
#1  std::atomic<bool>::operator bool (this=<optimized out>) at /usr/include/c++/7/atomic:86
86          { return _M_base.load(); }
(gdb) up
#2  VIO::LoopClosureDetector::isWorking (this=<optimized out>) at /home/guoqing/SLAM/Kimera/comments/Kimera-VIO/include/kimera-vio/loopclosure/LoopClosureDetector.h:153
153       inline bool isWorking() const { return is_thread_working_; }
(gdb) up
#3  VIO::Pipeline::shutdownWhenFinished (this=0x7fffc13b36e0) at /home/guoqing/SLAM/Kimera/comments/Kimera-VIO/src/pipeline/Pipeline.cpp:561
561                 !loop_closure_detector_->isWorking() &&
(gdb) 

Additional messages

I have one test failed during make test:

...
99% tests passed, 1 tests failed out of 165

Total Test time (real) = 110.28 sec

The following tests did not run:
          4 - testCameraParams.parseKITTICalib (Disabled)
          9 - FeatureSelector.createOmegaBarImu (Disabled)
         10 - FeatureSelector.GetVersorIfInFOV (Disabled)
         32 - testFrame.CalibratePixel (Disabled)
         33 - testFrame.CalibratePixel (Disabled)
         94 - StereoFrameFixture.undistortFisheyeStereoFrame (Disabled)
        150 - UtilsOpenCVFixture.ExtractCornersChessboard (Disabled)
        163 - UtilsOpenCVFixture.ExtractCornersChessboard (Disabled)
        173 - OnlineAlignmentFixture.GyroscopeBiasEstimation (Disabled)
        174 - OnlineAlignmentFixture.GyroscopeBiasEstimationAHRS (Disabled)
        176 - OnlineAlignmentFixture.OnlineGravityAlignment (Disabled)
        177 - OnlineAlignmentFixture.GravityAlignmentRealData (Disabled)

The following tests FAILED:
        162 - UtilsOpenCVFixture.ReadAndConvertToGrayScale (Failed)
Errors while running CTest
Makefile:129: recipe for target 'test' failed
make: *** [test] Error 8

Furthermore, the Triangular mesh displayed by 3-D Visualizer colored pure white, which is different to your demo GIFs:

Peek 2019-10-23 10-38

Is this OK? I don't know if it's related to the above "segmentation fault" problem.

Additional files:
These log files were generated before segmentation fault happened, with USE_LCD = 0 and PARALLEL_RUN = 1.

output_logs.zip

Environment

  • SparkVio branch master, commit be9fce3
  • GTSAM version used: 4.0.2
  • OpenGV version used: 1.0
  • OpenCV version used: 3.3.1
  • Operating system and version : Ubuntu 16.04, Kernel 4.12.9-041209
  • gcc/g++ version used: 7.4.0
  • Did you change the source code? (yes / no): No

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.