Git Product home page Git Product logo

rgbdslam_v2's Introduction

RGBDSLAMv2

... is a state-of-the-art SLAM system for RGB-D cameras, e.g., the Microsoft Kinect or the Asus Xtion Pro Live. You can use it to create 3D point clouds or OctoMaps.

RGBDSLAMv2 is based on the open source projects, ROS, OpenCV, OpenGL, PCL, OctoMap, SiftGPU, g2o, and more - Thanks!

A journal article with a system description and performance evaluation can be found in the following publication:

"3D Mapping with an RGB-D Camera",
F. Endres, J. Hess, J. Sturm, D. Cremers, W. Burgard,
IEEE Transactions on Robotics, 2014.

Even more information can be found in my PhD thesis

Additional information can be found here:

RGBDSLAM on the RGB-D Benchmark Dataset

Prerequisites

  • Ubuntu 16.04
  • ROS kinetic
  • Amd64 processor (there are known problems with ARM, mostly related to qt and opengl) Other versions may work, but are not tested. Please report success if you use other versions.

Installation

This is a canonical way, feel free to adapt if you known what you are doing.

  1. Put RGBDSLAMv2 in a catkin workspace: See the catkin tutorial for details. Use git to clone this repository into your workspace's "src/" directory. Or download RGBDSLAMv2 as an archive and extract it to "src/".

  2. Download my [g2o fork|https://github.com/felixendres/g2o], put it in some other directory. Build and install. Export the environment variable $G2O_DIR to the installation directory to let rgbdslam_v2 know where to find it (see Installation from Scratch for an example).

  3. Use rosdep (i.e. "rosdep install rgbdslam") to install missing dependencies. For details see http://wiki.ros.org/ROS/Tutorials/rosdep

  4. To build RGBDSLAMv2 go to your catkin workspace and execute "catkin_make". If you get an error about the missing siftgpu library, execute "catkin_make" again.

Installation from Scratch

There is now an install.sh script, which can be executed (bash install.sh). It installs everything required below ~/Code (you can change the location in the script).

The script is short and not complicated, so you can also use it as a manual.

If you want to use the install script, it is sufficient to download it directly. There is no need to clone this repository then, as the script will do that for you.

If you have a multi-core machine with 4GB RAM or more, you can speed up the compilation by increasing the two occurences of "-j2" to, e.g., "-j4".

Installation done! What's next?

See the sections below for more details on the usage. But to get you started quickly here's the most important pointers:

  • If you want to use RGBDSLAMv2 with an RGB-D camera you may have to install openni (sudo apt-get install ros-kinetic-openni-launch) or something similar

  • Check out the launch files in "launch/" for examples and specific use cases. roslaunch rgbdslam openni+rgbdslam.launch is a good starting point for live mapping.

  • You probably need to adapt the parameters for the input topics depending on your camera driver node.

  • Check out the README in "test/" for running, testing and evaluating RGBDSLAMv2 on Juergen Sturm's RGB-D SLAM Dataset and Benchmark: http://vision.in.tum.de/data/datasets/rgbd-dataset You need cython for the evaluation scripts (sudo apt-get install cython).

  • If you want to use SURF or SIFT, you will need to build OpenCV from source, including the non-free module (this does not include SIFTGPU, which is included, but needs to be enabled in CMakeLists.txt). In the CMakeLists.txt of RGBDSLAMv2 you can set the build directory of OpenCV and enable the non-free functionality. Note that SIFT and SURF are not the best choice. Due to new (software) features in RGBDSLAMv2, ORB outperforms both.

RGBDSLAM right after startup

IMPORTANT NOTE

This software is an update of the ROS Fuerte version of RGBDSLAM. However many things have changed, so some of the DOCUMENTATION BELOW MAY BE OUTDATED. Please report problems with the documentation. Thanks.

Configuration

There are several example launch-files that set the parameters of RGB-D SLAM for certain use cases. For a definitive list of all settings and their default settings have a look at their quite readable definition in src/parameter_server.cpp or (with the current settings instead of the default) in the GUI Menu Settings->View Current Settings.

The various use-case launch-files might not work correctly yet, as they are not regularly tested. You should get them running if you fiddle with the topics ("rostopic list" and "rosnode info" will help you. "rqt_graph" is great too).

Usage

Most people seem to want the registered point cloud. It is by default sent out on /rgbdslam/batch_clouds when you command RGB-D SLAM to do so (see below). The clouds sent are actually the same as before, but the according transformation - by default from /map to /openni_camera - is sent out on /tf.

The octoMap library is compiled into the rgbdslam node. This allows to create the octomap directly. In the GUI this can be done by selecting "Save Octomap" from the "Data" Menu. Online octomapping is possible, but not recommended.

OctoMap created from the RGB-D Benchmark sequence fr2/desk

Usage with GUI

To start RGBDSLAMv2 launch, e.g., $ roslaunch rgbdslam openni+rgbdslam.launch

Alternatively you can start the openni nodes and RGBDSLAMv2 separately, e.g.: roslaunch openni_camera openni_node.launch roslaunch rgbdslam rgbdslam.launch

To capture models either press space to start recording a continuous stream or press enter to record a single frame. To reduce data redundancy, sequential frames from (almost) the same position are not included in the final model.

Parameters RGBDSLAMv2 is customizable by parameters. These should be set in the launch file. Parameters can be changed during operation from the GUI, however, changes from the GUI may have no effect for many parameters.

Visualization The 3D visualization shows the globally optimized model (you might have to click into it to update the view after optimization). Neighbouring points can be triangulated except at missing values and depth jumps. With the shortcut "t", triangulation can be toggled. Since raw points render slightly faster the parameter "cloud_display_type" controls whether triangulation is computed at all - at the time the cloud is received. The parameter "gl_point_size" may be useful to most users.

Usage without GUI

The RosUI is an alternative to the Grapical_UI to run the rgbdslam headless, for example on the PR2. rgbdslam can then be used via service-calls. The possible calls are:

  • /rgbdslam/ros_ui {reset, quick_save, send_all, delete_frame, optimize, reload_config, save_trajectory}
  • /rgbdslam/ros_ui_b {pause, record} {true, false}
  • /rgbdslam/ros_ui_f {set_max} {float}
  • /rgbdslam/ros_ui_s {save_octomap, save_cloud, save_g2o_graph, save_trajectory, save_features, save_individual} {filename}

To start the rgbdslam headless use the headless.launch: $ roslaunch rgbdslam headless.launch

Capture single frames via: $ rosservice call /rgbdslam/ros_ui frame

Capture a stream of data: $ rosservice call /rgbdslam/ros_ui_b pause false

Send point clouds with computed transformations (e.g., to rviz or octomap_server): $ rosservice call /rgbdslam/ros_ui send_all

Save data using one of the following:

All pointclouds in one file quicksave.pcd in rgbdslam/bin-directory: $ rosservice call /rgbdslam/ros_ui_s save_cloud

Every pointcloud in its own file in rgbdslam/bin-directory: $ rosservice call /rgbdslam/ros_ui save_individual

/rgbdslam/ros_ui:

  • reset ''resets the graph, delets all nodes (refreshes only when capturing new images)''
  • frame ''capture one frame from the sensor''
  • optimize ''trigger graph optimizer''
  • reload_config ''reloads the paramters from the ROS paramter server''
  • quick_save ''saves all pointclouds in one file quicksave.pcd in rgbdslam/bin-directory''
  • send_all ''sends all pointclouds to /rgbdslam/transformed_cloud (can be visualized with rviz)''
  • delete_frame ''delete the last frame from the graph (refreshes only when capturing new images)''

/rgbdslam/ros_ui_b:

  • pause ''pauses or resumes the capturing of images''
  • record ''pauses or stops the recording of bag-files, can be found in the rgbdslam/bin-directory''

/rgbdslam/ros_ui_f:

  • set_max ''filters out all datapoints further away than this value (in cm, only for saving to files)''

/rgbdslam/ros_ui_s:

  • save_features ''saves the feature locations and descriptors in a yaml file with the given filename''
  • save_cloud ''saves the cloud to the given filename (should end with .ply or .pcd)''
  • save_individual ''saves every scan in its own file (appending a suffix to the given prefix)''
  • save_octomap ''saves the cloud to the given filename''
  • save_trajectory ''saves the sensor trajectory to the file _estimate.txt''

Further Help

The compilation may take a lot of memory, particularly if the environment variable $ROS_PARALLEL_JOBS is set.

If you are located in Germany and get errors loading the saved ply files into meshlab, try switching to U.S. locale or replace the decimal point with a comma in your .ply file

If you have questions regarding installation or usage of RGBDSLAM please refer to http://answers.ros.org/questions/?tags=RGBDSLAM For further questions, suggestions, corrections of this README or to submit patches, please contact Felix Endres ([email protected]).

Apart from this manual, code documentation can be created using rosdoc ("rosrun rosdoc rosdoc rgbdslam"), which will create a "doc" folder in your current directory.

GICP and SIFTGPU

If there are problems related to the compilation or linking of GICP or SIFTGPU, you can deactivate these features at the top of CMakeLists.txt. You might get even faster GPU features setting the parameter "siftgpu_with_cuda" but you will need to install the proprietary CUDA drivers that may require a NVidia GPU (see http://www.nvidia.com/object/cuda_gpus.html). For installing the development drivers and the CUDA SDK you can use the following tutorial: http://sublimated.wordpress.com/2011/03/25/installing-cuda-4-0-rc-on-ubuntu-10-10-64-bit/ or for ubuntu 10.04: http://ubuntuforums.org/showthread.php?t=1625433 (tested on Ubuntu 10.04 x64) To use SiftGPU you should install "libdevil-dev".

Additional compiling information can be changed in external/siftgpu/linux/makefile.

If you get an error that the siftgpu library is not found, execute "make" manually in the directory external/siftgpu/ and rerun catkin_make.

GICP Generalized ICP can be (de)activated for refining the registration. For more information see http://stanford.edu/~avsegal/generalized_icp.html

License Information

This software is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.

RGBDSLAM is licenced under GPL v.3. See the accompanying file "COPYING".

rgbdslam_v2's People

Contributors

agilmor avatar blueeaglex avatar bryant1410 avatar felixendres avatar icoderaven avatar kbalisciano avatar michaelkorn 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

rgbdslam_v2's Issues

Build errors about qt5

Hello,
There are some errors about qt5 when I built this package.
I try to install qt5 but it does not work.
Please tell me how to fix it.

dev@ubuntu:~/catkin_ws$ catkin_make
Base path: /home/dev/catkin_ws
Source space: /home/dev/catkin_ws/src
Build space: /home/dev/catkin_ws/build
Devel space: /home/dev/catkin_ws/devel
Install space: /home/dev/catkin_ws/install

Running command: "make cmake_check_build_system" in "/home/dev/catkin_ws/build"

-- Using CATKIN_DEVEL_PREFIX: /home/dev/catkin_ws/devel
-- Using CMAKE_PREFIX_PATH: /opt/ros/indigo
-- This workspace overlays: /opt/ros/indigo
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/dev/catkin_ws/build/test_results
-- Found gtest sources under '/usr/src/gtest': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.6.18
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~ traversing 1 packages in topological order:
-- ~~ - rgbdslam
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'rgbdslam'
-- ==> add_subdirectory(rgbdslam_v2)
-- SiftGPU library will be used
-- Using these message generators: gencpp;genlisp;genpy
-- rgbdslam: 0 messages, 4 services
-- Boost version: 1.54.0
-- Found the following Boost libraries:
-- system
-- filesystem
-- thread
-- date_time
-- iostreams
-- serialization
-- checking for module 'openni-dev'
-- package 'openni-dev' not found
-- looking for PCL_COMMON
-- looking for PCL_OCTREE
-- looking for PCL_IO
-- Searching for g2o ...
-- Found g2o headers in: /opt/ros/indigo/include
-- Found libg2o: /opt/ros/indigo/lib/libg2o_csparse_extension.so;/opt/ros/indigo/lib/libg2o_core.so;/opt/ros/indigo/lib/libg2o_stuff.so;/opt/ros/indigo/lib/libg2o_types_slam3d.so;/opt/ros/indigo/lib/libg2o_solver_cholmod.so;/opt/ros/indigo/lib/libg2o_solver_pcg.so;/opt/ros/indigo/lib/libg2o_solver_csparse.so
G2o-libraries /opt/ros/indigo/lib/libg2o_csparse_extension.so/opt/ros/indigo/lib/libg2o_core.so/opt/ros/indigo/lib/libg2o_stuff.so/opt/ros/indigo/lib/libg2o_types_slam3d.so/opt/ros/indigo/lib/libg2o_solver_cholmod.so/opt/ros/indigo/lib/libg2o_solver_pcg.so/opt/ros/indigo/lib/libg2o_solver_csparse.so
CMake Warning at rgbdslam_v2/CMakeLists.txt:98 (find_package):
By not providing "FindQt5Widgets.cmake" in CMAKE_MODULE_PATH this project
has asked CMake to find a package configuration file provided by
"Qt5Widgets", but CMake did not find one.

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

Qt5WidgetsConfig.cmake
qt5widgets-config.cmake

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

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

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

Qt5OpenGLConfig.cmake
qt5opengl-config.cmake

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

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

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

Qt5ConcurrentConfig.cmake
qt5concurrent-config.cmake

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

/home/dev/catkin_ws/src/rgbdslam_v2/external/SiftGPU/
/home/dev/catkin_ws/build/rgbdslam_v2/external/siftgpu_prefix
Using OpenCV from /usr/share/OpenCV
CMake Error at rgbdslam_v2/CMakeLists.txt:212 (qt5_add_resources):
Unknown CMake command "qt5_add_resources".

-- Configuring incomplete, errors occurred!
See also "/home/dev/catkin_ws/build/CMakeFiles/CMakeOutput.log".
See also "/home/dev/catkin_ws/build/CMakeFiles/CMakeError.log".
make: *** [cmake_check_build_system] Error 1
Invoking "make cmake_check_build_system" failed

Invoking "make -j8 -l8" failed for rgbdslam_v2

Hi

When I run catkin_make for rgbdslam_v2 in ROS Indigo, Ubuntu 14.04 LTS. I get the error below. This is only part of the error, couldn't get the rest.

/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:211:65: required from ‘Eigen::GeneralProduct<Lhs, Rhs, 3>::GeneralProduct(const Lhs&, const Rhs&) [with Lhs = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; Rhs = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:595:60: required from ‘const typename Eigen::ProductReturnType<Derived, OtherDerived>::Type Eigen::MatrixBase<Derived>::operator*(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; typename Eigen::ProductReturnType<Derived, OtherDerived>::Type = Eigen::GeneralProduct<Eigen::Transpose<Eigen::Matrix<double, 3, 1> >, Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >, 3>]’ /home/ap/catkin_ws/src/rgbdslam_v2/src/misc.cpp:763:125: required from here /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:56:30: warning: ignoring attributes on template argument ‘Eigen::internal::packet_traits<double>::type {aka __vector(2) double}’ [-Wignored-attributes] /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h: In instantiation of ‘class Eigen::DenseCoeffsBase<Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false>, 0>’: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:566:7: required from ‘class Eigen::DenseCoeffsBase<Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false>, 2>’ /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h:371:8: required from ‘struct Eigen::internal::special_scalar_op_base<Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false>, double, double, false>’ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:41:34: required from ‘class Eigen::DenseBase<Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >’ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:48:34: required from ‘class Eigen::MatrixBase<Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >’ /usr/include/eigen3/Eigen/src/Core/MapBase.h:27:34: required from ‘class Eigen::MapBase<Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false>, 0>’ /usr/include/eigen3/Eigen/src/Core/Block.h:313:7: [ skipping 13 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ] /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h:61:7: required from ‘void Eigen::ReturnByValue<Derived>::evalTo(Dest&) const [with Dest = Eigen::Matrix<double, 3, 1>; Derived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >]’ /usr/include/eigen3/Eigen/src/Core/Matrix.h:296:7: required from ‘Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::Matrix(const Eigen::ReturnByValue<OtherDerived>&) [with OtherDerived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >; _Scalar = double; int _Rows = 3; int _Cols = 1; int _Options = 0; int _MaxRows = 3; int _MaxCols = 1]’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:126:49: required from ‘Eigen::CwiseBinaryOp<BinaryOp, Lhs, Rhs>::CwiseBinaryOp(const Lhs&, const Rhs&, const BinaryOp&) [with BinaryOp = Eigen::internal::scalar_product_op<double, double>; Lhs = const Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; Rhs = const Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:24:10: required from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<typename Eigen::internal::traits<T>::Scalar, typename Eigen::internal::traits<OtherDerived>::Scalar>, const Derived, const OtherDerived> Eigen::MatrixBase<Derived>::cwiseProduct(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; typename Eigen::internal::traits<OtherDerived>::Scalar = double; typename Eigen::internal::traits<T>::Scalar = double]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:211:65: required from ‘Eigen::GeneralProduct<Lhs, Rhs, 3>::GeneralProduct(const Lhs&, const Rhs&) [with Lhs = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; Rhs = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:595:60: required from ‘const typename Eigen::ProductReturnType<Derived, OtherDerived>::Type Eigen::MatrixBase<Derived>::operator*(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; typename Eigen::ProductReturnType<Derived, OtherDerived>::Type = Eigen::GeneralProduct<Eigen::Transpose<Eigen::Matrix<double, 3, 1> >, Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >, 3>]’ /home/ap/catkin_ws/src/rgbdslam_v2/src/misc.cpp:763:125: required from here /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:56:30: warning: ignoring attributes on template argument ‘Eigen::internal::packet_traits<double>::type {aka __vector(2) double}’ [-Wignored-attributes] /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h: In instantiation of ‘class Eigen::DenseCoeffsBase<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, 0>’: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:566:7: required from ‘class Eigen::DenseCoeffsBase<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, 2>’ /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h:371:8: required from ‘struct Eigen::internal::special_scalar_op_base<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, double, double, false>’ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:41:34: required from ‘class Eigen::DenseBase<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> > >’ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:48:34: required from ‘class Eigen::MatrixBase<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> > >’ /usr/include/eigen3/Eigen/src/Core/Transpose.h:100:37: required from ‘class Eigen::TransposeImpl<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false>, Eigen::Dense>’ /usr/include/eigen3/Eigen/src/Core/Transpose.h:57:37: [ skipping 10 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ] /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h:61:7: required from ‘void Eigen::ReturnByValue<Derived>::evalTo(Dest&) const [with Dest = Eigen::Matrix<double, 3, 1>; Derived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >]’ /usr/include/eigen3/Eigen/src/Core/Matrix.h:296:7: required from ‘Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::Matrix(const Eigen::ReturnByValue<OtherDerived>&) [with OtherDerived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >; _Scalar = double; int _Rows = 3; int _Cols = 1; int _Options = 0; int _MaxRows = 3; int _MaxCols = 1]’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:126:49: required from ‘Eigen::CwiseBinaryOp<BinaryOp, Lhs, Rhs>::CwiseBinaryOp(const Lhs&, const Rhs&, const BinaryOp&) [with BinaryOp = Eigen::internal::scalar_product_op<double, double>; Lhs = const Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; Rhs = const Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:24:10: required from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<typename Eigen::internal::traits<T>::Scalar, typename Eigen::internal::traits<OtherDerived>::Scalar>, const Derived, const OtherDerived> Eigen::MatrixBase<Derived>::cwiseProduct(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; typename Eigen::internal::traits<OtherDerived>::Scalar = double; typename Eigen::internal::traits<T>::Scalar = double]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:211:65: required from ‘Eigen::GeneralProduct<Lhs, Rhs, 3>::GeneralProduct(const Lhs&, const Rhs&) [with Lhs = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; Rhs = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:595:60: required from ‘const typename Eigen::ProductReturnType<Derived, OtherDerived>::Type Eigen::MatrixBase<Derived>::operator*(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; typename Eigen::ProductReturnType<Derived, OtherDerived>::Type = Eigen::GeneralProduct<Eigen::Transpose<Eigen::Matrix<double, 3, 1> >, Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >, 3>]’ /home/ap/catkin_ws/src/rgbdslam_v2/src/misc.cpp:763:125: required from here /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:56:30: warning: ignoring attributes on template argument ‘Eigen::internal::packet_traits<double>::type {aka __vector(2) double}’ [-Wignored-attributes] /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h: In instantiation of ‘class Eigen::DenseCoeffsBase<Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false>, 0>’: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:274:7: required from ‘class Eigen::DenseCoeffsBase<Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false>, 1>’ /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:636:7: required from ‘class Eigen::DenseCoeffsBase<Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false>, 3>’ /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h:371:8: required from ‘struct Eigen::internal::special_scalar_op_base<Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false>, double, double, false>’ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:41:34: required from ‘class Eigen::DenseBase<Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> >’ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:48:34: required from ‘class Eigen::MatrixBase<Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> >’ /usr/include/eigen3/Eigen/src/Core/MapBase.h:27:34: [ skipping 15 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ] /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h:61:7: required from ‘void Eigen::ReturnByValue<Derived>::evalTo(Dest&) const [with Dest = Eigen::Matrix<double, 3, 1>; Derived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >]’ /usr/include/eigen3/Eigen/src/Core/Matrix.h:296:7: required from ‘Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::Matrix(const Eigen::ReturnByValue<OtherDerived>&) [with OtherDerived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >; _Scalar = double; int _Rows = 3; int _Cols = 1; int _Options = 0; int _MaxRows = 3; int _MaxCols = 1]’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:126:49: required from ‘Eigen::CwiseBinaryOp<BinaryOp, Lhs, Rhs>::CwiseBinaryOp(const Lhs&, const Rhs&, const BinaryOp&) [with BinaryOp = Eigen::internal::scalar_product_op<double, double>; Lhs = const Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; Rhs = const Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:24:10: required from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<typename Eigen::internal::traits<T>::Scalar, typename Eigen::internal::traits<OtherDerived>::Scalar>, const Derived, const OtherDerived> Eigen::MatrixBase<Derived>::cwiseProduct(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; typename Eigen::internal::traits<OtherDerived>::Scalar = double; typename Eigen::internal::traits<T>::Scalar = double]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:211:65: required from ‘Eigen::GeneralProduct<Lhs, Rhs, 3>::GeneralProduct(const Lhs&, const Rhs&) [with Lhs = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; Rhs = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:595:60: required from ‘const typename Eigen::ProductReturnType<Derived, OtherDerived>::Type Eigen::MatrixBase<Derived>::operator*(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; typename Eigen::ProductReturnType<Derived, OtherDerived>::Type = Eigen::GeneralProduct<Eigen::Transpose<Eigen::Matrix<double, 3, 1> >, Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >, 3>]’ /home/ap/catkin_ws/src/rgbdslam_v2/src/misc.cpp:763:125: required from here /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:56:30: warning: ignoring attributes on template argument ‘Eigen::internal::packet_traits<double>::type {aka __vector(2) double}’ [-Wignored-attributes] /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h: In instantiation of ‘class Eigen::DenseCoeffsBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> >, 0>’: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h:371:8: required from ‘struct Eigen::internal::special_scalar_op_base<Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> >, double, double, false>’ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:41:34: required from ‘class Eigen::DenseBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> > >’ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:48:34: required from ‘class Eigen::MatrixBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> > >’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:163:7: required from ‘class Eigen::CwiseBinaryOpImpl<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false>, Eigen::Dense>’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:106:7: required from ‘class Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Matrix<double, 3, 3>, 1, 3, false>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> >’ /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h:126:72: [ skipping 9 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ] /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h:61:7: required from ‘void Eigen::ReturnByValue<Derived>::evalTo(Dest&) const [with Dest = Eigen::Matrix<double, 3, 1>; Derived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >]’ /usr/include/eigen3/Eigen/src/Core/Matrix.h:296:7: required from ‘Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::Matrix(const Eigen::ReturnByValue<OtherDerived>&) [with OtherDerived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >; _Scalar = double; int _Rows = 3; int _Cols = 1; int _Options = 0; int _MaxRows = 3; int _MaxCols = 1]’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:126:49: required from ‘Eigen::CwiseBinaryOp<BinaryOp, Lhs, Rhs>::CwiseBinaryOp(const Lhs&, const Rhs&, const BinaryOp&) [with BinaryOp = Eigen::internal::scalar_product_op<double, double>; Lhs = const Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; Rhs = const Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:24:10: required from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<typename Eigen::internal::traits<T>::Scalar, typename Eigen::internal::traits<OtherDerived>::Scalar>, const Derived, const OtherDerived> Eigen::MatrixBase<Derived>::cwiseProduct(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; typename Eigen::internal::traits<OtherDerived>::Scalar = double; typename Eigen::internal::traits<T>::Scalar = double]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:211:65: required from ‘Eigen::GeneralProduct<Lhs, Rhs, 3>::GeneralProduct(const Lhs&, const Rhs&) [with Lhs = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; Rhs = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:595:60: required from ‘const typename Eigen::ProductReturnType<Derived, OtherDerived>::Type Eigen::MatrixBase<Derived>::operator*(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; typename Eigen::ProductReturnType<Derived, OtherDerived>::Type = Eigen::GeneralProduct<Eigen::Transpose<Eigen::Matrix<double, 3, 1> >, Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >, 3>]’ /home/ap/catkin_ws/src/rgbdslam_v2/src/misc.cpp:763:125: required from here /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:56:30: warning: ignoring attributes on template argument ‘Eigen::internal::packet_traits<double>::type {aka __vector(2) double}’ [-Wignored-attributes] /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h: In instantiation of ‘class Eigen::DenseCoeffsBase<Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false>, 0>’: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:566:7: required from ‘class Eigen::DenseCoeffsBase<Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false>, 2>’ /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h:371:8: required from ‘struct Eigen::internal::special_scalar_op_base<Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false>, double, double, false>’ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:41:34: required from ‘class Eigen::DenseBase<Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >’ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:48:34: required from ‘class Eigen::MatrixBase<Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >’ /usr/include/eigen3/Eigen/src/Core/MapBase.h:27:34: required from ‘class Eigen::MapBase<Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false>, 0>’ /usr/include/eigen3/Eigen/src/Core/Block.h:313:7: [ skipping 13 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ] /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h:61:7: required from ‘void Eigen::ReturnByValue<Derived>::evalTo(Dest&) const [with Dest = Eigen::Matrix<double, 3, 1>; Derived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >]’ /usr/include/eigen3/Eigen/src/Core/Matrix.h:296:7: required from ‘Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::Matrix(const Eigen::ReturnByValue<OtherDerived>&) [with OtherDerived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >; _Scalar = double; int _Rows = 3; int _Cols = 1; int _Options = 0; int _MaxRows = 3; int _MaxCols = 1]’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:126:49: required from ‘Eigen::CwiseBinaryOp<BinaryOp, Lhs, Rhs>::CwiseBinaryOp(const Lhs&, const Rhs&, const BinaryOp&) [with BinaryOp = Eigen::internal::scalar_product_op<double, double>; Lhs = const Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; Rhs = const Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:24:10: required from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<typename Eigen::internal::traits<T>::Scalar, typename Eigen::internal::traits<OtherDerived>::Scalar>, const Derived, const OtherDerived> Eigen::MatrixBase<Derived>::cwiseProduct(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; typename Eigen::internal::traits<OtherDerived>::Scalar = double; typename Eigen::internal::traits<T>::Scalar = double]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:211:65: required from ‘Eigen::GeneralProduct<Lhs, Rhs, 3>::GeneralProduct(const Lhs&, const Rhs&) [with Lhs = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; Rhs = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:595:60: required from ‘const typename Eigen::ProductReturnType<Derived, OtherDerived>::Type Eigen::MatrixBase<Derived>::operator*(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; typename Eigen::ProductReturnType<Derived, OtherDerived>::Type = Eigen::GeneralProduct<Eigen::Transpose<Eigen::Matrix<double, 3, 1> >, Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >, 3>]’ /home/ap/catkin_ws/src/rgbdslam_v2/src/misc.cpp:763:125: required from here /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:56:30: warning: ignoring attributes on template argument ‘Eigen::internal::packet_traits<double>::type {aka __vector(2) double}’ [-Wignored-attributes] /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h: In instantiation of ‘class Eigen::DenseCoeffsBase<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, 0>’: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:566:7: required from ‘class Eigen::DenseCoeffsBase<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, 2>’ /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h:371:8: required from ‘struct Eigen::internal::special_scalar_op_base<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, double, double, false>’ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:41:34: required from ‘class Eigen::DenseBase<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> > >’ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:48:34: required from ‘class Eigen::MatrixBase<Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> > >’ /usr/include/eigen3/Eigen/src/Core/Transpose.h:100:37: required from ‘class Eigen::TransposeImpl<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false>, Eigen::Dense>’ /usr/include/eigen3/Eigen/src/Core/Transpose.h:57:37: [ skipping 10 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ] /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h:61:7: required from ‘void Eigen::ReturnByValue<Derived>::evalTo(Dest&) const [with Dest = Eigen::Matrix<double, 3, 1>; Derived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >]’ /usr/include/eigen3/Eigen/src/Core/Matrix.h:296:7: required from ‘Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::Matrix(const Eigen::ReturnByValue<OtherDerived>&) [with OtherDerived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >; _Scalar = double; int _Rows = 3; int _Cols = 1; int _Options = 0; int _MaxRows = 3; int _MaxCols = 1]’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:126:49: required from ‘Eigen::CwiseBinaryOp<BinaryOp, Lhs, Rhs>::CwiseBinaryOp(const Lhs&, const Rhs&, const BinaryOp&) [with BinaryOp = Eigen::internal::scalar_product_op<double, double>; Lhs = const Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; Rhs = const Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:24:10: required from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<typename Eigen::internal::traits<T>::Scalar, typename Eigen::internal::traits<OtherDerived>::Scalar>, const Derived, const OtherDerived> Eigen::MatrixBase<Derived>::cwiseProduct(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; typename Eigen::internal::traits<OtherDerived>::Scalar = double; typename Eigen::internal::traits<T>::Scalar = double]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:211:65: required from ‘Eigen::GeneralProduct<Lhs, Rhs, 3>::GeneralProduct(const Lhs&, const Rhs&) [with Lhs = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; Rhs = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:595:60: required from ‘const typename Eigen::ProductReturnType<Derived, OtherDerived>::Type Eigen::MatrixBase<Derived>::operator*(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; typename Eigen::ProductReturnType<Derived, OtherDerived>::Type = Eigen::GeneralProduct<Eigen::Transpose<Eigen::Matrix<double, 3, 1> >, Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >, 3>]’ /home/ap/catkin_ws/src/rgbdslam_v2/src/misc.cpp:763:125: required from here /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:56:30: warning: ignoring attributes on template argument ‘Eigen::internal::packet_traits<double>::type {aka __vector(2) double}’ [-Wignored-attributes] /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h: In instantiation of ‘class Eigen::DenseCoeffsBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> >, 0>’: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h:371:8: required from ‘struct Eigen::internal::special_scalar_op_base<Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> >, double, double, false>’ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:41:34: required from ‘class Eigen::DenseBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> > >’ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:48:34: required from ‘class Eigen::MatrixBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> > >’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:163:7: required from ‘class Eigen::CwiseBinaryOpImpl<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false>, Eigen::Dense>’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:106:7: required from ‘class Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<double, double>, const Eigen::Transpose<const Eigen::Block<const Eigen::Block<const Eigen::Transpose<const Eigen::Matrix<double, 3, 3> >, 1, 3, true>, 1, 2, false> >, const Eigen::Block<Eigen::Matrix<double, 3, 1>, 2, 1, false> >’ /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h:126:72: [ skipping 9 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ] /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h:61:7: required from ‘void Eigen::ReturnByValue<Derived>::evalTo(Dest&) const [with Dest = Eigen::Matrix<double, 3, 1>; Derived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >]’ /usr/include/eigen3/Eigen/src/Core/Matrix.h:296:7: required from ‘Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::Matrix(const Eigen::ReturnByValue<OtherDerived>&) [with OtherDerived = Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> >; _Scalar = double; int _Rows = 3; int _Cols = 1; int _Options = 0; int _MaxRows = 3; int _MaxCols = 1]’ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:126:49: required from ‘Eigen::CwiseBinaryOp<BinaryOp, Lhs, Rhs>::CwiseBinaryOp(const Lhs&, const Rhs&, const BinaryOp&) [with BinaryOp = Eigen::internal::scalar_product_op<double, double>; Lhs = const Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; Rhs = const Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:24:10: required from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_product_op<typename Eigen::internal::traits<T>::Scalar, typename Eigen::internal::traits<OtherDerived>::Scalar>, const Derived, const OtherDerived> Eigen::MatrixBase<Derived>::cwiseProduct(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<const Eigen::Transpose<Eigen::Matrix<double, 3, 1> > >; typename Eigen::internal::traits<OtherDerived>::Scalar = double; typename Eigen::internal::traits<T>::Scalar = double]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:211:65: required from ‘Eigen::GeneralProduct<Lhs, Rhs, 3>::GeneralProduct(const Lhs&, const Rhs&) [with Lhs = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; Rhs = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >]’ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:595:60: required from ‘const typename Eigen::ProductReturnType<Derived, OtherDerived>::Type Eigen::MatrixBase<Derived>::operator*(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >; Derived = Eigen::Transpose<Eigen::Matrix<double, 3, 1> >; typename Eigen::ProductReturnType<Derived, OtherDerived>::Type = Eigen::GeneralProduct<Eigen::Transpose<Eigen::Matrix<double, 3, 1> >, Eigen::ReturnByValue<Eigen::internal::solve_retval_base<Eigen::LLT<Eigen::Matrix<double, 3, 3>, 1>, Eigen::Matrix<double, 3, 1> > >, 3>]’ /home/ap/catkin_ws/src/rgbdslam_v2/src/misc.cpp:763:125: required from here /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h:56:30: warning: ignoring attributes on template argument ‘Eigen::internal::packet_traits<double>::type {aka __vector(2) double}’ [-Wignored-attributes] make[2]: *** [rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/misc.cpp.o] Error 1 make[1]: *** [rgbdslam_v2/CMakeFiles/rgbdslam.dir/all] Error 2 make: *** [all] Error 2 make: INTERNAL: Exiting with 10 jobserver tokens available; should be 8! Invoking "make -j8 -l8" failed

Here are the CMakeLists.txt and package.xml files.

My pc also freezes sometimes when running catkin_make for this package. I have 8 Gb of RAM and 5 Gb of space left. Is this a memory problem ?

Thank you

error on installation from Scratch

system ubuntu 16.04
ros kinetic

when i run the install.sh script and then got this error . i guess it is because of the g2o library but i can‘t fix it.

error: #error This file requires compiler and library support for the ISO C++ 2011 standard. This support must be enabled with the -std=c++11 or -std=gnu++11 compiler options.
 #error This file requires compiler and library support \
  ^
In file included from /usr/local/include/g2o/core/optimizable_graph.h:38:0,
                 from /usr/local/include/g2o/core/sparse_optimizer.h:32,
                 from /home/liangzhu/Code/rgbdslam_catkin_ws/build/rgbdslam/src/../../../src/rgbdslam/src/graph_manager.h:58,
                 from /home/liangzhu/Code/rgbdslam_catkin_ws/build/rgbdslam/src/../../../src/rgbdslam/src/openni_listener.h:31,
                 from /home/liangzhu/Code/rgbdslam_catkin_ws/build/rgbdslam/src/moc_openni_listener.cpp:9:
/usr/local/include/g2o/core/hyper_graph.h:138:20: error: ‘unordered_map’ in namespace ‘std’ does not name a template type
       typedef std::unordered_map<int, Vertex*>     VertexIDMap;
                    ^
/usr/local/include/g2o/core/hyper_graph.h:225:13: error: ‘VertexIDMap’ does not name a type
       const VertexIDMap& vertices() const {return _vertices;}
             ^
/usr/local/include/g2o/core/hyper_graph.h:227:7: error: ‘VertexIDMap’ does not name a type
       VertexIDMap& vertices() {return _vertices;}

Issues with Boost > 1.48

[ 36%] Generating src/moc_qt_gui.cxx
Generating src/moc_graph_manager.cxx
Generating src/moc_openni_listener.cxx
Generating src/moc_glviewer.cxx
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
make[2]: *** [rgbdslam_v2-indigo/src/moc_qtros.cxx] Error 1
make[2]: *** Waiting for unfinished jobs....
make[2]: *** [rgbdslam_v2-indigo/src/moc_ros_service_ui.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
make[2]: *** [rgbdslam_v2-indigo/src/moc_glviewer.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
make[2]: *** [rgbdslam_v2-indigo/src/moc_qt_gui.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
make[2]: *** [rgbdslam_v2-indigo/src/moc_graph_manager.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
make[2]: *** [rgbdslam_v2-indigo/src/moc_openni_listener.cxx] Error 1
make[1]: *** [rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/all] Error 2
make: *** [all] Error 2

This is due to the way Boost handles messaging.

gqrx-sdr/gqrx#93

This seems to have the issue fixed but I'm confused as to why I'm having this problem and no one else. I will most down a few boost versions and try to reinstall.

RGBDSLAM ROS Indigo installation error - catkin_make error

With reference to this thread https://github.com/felixendres/rgbdslam_v2/issues/13 , I get the following error while installing rgbdslam in ROS Indigo. Can anyone kindly help me out with issue ...

Running command: "make cmake_check_build_system" in "/home/ram/rgbdslam_catkin_ws/build"

Running command: "make -j4 -l4" in "/home/ram/rgbdslam_catkin_ws/build"

[ 0%] [ 0%] [ 0%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_f
Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui
Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_s
[ 0%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_b
[ 8%] [ 13%] Built target rgbdslam_generate_messages_lisp
Built target rgbdslam_generate_messages_cpp
[ 31%] [ 34%] Built target rgbdslam_generate_messages_py
Built target siftgpu_proj
[ 34%] Built target rgbdslam_gencpp
[ 34%] Built target rgbdslam_generate_messages
[ 36%] [ 37%] Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/openni_listener.cpp.o
[ 39%] [ 40%] Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/glviewer.cpp.o
Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/parameter_server.cpp.o
Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/node.cpp.o
virtual memory exhausted: Cannot allocate memory
make[2]: *** [rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/node.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
c++: internal compiler error: Killed (program cc1plus)
Please submit a full bug report,
with preprocessed source if appropriate.
See file:///usr/share/doc/gcc-4.8/README.Bugs for instructions.
make[2]: *** [rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/glviewer.cpp.o] Error 4
c++: internal compiler error: Killed (program cc1plus)
Please submit a full bug report,
with preprocessed source if appropriate.
See file:///usr/share/doc/gcc-4.8/README.Bugs for instructions.
make[2]: *** [rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/openni_listener.cpp.o] Error 4
make[1]: *** [rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/all] Error 2
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

cmake error when install rgbdslam v2 using install.sh

I used to install rgbdslam_v2 on my kinetic laptop successfully. however, i deleted the rgbdslam workspace for some reason and now tried to install it again. I first followed instructions in this link: #42
didn't work. Then i tried the install.sh, still didn't work. Both failed in cmake process. Here are the errors:

-- Searching for g2o ...
-- Searching for g2o in /home/jack/Code/g2ofork/install
-- Found g2o headers in: /home/jack/Code/g2ofork/install/include
-- Found libg2o: /home/jack/Code/g2ofork/install/lib/libg2o_csparse_extension.so;/home/jack/Code/g2ofork/install/lib/libg2o_core.so;/home/jack/Code/g2ofork/install/lib/libg2o_stuff.so;/home/jack/Code/g2ofork/install/lib/libg2o_types_slam3d.so;G2O_SOLVER_CHOLMOD_LIB-NOTFOUND;/home/jack/Code/g2ofork/install/lib/libg2o_solver_pcg.so;/home/jack/Code/g2ofork/install/lib/libg2o_solver_csparse.so
G2o-libraries /home/jack/Code/g2ofork/install/lib/libg2o_csparse_extension.so/home/jack/Code/g2ofork/install/lib/libg2o_core.so/home/jack/Code/g2ofork/install/lib/libg2o_stuff.so/home/jack/Code/g2ofork/install/lib/libg2o_types_slam3d.soG2O_SOLVER_CHOLMOD_LIB-NOTFOUND/home/jack/Code/g2ofork/install/lib/libg2o_solver_pcg.so/home/jack/Code/g2ofork/install/lib/libg2o_solver_csparse.so
-- Try OpenMP C flag = [-fopenmp]
-- Performing Test OpenMP_FLAG_DETECTED
-- Performing Test OpenMP_FLAG_DETECTED - Success
-- Try OpenMP CXX flag = [-fopenmp]
-- Performing Test OpenMP_FLAG_DETECTED
-- Performing Test OpenMP_FLAG_DETECTED - Success
-- Found OpenMP: -fopenmp
/home/jack/Code/rgbdslam_catkin_ws/src/rgbdslam/external/SiftGPU/
/home/jack/Code/rgbdslam_catkin_ws/build/rgbdslam/external/siftgpu_prefix
Using OpenCV from
CMake Error: The following variables are used in this project, but they are set to NOTFOUND.
Please set them or make sure they are set and tested correctly in the CMake files:
G2O_SOLVER_CHOLMOD_LIB
linked by target "rgbdslam" in directory /home/jack/Code/rgbdslam_catkin_ws/src/rgbdslam
linked by target "rgbdslam" in directory /home/jack/Code/rgbdslam_catkin_ws/src/rgbdslam

-- Configuring incomplete, errors occurred!
See also "/home/jack/Code/rgbdslam_catkin_ws/build/CMakeFiles/CMakeOutput.log".
See also "/home/jack/Code/rgbdslam_catkin_ws/build/CMakeFiles/CMakeError.log".
Invoking "cmake" failed

So what's the problem exactly? why i used to install it successfully but failed now? Tanks

Update: the g20 output

`Downloading, building and installing g2o

fatal: destination path '/home/jack/Code/g2ofork' already exists and is not an empty directory.
mkdir: cannot create directory ‘/home/jack/Code/g2ofork/build’: File exists
-- Compiling on Unix
-- Could NOT find CHOLMOD (missing: CHOLMOD_INCLUDE_DIR CHOLMOD_LIBRARIES)
-- Compiling with OpenGL support
-- Could NOT find QGLVIEWER (missing: QGLVIEWER_INCLUDE_DIR QGLVIEWER_LIBRARY)
-- Compiling g2o apps
-- Compiling with GCC
-- Configuring done
-- Generating done
-- Build files have been written to: /home/jack/Code/g2ofork/build
[ 2%] Built target freeglut_minimal
[ 6%] Built target stuff
[ 7%] Built target opengl_helper
[ 32%] Built target csparse
[ 33%] Built target csparse_extension
[ 45%] Built target core
[ 47%] Built target g2o_cli_library
[ 51%] Built target g2o_hierarchical_library
[ 60%] Built target types_slam3d
[ 68%] Built target types_slam2d
[ 69%] Built target solver_pcg
[ 70%] Built target solver_dense
[ 71%] Built target solver_structure_only
[ 72%] Built target solver_csparse
[ 73%] Built target solver_eigen
[ 74%] Built target g2o_cli_application
[ 75%] Built target g2o_hierarchical_application
[ 76%] Built target test_isometry3d_mappings
[ 81%] Built target types_data
[ 82%] Built target test_mat2quat_jacobian
[ 83%] Built target test_slam3d_jacobian
[ 84%] Built target types_sba
[ 87%] Built target types_sclam2d
[ 91%] Built target types_slam2d_addons
[ 97%] Built target types_slam3d_addons
[ 98%] Built target solver_slam2d_linear
[ 99%] Built target types_sim3
[100%] Built target types_icp
Install the project...
-- Install configuration: "Release"
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/config.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/g2o/G2OConfig.cmake
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_ext_csparse.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/EXTERNAL/csparse/cs.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/EXTERNAL/csparse/cs_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_ext_freeglut_minimal.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/EXTERNAL/freeglut/freeglut_minimal.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_stuff.so
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_opengl_helper.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/opengl_primitives.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/opengl_wrapper.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/sampler.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/g2o_stuff_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/timeutil.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/filesys_tools.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/command_args.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/scoped_pointer.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/unscented.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/color_macros.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/macros.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/sparse_helper.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/property.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/os_specific.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/misc.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/tictoc.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/stuff/string_tools.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_core.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/matrix_operations.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/g2o_core_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/robust_kernel.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/factory.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/sparse_block_matrix_ccs.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/robust_kernel_factory.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/solver.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/sparse_optimizer_terminate_action.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/parameter.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/optimization_algorithm_property.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/sparse_block_matrix.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_edge.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/openmp_mutex.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/optimization_algorithm_levenberg.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/hyper_graph.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/parameter_container.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/linear_solver.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/sparse_block_matrix_diagonal.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/cache.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/eigen_types.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/batch_stats.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/estimate_propagator.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/optimization_algorithm_gauss_newton.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/hyper_dijkstra.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_unary_edge.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/robust_kernel_impl.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/creators.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/jacobian_workspace.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/sparse_optimizer.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/marginal_covariance_cholesky.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_binary_edge.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/optimization_algorithm.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/optimization_algorithm_factory.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/optimization_algorithm_dogleg.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/matrix_structure.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/hyper_graph_action.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/optimization_algorithm_with_hessian.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_multi_edge.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/optimizable_graph.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/block_solver.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_vertex.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_multi_edge.hpp
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_vertex.hpp
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_unary_edge.hpp
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/sparse_block_matrix.hpp
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/base_binary_edge.hpp
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/core/block_solver.hpp
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_cli.so
-- Up-to-date: /home/jack/Code/g2ofork/install/bin/g2o
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_cli/g2o_cli_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_cli/dl_wrapper.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_cli/g2o_common.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_cli/output_helper.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_hierarchical/edge_types_cost_function.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_hierarchical/backbone_tree_action.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_hierarchical/star.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_hierarchical/edge_creator.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_hierarchical/simple_star_ops.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_hierarchical/edge_labeler.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/apps/g2o_hierarchical/g2o_hierarchical_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_data.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/raw_laser.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/vertex_tag.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/g2o_types_data_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/laser_parameters.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/vertex_ellipse.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/robot_data.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/data_queue.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/types_data.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/data/robot_laser.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_slam2d.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_pointxy_bearing.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/types_slam2d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_prior.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/g2o_types_slam2d_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_xyprior.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/parameter_se2_offset.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_pointxy.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_lotsofxy.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/vertex_point_xy.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_pointxy.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/se2.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_pointxy_calib.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/vertex_se2.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_offset.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_pointxy_offset.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d/edge_se2_twopointsxy.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_slam3d.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/vertex_se3.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/types_slam3d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/parameter_camera.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/parameter_se3_offset.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/isometry3d_gradients.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/edge_se3_pointxyz_depth.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/dquat2mat.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/edge_se3_pointxyz_disparity.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/edge_se3_prior.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/edge_se3_pointxyz.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/parameter_stereo_camera.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/isometry3d_mappings.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/se3quat.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/edge_pointxyz.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/edge_se3.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/edge_se3_offset.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/se3_ops.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/vertex_pointxyz.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/g2o_types_slam3d_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/edge_se3_lotsofxyz.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d/se3_ops.hpp
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_sba.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sba/sbacam.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sba/types_six_dof_expmap.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sba/types_sba.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sba/g2o_types_sba_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_sim3.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sim3/types_seven_dof_expmap.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sim3/sim3.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_icp.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/icp/g2o_types_icp_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/icp/types_icp.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_sclam2d.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sclam2d/edge_se2_odom_differential_calib.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sclam2d/g2o_types_sclam2d_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sclam2d/odometry_measurement.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sclam2d/vertex_odom_differential_params.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sclam2d/types_sclam2d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/sclam2d/edge_se2_sensor_calib.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_slam2d_addons.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/edge_line2d_pointxy.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/edge_se2_segment2d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/edge_line2d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/edge_se2_line2d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/edge_se2_segment2d_pointLine.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/line_2d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/g2o_types_slam2d_addons_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/edge_se2_segment2d_line.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/vertex_line2d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/types_slam2d_addons.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam2d_addons/vertex_segment2d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_types_slam3d_addons.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/g2o_types_slam3d_addons_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/edge_se3_line.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/types_slam3d_addons.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/edge_se3_plane_calib.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/edge_se3_calib.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/edge_plane.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/edge_se3_euler.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/vertex_se3_euler.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/vertex_line3d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/vertex_plane.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/plane3d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/types/slam3d_addons/line3d.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_solver_pcg.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/pcg/linear_solver_pcg.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/pcg/linear_solver_pcg.hpp
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_solver_dense.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/dense/linear_solver_dense.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_solver_structure_only.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/structure_only/structure_only_solver.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_solver_csparse.so
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_csparse_extension.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/csparse/linear_solver_csparse.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/csparse/g2o_csparse_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/csparse/g2o_csparse_extension_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/csparse/csparse_helper.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_solver_slam2d_linear.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/slam2d_linear/solver_slam2d_linear.h
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/slam2d_linear/g2o_slam2d_linear_api.h
-- Up-to-date: /home/jack/Code/g2ofork/install/lib/libg2o_solver_eigen.so
-- Up-to-date: /home/jack/Code/g2ofork/install/include/g2o/solvers/eigen/linear_solver_eigen.h
`

cvflann problem in rgbdslamv2

I successfully installed rgbdslam on ROS hydro.When I launch the rgbdslam.launch, it can identify some features with blue circle around , but after hitting Space or Enter key that error appears.
I got this error log:
[ INFO] [1415264850.473182552]: No change to renderer skip (1).
[ INFO] [1415264850.473317810]: 1 Keyframes: 0,
[ INFO] [1415264850.565500255]: Siftgpu Feature Descriptors size: 600 x 128
[ INFO] [1415264850.565544782]: Feature Count of Node: 600
[ INFO] [1415264850.569676183]: Odometry Delta: Translation 0 0 0
[ INFO] [1415264850.569757595]: Odometry Delta: Rotation 0 0 0 1
[ INFO] [1415264850.569799697]: No Valid Odometry, using identity
[ INFO] [1415264850.569892681]: Node ID's to compare with candidate for node 1. Sequential: 0
[ INFO] [1415264850.569947773]: Nodes to compare: 0
[ INFO] [1415264850.569976833]: Running node comparisons in parallel in 7 (of 8) available threads
rgbdslam: /tmp/buildd/ros-hydro-opencv2-2.4.9-2precise-20140819-1808/modules/flann/include/opencv2/flann/kdtree_index.h:458: void cvflann::KDTreeIndex::getNeighbors(cvflann::ResultSet&, const ElementType_, int, float) [with Distance = cvflann::L2, typename Distance::ResultType = float, cvflann::KDTreeIndex::ElementType = float]: Assertion `result.full()' failed.
================================================================================REQUIRED process [rgbdslam-1] has died!
process has died [pid 21345, exit code -6, cmd /home/ycb13/catkin_ws/devel/lib/rgbdslam/rgbdslam __name:=rgbdslam _log:=/home/ycb13/.ros/log/182187ce-658e-11e4-9c34-3417ebd919cc/rgbdslam-1.log].
log file: /home/ycb13/.ros/log/182187ce-658e-11e4-9c34-3417ebd919cc/rgbdslam-1
.log

Initiating shutdown!

[rgbdslam-1] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done
I don`t know whats the problem is , I appreciate if you could Help me .
In advance thank you!

Trajectory estimation test failed

I use the vision group dateset to test the trajectory estimation. I run the test as rosrun rgbdslam run_tests.sh. The program runs well, however, in the end, an error prompt,

16:41:40 Finished processing rgbd_dataset_freiburg3_long_office_household
rgbd_dataset_freiburg3_long_office_household ... Couldn't find matching timestamp pairs between groundtruth and estimated trajectory! Did you choose the correct sequence?
Evaluation Failed

which I checked is because of the estimated trajectory file is empty. I don't konw how to correct this.

Installation instruction errors in kinetic branch

There are a few typos in the installation instructions for kinetic.

  1. Need to clone the c++03 branch of g2o
  2. Put clone in the correct folder (i.e., g2ofork in the below example)
  3. Actually clone rgbslam instead of g2o twice
  4. Remove ros-kinetic-libg2o

This should circumvent the qt/Boost parsing issues as well as g2o needing c++11. This works on ROS Kinetic and Ubuntu 16.04. Here's the updated version, changes in bold

#Prepare Workspace
source /opt/ros/kinetic/setup.bash
mkdir -p ~/rgbdslam_catkin_ws/src
cd ~/rgbdslam_catkin_ws/src
catkin_init_workspace
cd ~/rgbdslam_catkin_ws/
catkin_make
source devel/setup.bash

#Get and build g2o fork
mkdir -p ~/g2ofork
git clone -b c++03 https://github.com/felixendres/g2o.git g2ofork
mkdir -p ~/g2ofork/build
cd ~/g2ofork/build
cmake .. -DCMAKE_INSTALL_PREFIX=~/g2ofork/install -DG2O_BUILD_EXAMPLES=OFF
make -j2 install

#Get and build rgbdslam_v2
export G2O_DIR=~/g2ofork/install
cd ~/rgbdslam_catkin_ws/src
git clone -b kinetic https://github.com/felixendres/rgbdslam_v2.git
cd ~/rgbdslam_catkin_ws/
rosdep update
rosdep install rgbdslam
sudo apt-get purge ros-kinetic-libg2o
catkin_make 

Rgb color doesn't match point cloud

Hello,
I am using the rgbdslam_v2 with a Kinect_v2 on ROS indigo (iai_kinect2 +freenect) to create a point cloud from an object (moving on a circular path around the object, Kinect attached to an universal robot arm). But somehow the rgb image doesn't match the point cloud, it seems that there is a kind of offset between them. Distance btw. object and sensor is around 0,6m. Does anybody know what could be the reason for this behavior?
Thank you in advance!
Hannes

Update: It was a simple problem of calibration. There was a error during calibration, so I did it again and it works fine now. Thank you for this nice slam algorithm!

run with rosbag from TUM,stucked after 2 frames

I edited rgbdslam.launch ,changed topics to the topics of rosbag . rosbag play *.bag,and in a new terminal
I launch rgbdslam.launch , it stucked after processing 2 frames

screenshot from 2017-05-22 09-34-14
is it because that the rosbag moving too fast for rgbdslam?
what'more ,does it support kinect2?

rgbgslam_v2 (indigo) octomap geration of benchmark dataset

I download a number of data from the link:

http://vision.in.tum.de/data/datasets/rgbd-dataset

However, when I run generate_color_octomap_from_estimate.sh in rgbd_benchmark, I encountered the following error:
...........................................
...........................................
...........................................
[color_octomap_mapping_from_pcd.launch] is neither a launch file in package [octomap_server] nor is [octomap_server] a launch file name
The traceback for the exception was written to the log file
paul@paul-HP-Compaq-Elite-8300-SFF:~/rgbdslam_catkin_ws/src/rgbdslam_v2-indigo/rgbd_benchmark$ [rosout-1] killing on exit
[master] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

Any ideas? Thanks!

ubuntu14.04+indigo compile errors

Hi, I met some problem when compile rgbdslam_v2
env: ubuntu14.04+indigo

I had change cv:: -> std::, solve some errors.

but there are new errors happen.

[ 39%] [ 40%] [ 41%] Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/features.cpp.o
Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/aorb.cpp.o
Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/feature_adjuster.cpp.o
Current branch orbbec_ros is up to date.
[ 42%] Performing configure step for 'astra_openni2'
no need to configure
[ 43%] Performing build step for 'astra_openni2'
make[3]: warning: jobserver unavailable: using -j1. Add `+' to parent make rule.
[ 44%] Performing install step for 'astra_openni2'
[ 45%] Completed 'astra_openni2'
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp: In member function ‘virtual void DetectorAdjuster::detectImpl(const cv::Mat&, std::vectorcv::KeyPoint&, const cv::Mat&) const’:
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:91:49: error: cannot allocate an object of abstract type ‘cv::FastFeatureDetector’
detector = new FastFeatureDetector(thresh_);
^
In file included from /usr/local/include/opencv2/features2d/features2d.hpp:48:0,
from /home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.h:3,
from /home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:43:
/usr/local/include/opencv2/features2d.hpp:419:20: note: because the following virtual functions are pure within ‘cv::FastFeatureDetector’:
class CV_EXPORTS_W FastFeatureDetector : public Feature2D
^
/usr/local/include/opencv2/features2d.hpp:432:26: note: virtual void cv::FastFeatureDetector::setThreshold(int)
CV_WRAP virtual void setThreshold(int threshold) = 0;
^
/usr/local/include/opencv2/features2d.hpp:433:25: note: virtual int cv::FastFeatureDetector::getThreshold() const
CV_WRAP virtual int getThreshold() const=0;
^
/usr/local/include/opencv2/features2d.hpp:435:26: note: virtual void cv::FastFeatureDetector::setNonmaxSuppression(bool)
CV_WRAP virtual void setNonmaxSuppression(bool f) = 0;
^
/usr/local/include/opencv2/features2d.hpp:436:26: note: virtual bool cv::FastFeatureDetector::getNonmaxSuppression() const
CV_WRAP virtual bool getNonmaxSuppression() const = 0;
^
/usr/local/include/opencv2/features2d.hpp:438:26: note: virtual void cv::FastFeatureDetector::setType(int)
CV_WRAP virtual void setType(int type) = 0;
^
/usr/local/include/opencv2/features2d.hpp:439:25: note: virtual int cv::FastFeatureDetector::getType() const
CV_WRAP virtual int getType() const = 0;
^
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:116:7: error: ‘create’ is not a member of ‘cv::FeatureDetector {aka cv::Feature2D}’
FeatureDetector::create(detector_name_);
^
[ 48%] /home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp: At global scope:
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:152:5: error: ‘AdjusterAdapter’ was not declared in this scope
Ptr DetectorAdjuster::clone() const
^
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:152:20: error: template argument 1 is invalid
Ptr DetectorAdjuster::clone() const
^
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:152:22: error: prototype for ‘int DetectorAdjuster::clone() const’ does not match any in class ‘DetectorAdjuster’
Ptr DetectorAdjuster::clone() const
^
In file included from /home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:43:0:
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.h:21:39: error: candidate is: virtual cv::Ptr DetectorAdjuster::clone() const
virtual cv::Ptr clone() const;
^
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:162:77: error: ‘AdjusterAdapter’ was not declared in this scope
VideoDynamicAdaptedFeatureDetector::VideoDynamicAdaptedFeatureDetector(Ptr a,
^
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:162:92: error: template argument 1 is invalid
VideoDynamicAdaptedFeatureDetector::VideoDynamicAdaptedFeatureDetector(Ptr a,
^
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:162:2: error: prototype for ‘VideoDynamicAdaptedFeatureDetector::VideoDynamicAdaptedFeatureDetector(int, int, int, int)’ does not match any in class ‘VideoDynamicAdaptedFeatureDetector’
VideoDynamicAdaptedFeatureDetector::VideoDynamicAdaptedFeatureDetector(Ptr a,
^
In file included from /home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:43:0:
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.h:73:5: error: candidates are: VideoDynamicAdaptedFeatureDetector::VideoDynamicAdaptedFeatureDetector(const VideoDynamicAdaptedFeatureDetector&)
VideoDynamicAdaptedFeatureDetector(const VideoDynamicAdaptedFeatureDetector&);
^
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.h:63:6: error: VideoDynamicAdaptedFeatureDetector::VideoDynamicAdaptedFeatureDetector(cv::Ptr, int, int, int)
VideoDynamicAdaptedFeatureDetector( cv::Ptr adjuster, int min_features=400, int max_features=500, int max_iters=5);
^
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp: In member function ‘virtual bool VideoDynamicAdaptedFeatureDetector::empty() const’:
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:179:37: error: ‘class DetectorAdjuster’ has no member named ‘empty’
return !adjuster_ || adjuster_->empty();
^
Built target astra_openni2
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp: In member function ‘virtual void VideoDynamicAdaptedFeatureDetector::detectImpl(const cv::Mat&, std::vectorcv::KeyPoint&, const cv::Mat&) const’:
/home/cwc/code/catkin_ws/src/rgbdslam_v2-indigo/src/feature_adjuster.cpp:203:20: error: ‘class DetectorAdjuster’ has no member named ‘detect’
adjuster_->detect(_image, keypoints,_mask);

Problem of Compiling rgdslam_v2 hydro 12.04

Hi all,

I'm trying to compile the code in ubuntu 12.04 with hydro ROS. However, the compilation is failed and shown the errors as follows:

make[3]: warning: jobserver unavailable: using -j1. Add `+' to parent make rule.
src/SiftGPU/CuTexImage.cpp:33:18: fatal error: cuda.h: No such file or directory
compilation terminated.
Linking CXX executable /home/jayden/rgbdslam_catkin_ws/devel/lib/rgbdslam/rgbdslam
make[3]: *** [build/CuTexImage.o] Error 1
make[2]: *** [rgbdslam_v2-hydro/external/siftgpu_prefix/src/siftgpu_proj-stamp/siftgpu_proj-build] Error 2
make[1]: *** [rgbdslam_v2-hydro/external/CMakeFiles/siftgpu_proj.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
/usr/bin/ld: cannot find -lsiftgpu
collect2: ld returned 1 exit status
make[2]: *** [/home/jayden/rgbdslam_catkin_ws/devel/lib/rgbdslam/rgbdslam] Error 1
make[1]: *** [rgbdslam_v2-hydro/CMakeFiles/rgbdslam.dir/all] Error 2
make: *** [all] Error 2
Invoking "make" failed

Could you please give me some hint on how to solve this problem.

Thank you in advanced.

Regards,
Jayden

How to visualize octomap in rviz?

Hello,
I have experienced this package,It is very cool.But when I have tried to run octomap from Kinect data using rgbdslam, I can't visualize anything in rviz.
My setup:
ROS hydro on Ubuntu LTS12.04.
rgbdslam_v2 downloaded ,compiled and installed.
octomap and octomap_mapping installed

The terminal is:

roscore
roslaunch openni_launch openni.launch
roslaunch rgbdslam rgbdslam.launch
roslaunch rgbdslam octomap_server.launch
Some things I've done:
I select that the value of "Fixed frame" is "/map" ,At the same time ,I added MarkerArray /occupied_cells_vis_array.
I also tried to run: rostopic echo /batch/clouds ,The terminal display is:
WARNING: topic [/batch/clouds] does not appear to be published yet

Then I modified src/parameter_sever.cpp
from "addOption("batch_processing", static_cast (false), " to addOption("batch_processing", static_cast (true);
But there is nothing in rviz.
Also,When I added "pointcloud",I have no anything .

I want to visualize the octomap in rviz when it is connect kinect,Can you help me solve this problem ?In advance thank you!

About using SiftGPU with cuda

Hi,
I found that if I want to use siftgpu with cuda, I have to comment the following line in siftgpu's makefile
siftgpu_enable_cuda = 0 (line 17)
but the doc did not say that. Is there something wrong for my steps? or you just forget to comment it? :)

suspected bug in landmark.cpp

Close to the end of the GraphManager::updateLandmarks(...) function definition in "landmark.cpp", the line "landmarks.erase(landmarks.begin()+lm_id_new)" seems to be a bug. This line tries to remove a landmark out of the vector "landmarks" since it has been merged to another landmark (i.e., lm_1). However, removing it from the vector will cause all elements following it to be shifted towards the vector head. As a result, their id's (id is a class field) would not correspond to their real position/index in the vector. Later on when querying a landmark by its id, e.g. landmarks[lm->id], the result will be wrong.

Aparently, all elements in vector "landmarks" should update their id's whenever they are shifted due to reasons like erasing some elements, though this would be kind of awkward. My thought is to avoid explicitly erasing a landmark from the vector; instead, add a bool field in the "Landmark" class, say "deleted", to indicated whether a landmark has been deleted or not.
Please correct me if I'm wrong.

siftgpu library error

Dear sir

I am trying to catkin_make this package on my own Ubuntu14.04.
But here is something error.

[ 73%] Built target rgbdslam_gencpp
Linking CXX executable /home/ros/catkin_ws/devel/lib/rgbdslam/rgbdslam
/usr/bin/ld: cannot find -lsiftgpu
collect2: error: ld returned 1 exit status
make[2]: *** [/home/ros/catkin_ws/devel/lib/rgbdslam/rgbdslam] Error 1
make[1]: *** [rgbdslam_v2/CMakeFiles/rgbdslam.dir/all] Error 2
make: *** [all] Error 2
Invoking "make -j1 -l1" failed
ros@ros-VirtualBox:~/catkin_ws$

And I find this sentence in README.md,"To build RGBDSLAMv2 go to your catkin workspace and execute "catkin_make". If you get an error about the missing siftgpu library, execute "catkin_make" again."
I don't understand and it doesn't work.

Please give me a hand.
Thank a lot!!
Alyson

Online Octomapping Causing RGBDSLAM Application Rrash

Issue

When Online Octomapping is enabled at app start, the app crashes on image process. The workaround is to launch RGBDSLAM without drivers and disable Online Octomapping. Online Octomapping works fine if the user waits to enable it until after some point cloud information has been processed first.

Setup

$ lsb_release -a
No LSB modules are available.
Distributor ID: Ubuntu
Description:    Ubuntu 14.04.3 LTS
Release:    14.04
Codename:   trusty

$ rosversion -d
indigo

App Init

terminal A
$ roslaunch freenect_launch freenect.launch

terminal B
$ roslaunch rgbdslam rgbdslam.launch

Steps to Reproduce

  • Start Application
  • Begin processing
  • Enable Online Octomapping
  • Close application
  • Start application
  • Application crashes immediately

Crash Info

from terminal B

$ roslaunch rgbdslam rgbdslam.launch 
... logging to /home/jackson/.ros/log/b64242c4-d05c-11e5-aae8-080027c9e22a/roslaunch-jackson-VirtualBox-4188.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://jackson-VirtualBox:56952/

SUMMARY
========

PARAMETERS
 * /rgbdslam/config/backend_solver: pcg
 * /rgbdslam/config/cloud_creation_skip_step: 2
 * /rgbdslam/config/cloud_display_type: POINTS
 * /rgbdslam/config/detector_grid_resolution: 3
 * /rgbdslam/config/feature_detector_type: ORB
 * /rgbdslam/config/feature_extractor_type: ORB
 * /rgbdslam/config/max_keypoints: 600
 * /rgbdslam/config/max_matches: 300
 * /rgbdslam/config/min_sampled_candidates: 4
 * /rgbdslam/config/neighbor_candidates: 4
 * /rgbdslam/config/optimizer_skip_step: 1
 * /rgbdslam/config/pose_relative_to: largest_loop
 * /rgbdslam/config/predecessor_candidates: 4
 * /rgbdslam/config/ransac_iterations: 100
 * /rgbdslam/config/topic_image_depth: /camera/depth_reg...
 * /rgbdslam/config/topic_image_mono: /camera/rgb/image...
 * /rgbdslam/config/topic_points: 
 * /rosdistro: indigo
 * /rosversion: 1.11.16

NODES
  /
    rgbdslam (rgbdslam/rgbdslam)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[rgbdslam-1]: started with pid [4206]
Initializing Node...
[ INFO] [1455153268.195273441]: Connected to roscore
[ INFO] [1455153268.383877753]: Using ORB keypoint detector.
[ INFO] [1455153268.384054435]: Using gridded keypoint detector with 3x3 cells, keeping 900 keypoints in total.
[ INFO] [1455153268.384210123]: Using adjusted keypoint detector with 5 maximum iterations, keeping the number of keypoints between 67 and 100
[ INFO] [1455153268.413364198]: Listening to /camera/rgb/image_color and /camera/depth_registered/sw_registered/image_rect_raw
pci id for fd 41: 80ee:beef, driver (null)
OpenGL Warning: glFlushVertexArrayRangeNV not found in mesa table
OpenGL Warning: glVertexArrayRangeNV not found in mesa table
OpenGL Warning: glCombinerInputNV not found in mesa table
OpenGL Warning: glCombinerOutputNV not found in mesa table
OpenGL Warning: glCombinerParameterfNV not found in mesa table
OpenGL Warning: glCombinerParameterfvNV not found in mesa table
OpenGL Warning: glCombinerParameteriNV not found in mesa table
OpenGL Warning: glCombinerParameterivNV not found in mesa table
OpenGL Warning: glFinalCombinerInputNV not found in mesa table
OpenGL Warning: glGetCombinerInputParameterfvNV not found in mesa table
OpenGL Warning: glGetCombinerInputParameterivNV not found in mesa table
OpenGL Warning: glGetCombinerOutputParameterfvNV not found in mesa table
OpenGL Warning: glGetCombinerOutputParameterivNV not found in mesa table
OpenGL Warning: glGetFinalCombinerInputParameterfvNV not found in mesa table
OpenGL Warning: glGetFinalCombinerInputParameterivNV not found in mesa table
OpenGL Warning: glDeleteFencesNV not found in mesa table
OpenGL Warning: glFinishFenceNV not found in mesa table
OpenGL Warning: glGenFencesNV not found in mesa table
OpenGL Warning: glGetFenceivNV not found in mesa table
OpenGL Warning: glIsFenceNV not found in mesa table
OpenGL Warning: glSetFenceNV not found in mesa table
OpenGL Warning: glTestFenceNV not found in mesa table
libGL error: core dri or dri2 extension not found
libGL error: failed to load driver: vboxvideo
X Error: BadDrawable (invalid Pixmap or Window parameter) 9
  Major opcode: 14 (X_GetGeometry)
  Resource id:  0x440000e
[ WARN] [1455153268.995914788]: First RGBD-Data Received
[ INFO] [1455153268.996155739]: Encoding: bgr8
[ INFO] [1455153269.083485905]: Feature 2d size: 563, 3D: 563
[ INFO] [1455153269.083785553]: Keypoints: 563
[ INFO] [1455153269.083975101]: Feature Count of Node:  563
[ WARN] [1455153269.095225182]: "openni_rgb_optical_frame" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1455153269.095646395]: Using Standard kinect /openni_camera -> /openni_rgb_optical_frame as transformation (This message is throttled to 1 per 5 seconds)
[ INFO] [1455153269.109451891]: Encoding: bgr8
[ INFO] [1455153269.114531126]: Setting Renderable
[ INFO] [1455153269.115756613]: Ground Truth Transform for First Node: Translation 0 0 0
[ INFO] [1455153269.115887763]: Ground Truth Transform for First Node: Rotation 0 0 0 1
[ INFO] [1455153269.116005412]: Adding initial node with id 0 and seq 0, v_id: 0
[ INFO] [1455153269.148527475]: No change to renderer skip (1).
[ INFO] [1455153269.148858803]: 1 Keyframes: 0, 
[ WARN] [1455153269.189030270]: Loop Closures: 0, Sequential Edges: 0
[ WARN] [1455153269.189261837]: Starting Optimization
rgbdslam: /tmp/binarydeb/ros-indigo-libg2o-2014.02.18/g2o/core/sparse_optimizer.cpp:271: virtual bool g2o::SparseOptimizer::initializeOptimization(g2o::HyperGraph::EdgeSet&): Assertion `workspaceAllocated && "Error while allocating memory for the Jacobians"' failed.
================================================================================REQUIRED process [rgbdslam-1] has died!
process has died [pid 4206, exit code -6, cmd /home/jackson/rgbdslam_catkin_ws/devel/lib/rgbdslam/rgbdslam __name:=rgbdslam __log:=/home/jackson/.ros/log/b64242c4-d05c-11e5-aae8-080027c9e22a/rgbdslam-1.log].
log file: /home/jackson/.ros/log/b64242c4-d05c-11e5-aae8-080027c9e22a/rgbdslam-1*.log
Initiating shutdown!
================================================================================
[rgbdslam-1] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

Parse error at "BOOST_JOIN"

when compiling rgbdslam_v2, get the following error:

$ catkin_make
Base path: /home/akos/src/ros/src/catkin_ws
Source space: /home/akos/src/ros/src/catkin_ws/src
Build space: /home/akos/src/ros/src/catkin_ws/build
Devel space: /home/akos/src/ros/src/catkin_ws/devel
Install space: /home/akos/src/ros/src/catkin_ws/install
####
#### Running command: "make cmake_check_build_system" in "/home/akos/src/ros/src/catkin_ws/build"
####
####
#### Running command: "make -j8 -l8" in "/home/akos/src/ros/src/catkin_ws/build"
####
[  1%] Built target pico_flexx_driver_gencfg
[  2%] Performing build step for 'siftgpu_proj'
make[3]: warning: jobserver unavailable: using -j1.  Add '+' to parent make rule.
[  2%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_s
[  2%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui
[  2%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_f
[  2%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_b
[  5%] Built target pico_flexx_nodelet
[  8%] Built target pico_flexx_driver
[ 14%] Built target rgbdslam_generate_messages_lisp
[ 22%] Built target rgbdslam_generate_messages_py
[ 28%] Built target rgbdslam_generate_messages_cpp
[ 28%] Built target rgbdslam_generate_messages
[ 28%] Built target rgbdslam_gencpp
[ 31%] Generating src/moc_glviewer.cxx
[ 32%] Generating src/moc_ros_service_ui.cxx
[ 34%] Generating src/moc_openni_listener.cxx
[ 35%] Generating src/moc_qt_gui.cxx
[ 37%] Generating src/moc_graph_manager.cxx
[ 31%] Generating src/moc_qtros.cxx
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2/CMakeFiles/rgbdslam.dir/build.make:62: recipe for target 'rgbdslam_v2/src/moc_qtros.cxx' failed
make[2]: *** [rgbdslam_v2/src/moc_qtros.cxx] Error 1
make[2]: *** Waiting for unfinished jobs....
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2/CMakeFiles/rgbdslam.dir/build.make:87: recipe for target 'rgbdslam_v2/src/moc_ros_service_ui.cxx' failed
make[2]: *** [rgbdslam_v2/src/moc_ros_service_ui.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2/CMakeFiles/rgbdslam.dir/build.make:82: recipe for target 'rgbdslam_v2/src/moc_glviewer.cxx' failed
make[2]: *** [rgbdslam_v2/src/moc_glviewer.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2/CMakeFiles/rgbdslam.dir/build.make:72: recipe for target 'rgbdslam_v2/src/moc_qt_gui.cxx' failed
make[2]: *** [rgbdslam_v2/src/moc_qt_gui.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2/CMakeFiles/rgbdslam.dir/build.make:67: recipe for target 'rgbdslam_v2/src/moc_openni_listener.cxx' failed
make[2]: *** [rgbdslam_v2/src/moc_openni_listener.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2/CMakeFiles/rgbdslam.dir/build.make:77: recipe for target 'rgbdslam_v2/src/moc_graph_manager.cxx' failed
make[2]: *** [rgbdslam_v2/src/moc_graph_manager.cxx] Error 1
CMakeFiles/Makefile2:1355: recipe for target 'rgbdslam_v2/CMakeFiles/rgbdslam.dir/all' failed
make[1]: *** [rgbdslam_v2/CMakeFiles/rgbdslam.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
[ 38%] No install step for 'siftgpu_proj'
[ 40%] Completed 'siftgpu_proj'
[ 47%] Built target siftgpu_proj
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

this is on Ubuntu 16.04 64 bit

rosdep install rgbdslam error in indigo

My ros version is indigo. And my rosdep version is newest(0.11.5-1).

  1. I do the command "rosdep update" and it finished with no error.
  2. I do the command "rosdep install rgbdslam", and then a error is displayed.
    the details is below:

w@w-Aspire-VN7-791G:/catkin_ws$ rosdep update
reading in sources list data from /etc/ros/rosdep/sources.list.d
Hit https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/osx-homebrew.yaml
Hit https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/base.yaml
Hit https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/python.yaml
Hit https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/ruby.yaml
Hit https://raw.githubusercontent.com/ros/rosdistro/master/releases/fuerte.yaml
Query rosdistro index https://raw.githubusercontent.com/ros/rosdistro/master/index.yaml
Add distro "groovy"
Add distro "hydro"
Add distro "indigo"
Add distro "jade"
Add distro "kinetic"
updated cache in /home/wangke/.ros/rosdep/sources.cache
w@w-Aspire-VN7-791G:
/catkin_ws$ rosdep install rgbdslam

ERROR: Rosdep cannot find all required resources to answer your query
Missing resource rgbdslam
ROS path [0]=/opt/ros/indigo/share/ros
ROS path [1]=/opt/ros/indigo/share
ROS path [2]=/opt/ros/indigo/stacks

No devices found (kinect works w freenect-glview)

rgbdslam worked fine on precise. I upgraded to trusty, installed ros indigo, and have everything working fine except that the camera isn't detected. You can see the output below.

$ roslaunch rgbdslam openni+rgbdslam.launch 
... logging to /home/jackson/.ros/log/41df8eaa-c913-11e5-be97-b886879b31ee/roslaunch-jackson-HP-Pavilion-Notebook-22023.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://jackson-HP-Pavilion-Notebook:52593/

SUMMARY
========

PARAMETERS
 * /camera/camera_nodelet_manager/num_worker_threads: 4
 * /camera/depth_rectify_depth/interpolation: 0
 * /camera/depth_registered_rectify_depth/interpolation: 0
 * /camera/disparity_depth/max_range: 4.0
 * /camera/disparity_depth/min_range: 0.5
 * /camera/disparity_registered_hw/max_range: 4.0
 * /camera/disparity_registered_hw/min_range: 0.5
 * /camera/disparity_registered_sw/max_range: 4.0
 * /camera/disparity_registered_sw/min_range: 0.5
 * /camera/driver/depth_camera_info_url: 
 * /camera/driver/depth_frame_id: camera_depth_opti...
 * /camera/driver/depth_registration: False
 * /camera/driver/device_id: #1
 * /camera/driver/rgb_camera_info_url: 
 * /camera/driver/rgb_frame_id: camera_rgb_optica...
 * /rgbdslam/config/backend_solver: pcg
 * /rgbdslam/config/cloud_creation_skip_step: 2
 * /rgbdslam/config/cloud_display_type: POINTS
 * /rgbdslam/config/detector_grid_resolution: 3
 * /rgbdslam/config/feature_detector_type: ORB
 * /rgbdslam/config/feature_extractor_type: ORB
 * /rgbdslam/config/max_keypoints: 600
 * /rgbdslam/config/max_matches: 300
 * /rgbdslam/config/min_sampled_candidates: 4
 * /rgbdslam/config/neighbor_candidates: 4
 * /rgbdslam/config/optimizer_skip_step: 1
 * /rgbdslam/config/pose_relative_to: largest_loop
 * /rgbdslam/config/predecessor_candidates: 4
 * /rgbdslam/config/ransac_iterations: 100
 * /rgbdslam/config/topic_image_depth: /camera/depth_reg...
 * /rgbdslam/config/topic_image_mono: /camera/rgb/image...
 * /rosdistro: indigo
 * /rosversion: 1.11.16

NODES
  /camera/
    camera_nodelet_manager (nodelet/nodelet)
    debayer (nodelet/nodelet)
    depth_metric (nodelet/nodelet)
    depth_metric_rect (nodelet/nodelet)
    depth_points (nodelet/nodelet)
    depth_rectify_depth (nodelet/nodelet)
    depth_registered_hw_metric_rect (nodelet/nodelet)
    depth_registered_metric (nodelet/nodelet)
    depth_registered_rectify_depth (nodelet/nodelet)
    depth_registered_sw_metric_rect (nodelet/nodelet)
    disparity_depth (nodelet/nodelet)
    disparity_registered_hw (nodelet/nodelet)
    disparity_registered_sw (nodelet/nodelet)
    driver (nodelet/nodelet)
    points_xyzrgb_hw_registered (nodelet/nodelet)
    points_xyzrgb_sw_registered (nodelet/nodelet)
    rectify_color (nodelet/nodelet)
    rectify_ir (nodelet/nodelet)
    rectify_mono (nodelet/nodelet)
    register_depth_rgb (nodelet/nodelet)
  /
    camera_base_link (tf/static_transform_publisher)
    camera_base_link1 (tf/static_transform_publisher)
    camera_base_link2 (tf/static_transform_publisher)
    camera_base_link3 (tf/static_transform_publisher)
    rgbdslam (rgbdslam/rgbdslam)

auto-starting new master
process[master]: started with pid [22036]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 41df8eaa-c913-11e5-be97-b886879b31ee
process[rosout-1]: started with pid [22049]
started core service [/rosout]
process[camera/camera_nodelet_manager-2]: started with pid [22066]
process[camera/driver-3]: started with pid [22067]
process[camera/debayer-4]: started with pid [22068]
process[camera/rectify_mono-5]: started with pid [22069]
process[camera/rectify_color-6]: started with pid [22079]
process[camera/rectify_ir-7]: started with pid [22091]
process[camera/depth_rectify_depth-8]: started with pid [22103]
[ INFO] [1454352026.660961647]: Initializing nodelet with 4 worker threads.
process[camera/depth_metric_rect-9]: started with pid [22117]
process[camera/depth_metric-10]: started with pid [22121]
process[camera/depth_points-11]: started with pid [22131]
process[camera/register_depth_rgb-12]: started with pid [22149]
process[camera/points_xyzrgb_sw_registered-13]: started with pid [22156]
process[camera/depth_registered_sw_metric_rect-14]: started with pid [22165]
process[camera/depth_registered_rectify_depth-15]: started with pid [22179]
process[camera/points_xyzrgb_hw_registered-16]: started with pid [22200]
process[camera/depth_registered_hw_metric_rect-17]: started with pid [22208]
process[camera/depth_registered_metric-18]: started with pid [22217]
process[camera/disparity_depth-19]: started with pid [22233]
process[camera/disparity_registered_sw-20]: started with pid [22236]
[ INFO] [1454352027.005966191]: No devices connected.... waiting for devices to be connected
process[camera/disparity_registered_hw-21]: started with pid [22247]
process[camera_base_link-22]: started with pid [22253]
process[camera_base_link1-23]: started with pid [22261]
process[camera_base_link2-24]: started with pid [22274]
process[camera_base_link3-25]: started with pid [22286]
process[rgbdslam-26]: started with pid [22301]
Initializing Node...
[ INFO] [1454352027.363848742]: Connected to roscore
[ INFO] [1454352027.776813671]: Using ORB keypoint detector.
[ INFO] [1454352027.776982264]: Using gridded keypoint detector with 3x3 cells, keeping 900 keypoints in total.
[ INFO] [1454352027.777047903]: Using adjusted keypoint detector with 5 maximum iterations, keeping the number of keypoints between 67 and 100
[ INFO] [1454352027.840839128]: Listening to /camera/rgb/image_color and /camera/depth_registered/sw_registered/image_rect_raw
[ INFO] [1454352030.007229077]: No devices connected.... waiting for devices to be connected
[ INFO] [1454352033.008288294]: No devices connected.... waiting for devices to be connected
[ INFO] [1454352036.008989125]: No devices connected.... waiting for devices to be connected

The kinect is listed in lsusb

$ lsusb
Bus 002 Device 001: ID 1d6b:0003 Linux Foundation 3.0 root hub
Bus 001 Device 003: ID 05c8:0379 Cheng Uei Precision Industry Co., Ltd (Foxlink) 
Bus 001 Device 002: ID 05e3:0608 Genesys Logic, Inc. USB-2.0 4-Port HUB
Bus 001 Device 005: ID 148f:5370 Ralink Technology, Corp. RT5370 Wireless Adapter
Bus 001 Device 018: ID 045e:02ae Microsoft Corp. Xbox NUI Camera
Bus 001 Device 016: ID 045e:02b0 Microsoft Corp. Xbox NUI Motor
Bus 001 Device 017: ID 045e:02ad Microsoft Corp. Xbox NUI Audio
Bus 001 Device 015: ID 0409:005a NEC Corp. HighSpeed Hub
Bus 001 Device 001: ID 1d6b:0002 Linux Foundation 2.0 root hub

and the kinect works with the freenect library. What can I do to get the kinect working with rgbdslam w indigo?

Compiling SiftGPU: gcc version for nvcc

nvcc is needed to compile SiftGPU, but the gcc version for nvcc must be lower than 4.8. However the default gcc version is usually higher than 4.8 in some Ubuntu versions.
Changing the default gcc is not good and need root permission. I used the patch command of ExternalProject to change the line in the SiftGPU makefile to force it using appropriate gcc version for nvcc. But this needs additional patch file and maybe cause some problem when the author of SiftGPU modifies the makefile of SiftGPU.
Is there better way to change the gcc for nvcc, like setting some environment variable in the CMakeLists.txt of the project?

catkin_make error

When I run catkin_make in catkin_ws I get the following error message:

/home/ubuntu/catkin_ws/src/rgbdslam_v2-indigo/src/main.cpp: In function 'int main(int, char*)':
/home/ubuntu/catkin_ws/src/rgbdslam_v2-indigo/src/main.cpp:134:10: error: 'class QApplication' has no member named 'type'
if (app.type() == QApplication::GuiClient){
^
/home/ubuntu/catkin_ws/src/rgbdslam_v2-indigo/src/main.cpp:134:20: error: 'GuiClient' is not a member of 'QApplication'
if (app.type() == QApplication::GuiClient){
^
make[2]: *
* [rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/main.o] Error 1
make[1]: *** [rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/all] Error 2
make: *** [all] Error 2
Invoking "make -j1 -l1" failed

What can I do to resolve it? Thank you!

Failed to process Kinect2 PointCloud Data

When I try to use with Kinect2, the below error appeared.
How can I solve this problem?

rgbdslam: /home/aginika/ros/indigo/src/rgbdslam/src/node.cpp:315: Node::Node(cv::Mat, cv::Ptr<cv::FeatureDetector>, cv::Ptr<cv::DescriptorExtractor>, 
pcl::PointCloud<pcl::PointXYZRGB>::Ptr, cv::Mat): Assertion `feature_locations_2d_.size() == feature_locations_3d_.size()' failed

the whole output when died is below

$ roslaunch test_rgbd rgbd_slam.launch 
... logging to /home/aginika/.ros/log/f2d484b2-8161-11e5-8579-40a8f055f334/roslaunch-remi-28623.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://remi:39140/

SUMMARY
========

PARAMETERS
 * /rgbdslam/config/backend_solver: pcg
 * /rgbdslam/config/base_frame_name: /kinect2_head_rgb...
 * /rgbdslam/config/camera_info_topic: /kinect2_head/qhd...
 * /rgbdslam/config/cloud_creation_skip_step: 2
 * /rgbdslam/config/cloud_display_type: POINTS
 * /rgbdslam/config/detector_grid_resolution: 3
 * /rgbdslam/config/feature_detector_type: ORB
 * /rgbdslam/config/feature_extractor_type: ORB
 * /rgbdslam/config/max_keypoints: 600
 * /rgbdslam/config/max_matches: 300
 * /rgbdslam/config/min_sampled_candidates: 4
 * /rgbdslam/config/neighbor_candidates: 4
 * /rgbdslam/config/optimizer_skip_step: 1
 * /rgbdslam/config/pose_relative_to: largest_loop
 * /rgbdslam/config/predecessor_candidates: 4
 * /rgbdslam/config/ransac_iterations: 100
 * /rgbdslam/config/topic_image_depth: /kinect2_head/qhd...
 * /rgbdslam/config/topic_image_mono: /kinect2_head/qhd...
 * /rgbdslam/config/topic_points: /kinect2_head/qhd...
 * /rosdistro: indigo
 * /rosversion: 1.11.13

NODES
  /
    rgbdslam (rgbdslam/rgbdslam)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[rgbdslam-1]: started with pid [28641]
Initializing Node...
[ INFO] [1446471301.608257969]: Connected to roscore
[ INFO] [1446471301.783546557]: Using ORB keypoint detector.
[ INFO] [1446471301.783630228]: Using gridded keypoint detector with 3x3 cells, keeping 900 keypoints in total.
[ INFO] [1446471301.783662565]: Using adjusted keypoint detector with 5 maximum iterations, keeping the number of keypoints between 67 and 100
[ INFO] [1446471301.799234774]: Listening to /kinect2_head/qhd/image_color_rect, /kinect2_head/qhd/image_depth_rect and /kinect2_head/qhd/points
[ WARN] [1446471302.504091410]: First RGBD-Data Received
[ INFO] [1446471302.525659170]: Construction of Node with ORB Features
[ INFO] [1446471302.549767034]: Feature 2d size: 850, 3D: 600
[ INFO] [1446471302.549834571]: Feature 2d size: 600, 3D: 600
rgbdslam: /home/aginika/ros/indigo/src/rgbdslam/src/node.cpp:315: Node::Node(cv::Mat, cv::Ptr<cv::FeatureDetector>, cv::Ptr<cv::DescriptorExtractor>, pcl::PointCloud<pcl::PointXYZRGB>::Ptr, cv::Mat): Assertion `feature_locations_2d_.size() == feature_locations_3d_.size()' failed.
================================================================================REQUIRED process [rgbdslam-1] has died!
process has died [pid 28641, exit code -6, cmd /home/aginika/ros/indigo/devel/lib/rgbdslam/rgbdslam __name:=rgbdslam __log:=/home/aginika/.ros/log/f2d484b2-8161-11e5-8579-40a8f055f334/rgbdslam-1.log].
log file: /home/aginika/.ros/log/f2d484b2-8161-11e5-8579-40a8f055f334/rgbdslam-1*.log
Initiating shutdown!
================================================================================
[rgbdslam-1] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

I am using iai_kinect2(https://github.com/code-iai/iai_kinect2) as a launcher of Kinect2 and I passed the topics to below launch file.
When I use this with xtion, it works well.

<launch>
  <node pkg="rgbdslam" type="rgbdslam" name="rgbdslam" cwd="node" required="true" output="screen">
    <!-- Input data settings-->
    <param name="config/topic_image_mono"              value="/kinect2_head/qhd/image_color_rect"/>
    <param name="config/topic_image_depth"             value="/kinect2_head/qhd/image_depth_rect"/>
    <param name="config/camera_info_topic"             value="/kinect2_head/qhd/camera_info"/>

    <param name="config/base_frame_name"             value="/kinect2_head_rgb_optical_frame"/>


    <!-- <param name="config/topic_image_mono"              value="/kinect_head/rgb/image_color"/>  -->
    <!-- <param name="config/topic_image_depth"             value="/kinect_head/depth_registered/hw_registered/image_rect_raw"/>  -->
    <!-- <param name="config/camera_info_topic"             value="/kinect_head/rgb/camera_info"/> -->

    <!-- <param name="config/base_frame_name"             value="/kinect_head_rgb_optical_frame"/> -->

    <param name="config/topic_points"                  value="/kinect2_head/qhd/points"/> <!--if empty, poincloud will be reconstructed from image and depth -->

    <!-- These are the default values of some important parameters -->
    <param name="config/feature_extractor_type"        value="ORB"/><!-- also available: SIFT, SIFTGPU, SURF, SURF128 (extended SURF), ORB. -->
    <param name="config/feature_detector_type"         value="ORB"/><!-- also available: SIFT, SURF, GFTT (good features to track), ORB. -->
    <param name="config/detector_grid_resolution"      value="3"/><!-- detect on a 3x3 grid (to spread ORB keypoints and parallelize SIFT and SURF) -->
    <param name="config/max_keypoints"                 value="600"/><!-- Extract no more than this many keypoints -->
    <param name="config/max_matches"                   value="300"/><!-- Keep the best n matches (important for ORB to set lower than max_keypoints) -->

    <param name="config/min_sampled_candidates"        value="4"/><!-- Frame-to-frame comparisons to random frames (big loop closures) -->
    <param name="config/predecessor_candidates"        value="4"/><!-- Frame-to-frame comparisons to sequential frames-->
    <param name="config/neighbor_candidates"           value="4"/><!-- Frame-to-frame comparisons to graph neighbor frames-->
    <param name="config/ransac_iterations"             value="100"/>
    <param name="config/cloud_creation_skip_step"      value="2"/><!-- subsample the images' pixels (in both, width and height), when creating the cloud (and therefore reduce memory consumption) -->


    <param name="config/cloud_display_type"            value="POINTS"/><!-- Show pointclouds as points (as opposed to TRIANGLE_STRIP) -->
    <param name="config/pose_relative_to"              value="largest_loop"/><!-- optimize only a subset of the graph: "largest_loop" = Everything from the earliest matched frame to the current one. Use "first" to optimize the full graph, "inaffected" to optimize only the fra\
mes that were matched (not those inbetween for loops) -->
    <param name="config/backend_solver"                value="pcg"/><!-- pcg is faster and good for continuous online optimization, cholmod and csparse are better for offline optimization (without good initial guess)-->
    <param name="config/optimizer_skip_step"           value="1"/><!-- optimize only every n-th frame -->
  </node>
</launch>

Each topic's height x width was all 540 x 960.

$ rostopic echo --noarr /kinect2_head/qhd/image_depth_rect
header: 
  seq: 228
  stamp: 
    secs: 1446471841
    nsecs: 146858714
  frame_id: kinect2_head_rgb_optical_frame
height: 540
width: 960
encoding: 16UC1
is_bigendian: 0
step: 1920

---

This is tf tree.
frames

Thank you.

No devices connected.... waiting for devices to be connected

when I run openni+rgbdslam , I connect kinect2 with the computer ,but it seems the camera is not turned on.
I m using ubuntu 16.04 , my computer has usb 3.0 ,and I have installed SenserKinect ~
even lsusb cannot find the kinect

Any one can help me?

CATKIN_MAKE error "make -j4 -l4" failed

I am witnessing problem in ubuntu 16.04LTS for rgbdslam_v2-hydro. Following the steps posted by Mr. felixendres. I cannot get past this problem showed below. kindly advise me on this matter. This is what is shown after i run the command, "catkin_make".

Base path: /home/adil/rgbdslam_catkin_ws
Source space: /home/adil/rgbdslam_catkin_ws/src
Build space: /home/adil/rgbdslam_catkin_ws/build
Devel space: /home/adil/rgbdslam_catkin_ws/devel
Install space: /home/adil/rgbdslam_catkin_ws/install

Running command: "make cmake_check_build_system" in "/home/adil/rgbdslam_catkin_ws/build"

Running command: "make -j4 -l4" in "/home/adil/rgbdslam_catkin_ws/build"

[ 0%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_s
[ 0%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_b
[ 0%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui_f
[ 0%] Built target _rgbdslam_generate_messages_check_deps_rgbdslam_ros_ui
[ 5%] Built target rgbdslam_generate_messages_lisp
[ 16%] Built target siftgpu_proj
[ 23%] Built target rgbdslam_generate_messages_eus
[ 29%] Built target rgbdslam_generate_messages_cpp
[ 35%] Built target rgbdslam_generate_messages_nodejs
[ 42%] Built target rgbdslam_generate_messages_py
[ 42%] Built target rgbdslam_gencpp
[ 42%] Built target rgbdslam_generate_messages
[ 43%] Generating src/moc_ros_service_ui.cxx
[ 45%] Generating src/moc_qtros.cxx
[ 46%] Generating src/moc_openni_listener.cxx
[ 47%] Generating src/moc_qt_gui.cxx
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2-hydro/CMakeFiles/rgbdslam.dir/build.make:62: recipe for target 'rgbdslam_v2-hydro/src/moc_qtros.cxx' failed
make[2]: *** [rgbdslam_v2-hydro/src/moc_qtros.cxx] Error 1
make[2]: *** Waiting for unfinished jobs....
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2-hydro/CMakeFiles/rgbdslam.dir/build.make:87: recipe for target 'rgbdslam_v2-hydro/src/moc_ros_service_ui.cxx' failed
make[2]: *** [rgbdslam_v2-hydro/src/moc_ros_service_ui.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2-hydro/CMakeFiles/rgbdslam.dir/build.make:72: recipe for target 'rgbdslam_v2-hydro/src/moc_qt_gui.cxx' failed
make[2]: *** [rgbdslam_v2-hydro/src/moc_qt_gui.cxx] Error 1
usr/include/boost/type_traits/detail/has_binary_operator.hp:50: Parse error at "BOOST_JOIN"
rgbdslam_v2-hydro/CMakeFiles/rgbdslam.dir/build.make:67: recipe for target 'rgbdslam_v2-hydro/src/moc_openni_listener.cxx' failed
make[2]: *** [rgbdslam_v2-hydro/src/moc_openni_listener.cxx] Error 1
CMakeFiles/Makefile2:3158: recipe for target 'rgbdslam_v2-hydro/CMakeFiles/rgbdslam.dir/all' failed
make[1]: *** [rgbdslam_v2-hydro/CMakeFiles/rgbdslam.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

Segmentation fault at PCL when compiling with -std=c++11

The use of auto type requires compilation with c++11 option(or c++0x), but this results in PCL libraries failing when trying to start rgbd slam. This is the print that gdb gives:

Program received signal SIGSEGV, Segmentation fault.
0x00007ffff7600a8c in boost::math::lanczos::lanczos_initializer<boost::math::lanczos::lanczos17m64, long double>::init::init() () from /usr/lib/libpcl_io.so.1.7

The code works if you replace the auto type with the real type and recompile with out c++11.
The failure is also present in PCL compiled from their GIT repository.
I managed to fix this on my branch from the hydro branch but the increased use of the auto type etc. in the experimental odometry branch makes compilation without c++11 harder.

I am using ubuntu 14.04 with Indigo.

Hi I have a question on RGBD_slam for ros

Hi I have a question on RGBD_slam for ros.

I want to test rgbdslam_v2 on my computer.
However, I am using ubuntu 14.04 for my research..(so, I can't downgrade to 12.04)
so ubuntu 14.04 doesn't support hydro.

Actually I tried to install with this way

source /opt/ros/hydro/setup.bash
mkdir -p ~/rgbdslam_catkin_ws/src
cd ~/rgbdslam_catkin_ws/src
catkin_init_workspace
cd ~/rgbdslam_catkin_ws/
catkin_make
source devel/setup.bash

Get RGBDSLAM

cd ~/rgbdslam_catkin_ws/src
wget -q http://github.com/felixendres/rgbdslam_v2/archive/hydro.zip
unzip -q hydro.zip
cd ~/rgbdslam_catkin_ws/

Install

rosdep update
rosdep install rgbdslam
catkin_make
catkin_make
------------------------------------------------------but I got this error
make[1]: *** [rgbdslam_v2-hydro/CMakeFiles/rgbdslam.dir/all] Error 2
make: *** [all] Error 2

Invoking "make -j8 -l8" failed

So, this is my question.

  1. Is there any way that I can use rgbdslam_v2 on ros indigo at ubuntu 14.04?

Compiling requirements

This is not really an issue, but I didn't know how to communicate this differently. I just wanted to mention that I was not able to compile the package with 1 GB of RAM. The compiler is always killed with an out of memory error. Increasing RAM to 2 GB seems to fix it. I don't know if it is worth to mention this in the ReadMe somewhere. (Maybe it's also just dependend on my individual configuration)

catkin_make error in moc_glviewer

Hi

I m trying to make the package on ROS kinetic and Ubuntu 16.04. The pcl version I have is 1.7.2 and Qt 4.8. I tried several ways to make the package reading the issues in the repository. I initially had problems compiling the g2ofork. The c++03 branch finally worked for me using
cmake .. -DCMAKE_INSTALL_PREFIX=~/g2ofork/install -DG2O_BUILD_EXAMPLES=OFF

When making the rgbdslam_v2 however, I am having the following error. Request you to provide inputs on the same.

Cheers!

Error:

[ 52%] Building CXX object rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_qtros.cpp.o
[ 54%] Building CXX object rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_openni_listener.cpp.o
[ 55%] Building CXX object rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_graph_manager.cpp.o
[ 57%] Building CXX object rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_qt_gui.cpp.o
[ 58%] Building CXX object rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_glviewer.cpp.o
In file included from /usr/include/c++/5/unordered_map:35:0,
from /opt/ros/kinetic/include/g2o/core/hyper_graph.h:38,
from /opt/ros/kinetic/include/g2o/core/optimizable_graph.h:38,
from /opt/ros/kinetic/include/g2o/core/sparse_optimizer.h:32,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:58,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/openni_listener.h:31,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_openni_listener.cpp:9:
/usr/include/c++/5/bits/c++0x_warning.h:32:2: error: #error This file requires compiler and library support for the ISO C++ 2011 standard. This support must be enabled with the -std=c++11 or -std=gnu++11 compiler options.
#error This file requires compiler and library support
^
In file included from /usr/include/c++/5/unordered_map:35:0,
from /opt/ros/kinetic/include/g2o/core/hyper_graph.h:38,
from /opt/ros/kinetic/include/g2o/core/optimizable_graph.h:38,
from /opt/ros/kinetic/include/g2o/core/sparse_optimizer.h:32,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:58,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_graph_manager.cpp:9:
/usr/include/c++/5/bits/c++0x_warning.h:32:2: error: #error This file requires compiler and library support for the ISO C++ 2011 standard. This support must be enabled with the -std=c++11 or -std=gnu++11 compiler options.
#error This file requires compiler and library support
^
In file included from /opt/ros/kinetic/include/g2o/core/optimizable_graph.h:38:0,
from /opt/ros/kinetic/include/g2o/core/sparse_optimizer.h:32,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:58,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/openni_listener.h:31,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_openni_listener.cpp:9:
/opt/ros/kinetic/include/g2o/core/hyper_graph.h:138:20: error: ‘unordered_map’ in namespace ‘std’ does not name a template type
typedef std::unordered_map<int, Vertex*> VertexIDMap;
^
/opt/ros/kinetic/include/g2o/core/hyper_graph.h:225:13: error: ‘VertexIDMap’ does not name a type
const VertexIDMap& vertices() const {return _vertices;}
^
/opt/ros/kinetic/include/g2o/core/hyper_graph.h:227:7: error: ‘VertexIDMap’ does not name a type
VertexIDMap& vertices() {return _vertices;}
^
/opt/ros/kinetic/include/g2o/core/hyper_graph.h:274:7: error: ‘VertexIDMap’ does not name a type
VertexIDMap _vertices;
^
In file included from /opt/ros/kinetic/include/g2o/core/sparse_block_matrix.h:38:0,
from /opt/ros/kinetic/include/g2o/core/sparse_optimizer.h:33,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:58,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/openni_listener.h:31,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_openni_listener.cpp:9:
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:222:20: error: ‘unordered_map’ in namespace ‘std’ does not name a template type
typedef std::unordered_map<int, MatrixType*> SparseColumn;
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:241:25: error: ‘SparseColumn’ was not declared in this scope
const std::vector& blockCols() const { return _blockCols;}
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:241:37: error: template argument 1 is invalid
const std::vector& blockCols() const { return _blockCols;}
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:241:37: error: template argument 2 is invalid
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:242:19: error: ‘SparseColumn’ was not declared in this scope
std::vector& blockCols() { return _blockCols;}
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:242:31: error: template argument 1 is invalid
std::vector& blockCols() { return _blockCols;}
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:242:31: error: template argument 2 is invalid
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:273:19: error: ‘SparseColumn’ was not declared in this scope
std::vector _blockCols; ///< the matrices stored in CCS order
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:273:31: error: template argument 1 is invalid
std::vector _blockCols; ///< the matrices stored in CCS order
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:273:31: error: template argument 2 is invalid
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h: In member function ‘MatrixType* g2o::SparseBlockMatrixHashMap::addBlock(int, int, bool)’:
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:256:9: error: ‘SparseColumn’ was not declared in this scope
SparseColumn& sparseColumn = _blockCols[c];
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:256:23: error: ‘sparseColumn’ was not declared in this scope
SparseColumn& sparseColumn = _blockCols[c];
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:256:50: error: invalid types ‘int[int]’ for array subscript
SparseColumn& sparseColumn = _blockCols[c];
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:257:18: error: ‘SparseColumn’ is not a class or namespace
typename SparseColumn::iterator foundIt = sparseColumn.find(r);
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:257:41: error: expected ‘(’ before ‘foundIt’
typename SparseColumn::iterator foundIt = sparseColumn.find(r);
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:258:13: error: ‘foundIt’ was not declared in this scope
if (foundIt == sparseColumn.end()) {
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:267:16: error: ‘foundIt’ was not declared in this scope
return foundIt->second;
^
In file included from /opt/ros/kinetic/include/g2o/core/optimizable_graph.h:38:0,
from /opt/ros/kinetic/include/g2o/core/sparse_optimizer.h:32,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:58,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_graph_manager.cpp:9:
/opt/ros/kinetic/include/g2o/core/hyper_graph.h:138:20: error: ‘unordered_map’ in namespace ‘std’ does not name a template type
typedef std::unordered_map<int, Vertex*> VertexIDMap;
^
/opt/ros/kinetic/include/g2o/core/hyper_graph.h:225:13: error: ‘VertexIDMap’ does not name a type
const VertexIDMap& vertices() const {return _vertices;}
^
/opt/ros/kinetic/include/g2o/core/hyper_graph.h:227:7: error: ‘VertexIDMap’ does not name a type
VertexIDMap& vertices() {return _vertices;}
^
/opt/ros/kinetic/include/g2o/core/hyper_graph.h:274:7: error: ‘VertexIDMap’ does not name a type
VertexIDMap _vertices;
^
In file included from /opt/ros/kinetic/include/g2o/core/sparse_block_matrix.h:38:0,
from /opt/ros/kinetic/include/g2o/core/sparse_optimizer.h:33,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:58,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_graph_manager.cpp:9:
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:222:20: error: ‘unordered_map’ in namespace ‘std’ does not name a template type
typedef std::unordered_map<int, MatrixType*> SparseColumn;
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:241:25: error: ‘SparseColumn’ was not declared in this scope
const std::vector& blockCols() const { return _blockCols;}
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:241:37: error: template argument 1 is invalid
const std::vector& blockCols() const { return _blockCols;}
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:241:37: error: template argument 2 is invalid
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:242:19: error: ‘SparseColumn’ was not declared in this scope
std::vector& blockCols() { return _blockCols;}
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:242:31: error: template argument 1 is invalid
std::vector& blockCols() { return _blockCols;}
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:242:31: error: template argument 2 is invalid
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:273:19: error: ‘SparseColumn’ was not declared in this scope
std::vector _blockCols; ///< the matrices stored in CCS order
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:273:31: error: template argument 1 is invalid
std::vector _blockCols; ///< the matrices stored in CCS order
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:273:31: error: template argument 2 is invalid
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h: In member function ‘MatrixType* g2o::SparseBlockMatrixHashMap::addBlock(int, int, bool)’:
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:256:9: error: ‘SparseColumn’ was not declared in this scope
SparseColumn& sparseColumn = _blockCols[c];
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:256:23: error: ‘sparseColumn’ was not declared in this scope
SparseColumn& sparseColumn = _blockCols[c];
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:256:50: error: invalid types ‘int[int]’ for array subscript
SparseColumn& sparseColumn = _blockCols[c];
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:257:18: error: ‘SparseColumn’ is not a class or namespace
typename SparseColumn::iterator foundIt = sparseColumn.find(r);
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:257:41: error: expected ‘(’ before ‘foundIt’
typename SparseColumn::iterator foundIt = sparseColumn.find(r);
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:258:13: error: ‘foundIt’ was not declared in this scope
if (foundIt == sparseColumn.end()) {
^
/opt/ros/kinetic/include/g2o/core/sparse_block_matrix_ccs.h:267:16: error: ‘foundIt’ was not declared in this scope
return foundIt->second;
^
In file included from /opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:30:0,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:65,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/openni_listener.h:31,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_openni_listener.cpp:9:
/opt/ros/kinetic/include/g2o/core/robust_kernel.h: At global scope:
/opt/ros/kinetic/include/g2o/core/robust_kernel.h:74:16: error: ‘shared_ptr’ in namespace ‘std’ does not name a template type
typedef std::shared_ptr RobustKernelPtr;
^
In file included from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:65:0,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/openni_listener.h:31,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_openni_listener.cpp:9:
/opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:49:45: error: ‘RobustKernelPtr’ does not name a type
explicit RobustKernelScaleDelta(const RobustKernelPtr& kernel, double delta = 1.);
^
/opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:53:13: error: ‘RobustKernelPtr’ does not name a type
const RobustKernelPtr kernel() const { return _kernel;}
^
/opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:55:28: error: ‘RobustKernelPtr’ does not name a type
void setKernel(const RobustKernelPtr& ptr);
^
/opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:60:7: error: ‘RobustKernelPtr’ does not name a type
RobustKernelPtr _kernel;
^
In file included from /opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:30:0,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:65,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_graph_manager.cpp:9:
/opt/ros/kinetic/include/g2o/core/robust_kernel.h: At global scope:
/opt/ros/kinetic/include/g2o/core/robust_kernel.h:74:16: error: ‘shared_ptr’ in namespace ‘std’ does not name a template type
typedef std::shared_ptr RobustKernelPtr;
^
In file included from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/../../../src/rgbdslam_v2/src/graph_manager.h:65:0,
from /home/atros/rgbdslam_v2/build/rgbdslam_v2/src/moc_graph_manager.cpp:9:
/opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:49:45: error: ‘RobustKernelPtr’ does not name a type
explicit RobustKernelScaleDelta(const RobustKernelPtr& kernel, double delta = 1.);
^
/opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:53:13: error: ‘RobustKernelPtr’ does not name a type
const RobustKernelPtr kernel() const { return _kernel;}
^
/opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:55:28: error: ‘RobustKernelPtr’ does not name a type
void setKernel(const RobustKernelPtr& ptr);
^
/opt/ros/kinetic/include/g2o/core/robust_kernel_impl.h:60:7: error: ‘RobustKernelPtr’ does not name a type
RobustKernelPtr _kernel;
^
rgbdslam_v2/CMakeFiles/rgbdslam.dir/build.make:110: recipe for target 'rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_openni_listener.cpp.o' failed
make[2]: *** [rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_openni_listener.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
rgbdslam_v2/CMakeFiles/rgbdslam.dir/build.make:158: recipe for target 'rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_graph_manager.cpp.o' failed
make[2]: *** [rgbdslam_v2/CMakeFiles/rgbdslam.dir/src/moc_graph_manager.cpp.o] Error 1
CMakeFiles/Makefile2:3158: recipe for target 'rgbdslam_v2/CMakeFiles/rgbdslam.dir/all' failed
make[1]: *** [rgbdslam_v2/CMakeFiles/rgbdslam.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

rgbdslam_v2 fail at the start up. Error in `/home/username/catkin_ws/devel/lib/rgbdslam/rgbdslam': realloc(): invalid pointer: ...

I have Ubuntu 14.04, ROS Indigo.

I downloaded rgbdslam_v2-indigo and placed it into catkin_ws/src. catkin_ws initialized and builded before. I installed all dependencies with rosdep and then did catkin_make. It finished with

[ 98%] Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/features.cpp.o
[100%] Building CXX object rgbdslam_v2-indigo/CMakeFiles/rgbdslam.dir/src/sift_gpu_wrapper.cpp.o
Linking CXX executable /home/evgeny/catkin_ws/devel/lib/rgbdslam/rgbdslam
[100%] Built target rgbdslam

I have new Xtion, so I installed openni2-launch instead of openni-launch (openni-launch did not work, it pop up USB interface error). I tested it with the rviz - it works.

I am starting openni node separately with

roslaunch openni_launch openni.launch

Now the question! When I run

rosrun rgbdslam rgbdslam

I got the following error:

*** Error in `/home/evgeny/catkin_ws/devel/lib/rgbdslam/rgbdslam': realloc(): invalid pointer: 0x00007f1ba0d51840 ***

The pointer number is different all the times.
I tried to run catkin_make again. I tried "catkin_make clean" and then build again. Always the same error.

Help please!

RGB-D Map displacement

Hi

I am trying to map an environment in the gazebo simulator using the Kinect, but everytime it starts to create a displaced map after some time.

My steps:
Step 1: launching gazebo with the erle copter drone wich has a kinect attached
Step 2: launch RGB-D SLAM
roslaunch rgbdslam openni+rgbdslam.launch
Step 3: wait 30sec - 1 minute

result (without even moving): http://imgur.com/a/jzbxM

as you can see at the top of the RGB-D SLAM viewer, it made a completely distorted mesh, without even moving. Does anyone have a clue what goes wrong?

I have tried this using different launch files, using different models (Rover + Kinect, Turtlebot + Kinect, Erle copter + Kinect) but none of them worked and gave the same results.

My setup:
Ubuntu 14.04
ROS Indigo

Little note*
Using the real kinect (v2) with the iai_kinect2 bridge for libfreenect2, it does create a decent mapping without the displacement. I assume there is an error in the simulator.

RgbdslamV2 depth picuture not working

Hello,

I know that rgbdslam_v2 is in beta state, but somehow i cannot make it work properly.
I have hydro version of ROS, on Ubuntu 12.04, and i have installed it like on this tutorial:
http://felixendres.github.io/rgbdslam_v2/

when i run roslaunch rgbdslam openni+rgbdslam.launch
it opens GUI but it finds /camera/rgb/image_color but somehow it cannot subscribe on

/camera/depth_registered/sw_registered/image_rect_raw

Making rostopic echo of the topic, it gives me a values, and i can see the image on rviz.
But here on rgbdslam it cannot get the image.

Is this a bug, or settings are wrong? How can i solve the problem?

thank you
best

Michael

no cloud points showing

I am using ubuntu 14.04, ros inidgo and kinect2. I had installed libfreenect2 and iai_kinect2, then I tested them which run nice.But when I "roslaunch rgbdslam.launch ", the terminal show some messages following and I do not see cloud points.
+++++++++++++++++++++++++++++
....
auto-starting new master
process[master]: started with pid [7915]
ROS_MASTER_URI=http://turtlebot-HP-ZBook-14-G2.local:11311

setting /run_id to a39bcbd6-4032-11e6-a1d1-6480999b1afe
process[rosout-1]: started with pid [7928]
started core service [/rosout]
process[rgbdslam-2]: started with pid [7945]
Initializing Node...
[ INFO] [1467449692.428582021]: Connected to roscore
[ INFO] [1467449692.581739930]: Using ORB keypoint detector.
[ INFO] [1467449692.581822911]: Using gridded keypoint detector with 3x3 cells, keeping 900 keypoints in total.
[ INFO] [1467449692.581859952]: Using adjusted keypoint detector with 5 maximum iterations, keeping the number of keypoints between 67 and 100
[ INFO] [1467449692.602606555]: Listening to /kinect2/sd/image_color_rect and /kinect2/sd/image_depth_rect
....
+++++++++++++++++++++++++++++
what should I do?
Thanks

rosdep problem

rosdep install rgbdslam_v2 yeilds:

ERROR: Rosdep cannot find all required resources to answer your query
Missing resource rgbdslam_v2
ROS path [0]=/opt/ros/indigo/share/ros
ROS path [1]=/opt/ros/indigo/share
ROS path [2]=/opt/ros/indigo/stacks

Following issues on El Captian (osx 10.11.3)

Original Post: http://answers.ros.org/question/225798/osx-rgbdslamv2-install-via-indigo/?comment=226057#post-id-226057

From there I've commented out libdevl in package.xml and now receiving the following error:

$ rosdep install rgbdslam
Error: No available formula with the name "ros/indigo/common_msgs" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/ros_comm" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/libg2o" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/message_runtime" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/std_msgs" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/geometry" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/perception_pcl" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/pcl_conversions" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/cmake_modules" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/vision_opencv" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/octomap" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/image_common" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "ros/indigo/message_generation" 
Please tap it and then try again: brew tap ros/indigo
Error: No available formula with the name "freeglut" 
Error: No available formula with the name "ros/indigo/catkin" 
Please tap it and then try again: brew tap ros/indigo
executing command [brew install ros/indigo/common_msgs]
==> Tapping ros/indigo
Cloning into '/usr/local/Library/Taps/ros/homebrew-indigo'...
Username for 'https://github.com': [email protected]
Password for 'https://[email protected]@github.com': 
remote: Repository not found.
fatal: repository 'https://github.com/ros/homebrew-indigo/' not found
Error: Failure while executing: git clone https://github.com/ros/homebrew-indigo /usr/local/Library/Taps/ros/homebrew-indigo --depth=1
ERROR: the following rosdeps failed to install
  homebrew: command [brew install ros/indigo/common_msgs] failed

I tried tapping ros/indigo:

$ brew tap ros/indigo
==> Tapping ros/indigo
Cloning into '/usr/local/Library/Taps/ros/homebrew-indigo'...
Username for 'https://github.com': [email protected]
Password for 'https://[email protected]@github.com': 
remote: Repository not found.
fatal: repository 'https://github.com/ros/homebrew-indigo/' not found
Error: Failure while executing: git clone https://github.com/ros/homebrew-indigo /usr/local/Library/Taps/ros/homebrew-indigo --depth=1

But you see that it's trying to get "ros/homebrew-indigo" - I researched for a while trying to find out how to get even just one package: "lib2go". Success yet to come. Any ideas?

Problem making catkin_make

Hi, i tried to install rgbdslam, but i can't make catkin_make.I have these errors :
Linking CXX executable /home/patri/catkin_ws/devel/lib/rgbdslam/rgbdslam
/usr/bin/ld: cannot find -lQt5::Core
/usr/bin/ld: cannot find -lQt5::Gui
/usr/bin/ld: cannot find -lQt5::Widgets
/usr/bin/ld: cannot findr -lQt5::Test
/usr/bin/ld: cannot find -lQt5::Concurrent
/usr/bin/ld: cannot find -lQt5::OpenGL
collect2: error: ld returned 1 exit status
make[2]: *** [/home/patri/catkin_ws/devel/lib/rgbdslam/rgbdslam] Error 1
make[1]: *** [rgbdslam/CMakeFiles/rgbdslam.dir/all] Error 2
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

Help, please!

kinect 2

hi
i have tried with kinect 2 (ubuntu 14.04 -indigo )according to this tutorial ::
http://answers.ros.org/question/234659/rgbdslam-v2-on-kinect-v2-no-devices-connected-waiting-for-devices-to-be-connected/
its very slow ! i need know whether there are some problems ? or should be like this?
and i have these messages after running ::

[ INFO] [1495442938.598059664]: Nodes 248<->48: 2 good iterations (from 100), inlier pct 85, inlier cnt: 256, error (MHD): 0.87
[ INFO] [1495442938.598074955]: RANSAC found a valid transformation with 256 inliers matches with average ratio 0.095311
[ INFO] [1495442938.598085358]: Returning Valid Edge
[ INFO] [1495442938.598113968]: Optimizer Size: 245
[ INFO] [1495442938.598223933]: You specified FLANN with ORB, this is SLOW! Using BRUTEFORCE instead.
[ INFO] [1495442938.598324452]: My bruteforce Search runtime: 0.0132416 s
[ INFO] [1495442938.598586335]: You specified FLANN with ORB, this is SLOW! Using BRUTEFORCE instead.
[ INFO] [1495442938.598607488]: My bruteforce Search runtime: 0.00655231 s
[ INFO] [1495442938.598716612]: My bruteforce Search runtime: 0.0137097 s
[ INFO] [1495442938.598833951]: 1 good iterations (from 100), inlier pct 82, inlier cnt: 247, error (MHD): 0.83
[ INFO] [1495442938.599453604]: Nodes 248<->0: g2o transformation estimated to Node 0:

[ WARN] [1495438960.643429202]: Could not find a connection between 'openni_rgb_optical_frame' and 'kinect2_rgb_optical_frame' because they are not part of the same tree.Tf has two or more unconnected trees.
[ WARN] [1495438960.643460247]: Using Standard kinect /openni_camera -> /openni_rgb_optical_frame as transformation (This message is throttled to 1 per 5 seconds)

error This file requires compiler and library support for the ISO C++ 2011 standard

the last step "nice catkin_make -C $WORKSPACE -j2", this error occured :

[ 48%] Building CXX object rgbdslam/CMakeFiles/rgbdslam.dir/src/main.cpp.o
In file included from /usr/include/c++/5/unordered_map:35:0,
from /usr/local/include/g2o/core/hyper_graph.h:38,
from /usr/local/include/g2o/core/optimizable_graph.h:38,
from /usr/local/include/g2o/core/sparse_optimizer.h:32,
from /home/ros/work/slam/rgbdslam_catkin_ws/build/rgbdslam/src/../../../src/rgbdslam/src/graph_manager.h:58,
from /home/ros/work/slam/rgbdslam_catkin_ws/build/rgbdslam/src/moc_graph_manager.cpp:9:
/usr/include/c++/5/bits/c++0x_warning.h:32:2: error: #error This file requires compiler and library support for the ISO C++ 2011 standard. This support must be enabled with the -std=c++11 or -std=gnu++11 compiler options.
#error This file requires compiler and library support \

what happend?Please help
(I have installed g2o of RainerKuemmerle before , is that the reason of erro?)

Benchmark Dataset URLs obselete

This is mostly for other users, but also for Felix if you feel like updating things.

I'm following the instructions on Evaluation of the RGB-D SLAM system (Section 3). When running download_benchmark_files.sh, it cannot find the urls (which are in download_benchmark_data.urls).

The dataset is now found at http://vision.in.tum.de/data/datasets/rgbd-dataset/download. You can either edit download_benchmark_data.urls, or manually download them into [wherever rgbd_benchmark is]/benchmark_data. (Make sure you pick the .bag files).

Also, the instructions to referring to ~/ros/rgbdslam/rgbd_benchmark/ could be changed to $(rospack find rgbdslam)/rgbd_benchmark/ so it works on more systems.

Error catkin_make

I am using Hydro in Ubuntu12.04. When I try to make the pkg I come across the following error. I guess it is because the codes make use of deleted function boost::weak_ptr

/usr/include/c++/4.8/bits/stl_vector.h:920:36: required from ‘void std::vector<_Tp, _Alloc>::push_back(std::vector<_Tp, _Alloc>::value_type&&) [with _Tp = boost::variantboost::weak_ptr<void, boost::signals2::detail::foreign_void_weak_ptr>; Alloc = std::allocatorboost::variant<boost::weak_ptr<void, boost::signals2::detail::foreign_void_weak_ptr> >; std::vector<Tp, Alloc>::value_type = boost::variantboost::weak_ptr<void, boost::signals2::detail::foreign_void_weak_ptr>]’
/usr/include/boost/signals2/slot_base.hpp:93:55: required from here
/usr/include/boost/variant/variant.hpp:401:9: error: use of deleted function ‘boost::weak_ptr::weak_ptr(const boost::weak_ptr&)’
new(storage
) T( operand.get() );
^
In file included from /usr/include/boost/variant/variant.hpp:31:0,
from /usr/include/boost/signals2/slot_base.hpp:23,
from /usr/include/boost/signals2/detail/tracked_objects_visitor.hpp:18,
from /usr/include/boost/signals2/slot.hpp:22,
from /usr/include/boost/signals2/connection.hpp:23,
from /usr/include/boost/signals2/signal.hpp:21,
from /usr/include/boost/signals2.hpp:19,
from /usr/include/pcl-1.7/pcl/io/boost.h:73,
from /usr/include/pcl-1.7/pcl/io/file_io.h:43,
from /usr/include/pcl-1.7/pcl/io/pcd_io.h:44,
from /opt/ros/hydro/include/pcl_conversions/pcl_conversions.h:69,
from /opt/ros/hydro/include/pcl_ros/point_cloud.h:9,
from /home/zli-dji/ros/catkin_ws/build/rgbdslam/src/../../../src/rgbdslam/src/parameter_server.h:30,
from /home/zli-dji/ros/catkin_ws/build/rgbdslam/src/../../../src/rgbdslam/src/node.h:39,
from /home/zli-dji/ros/catkin_ws/build/rgbdslam/src/../../../src/rgbdslam/src/graph_manager.h:30,
from /home/zli-dji/ros/catkin_ws/build/rgbdslam/src/../../../src/rgbdslam/src/openni_listener.h:30,
from /home/zli-dji/ros/catkin_ws/build/rgbdslam/src/moc_openni_listener.cxx:10:
/usr/include/boost/variant/detail/initializer.hpp: In instantiation of ‘static int boost::detail::variant::make_initializer_node::apply<BaseIndexPair, Iterator>::initializer_node::initialize(void*, boost::detail::variant::make_initializer_node::apply<BaseIndexPair, Iterator>::initializer_node::param_T) [with BaseIndexPair = boost::mpl::pair<boost::detail::variant::initializer_root, mpl
::int
<0> >; Iterator = boost::mpl::l_iterboost::mpl::list2<boost::shared_ptr<void, boost::signals2::detail::foreign_void_shared_ptr> >; boost::detail::variant::make_initializer_node::apply<BaseIndexPair, Iterator>::initializer_node::param_T = const boost::shared_ptr&]’:

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.