tum-vision/dvo_slam

Error in compiling dvo_core

ple13 opened this issue · 12 comments

ple13 commented

I'm trying to compile dvo_slam on my machine: Ubuntu 12.04.5 / ros fuerte. The compilation terminates when dvo_core is compiled.

In summary, I notice that there is an error relating to conversion between different data types.

In dense_tracking.cpp, line 263 causes the compilation error:
Eigen::Affine3f transformf;
transformf = estimate().matrix().cast();

I'm thinking about passing data from estimate().matrix() to transformf manually. However I guess there should be a better way to handle the issue.

Below is the error message:

{-------------------------------------------------------------------------------
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp: In instantiation of ‘Eigen::Matrix<typename Eigen::internal::traits::Scalar, 3, 3> Sophus::SE3GroupBase::rotationMatrix() const [with Derived = Sophus::SE3Group; typename Eigen::internal::traits::Scalar = double]’:
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp:227:59: required from ‘Sophus::SE3GroupBase::Transformation Sophus::SE3GroupBase::matrix() const [with Derived = Sophus::SE3Group; Sophus::SE3GroupBase::Transformation = Eigen::Matrix<double, 4, 4>; typename Eigen::internal::traits::Scalar = double]’
/home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/src/dense_tracking.cpp:263:40: required from here
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp:311:25: error: could not convert ‘((const Sophus::SO3GroupBaseSophus::SO3Group)(& Sophus::SE3GroupBase::so3Sophus::SE3Group()))->Sophus::SO3GroupBase::matrixSophus::SO3Group()’ from ‘Sophus::SO3GroupBaseSophus::SO3Group::Transformation {aka int}’ to ‘Eigen::Matrix<double, 3, 3>’
return so3().matrix();
^
In file included from /home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp:27:0,
from /home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/src/dense_tracking.cpp:27:
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/so3.hpp: In instantiation of ‘static Sophus::SO3GroupBase::Tangent Sophus::SO3GroupBase::logAndTheta(const int&, int
) [with Derived = Sophus::SO3Group; Sophus::SO3GroupBase::Tangent = int]’:
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp:611:56: required from ‘static Sophus::SE3GroupBase::Tangent Sophus::SE3GroupBase::log(const Sophus::SE3Group<typename Eigen::internal::traits::Scalar>&) [with Derived = Sophus::SE3Group; Sophus::SE3GroupBase::Tangent = Eigen::Matrix<double, 6, 1>; typename Eigen::internal::traits::Scalar = double]’
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp:211:21: required from ‘Sophus::SE3GroupBase::Tangent Sophus::SE3GroupBase::log() const [with Derived = Sophus::SE3Group; Sophus::SE3GroupBase::Tangent = Eigen::Matrix<double, 6, 1>; typename Eigen::internal::traits::Scalar = double]’
/home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/src/dense_tracking.cpp:238:17: required from here
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/so3.hpp:569:3: warning: no return statement in function returning non-void [-Wreturn-type]
}
^
In file included from /home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/src/dense_tracking.cpp:27:0:
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp: In member function ‘Sophus::SE3Group<typename Eigen::internal::traits::Scalar> Sophus::SE3GroupBase::inverse() const [with Derived = Sophus::SE3Group; typename Eigen::internal::traits::Scalar = double]’:
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp:200:3: warning: control reaches end of non-void function [-Wreturn-type]
}
^
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp: In member function ‘Eigen::Matrix<typename Eigen::internal::traits::Scalar, 3, 3> Sophus::SE3GroupBase::rotationMatrix() const [with Derived = Sophus::SE3Group; typename Eigen::internal::traits::Scalar = double]’:
/home/panda/Desktop/slam_baselines/dvo_slam/sophus/include/sophus/se3.hpp:312:3: warning: control reaches end of non-void function [-Wreturn-type]
}
^
In file included from /home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/include/dvo/dense_tracking.h:28:0,
from /home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/src/dense_tracking.cpp:23:
/home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/include/dvo/core/datatypes.h: At global scope:
/home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/include/dvo/core/datatypes.h:33:28: warning: ‘dvo::core::Invalid’ defined but not used [-Wunused-variable]
static const IntensityType Invalid = std::numeric_limits::quiet_NaN();
^
/home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/include/dvo/core/datatypes.h:36:24: warning: ‘dvo::core::InvalidDepth’ defined but not used [-Wunused-variable]
static const DepthType InvalidDepth = std::numeric_limits::quiet_NaN();
^
make[3]: *** [CMakeFiles/dvo_core.dir/src/dense_tracking.o] Error 1
make[3]: Leaving directory /home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/build' make[2]: *** [CMakeFiles/dvo_core.dir/all] Error 2 make[2]: Leaving directory/home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/build'
make[1]: *** [all] Error 2
make[1]: Leaving directory `/home/panda/Desktop/slam_baselines/dvo_slam/dvo_core/build'
-------------------------------------------------------------------------------}
[ rosmake ] Output from build of package dvo_core written to:
[ rosmake ] /home/panda/.ros/rosmake/rosmake_output-20161004-150237/dvo_core/build_output.log
[rosmake-0] Finished <<< dvo_core [FAIL] [ 8.61 seconds ]
[ rosmake ] Halting due to failure in package dvo_core.
[ rosmake ] Waiting for other threads to complete.
[ rosmake ] Results:
[ rosmake ] Built 40 packages with 1 failures.
[ rosmake ] Summary output to directory

Hi,

A few months ago I attempted to compile DVO_SLAM on Linux Mint (Linux distro based on Ubuntu). The forked repository and step-by-step instructions for compilation are here: https://github.com/songuke/dvo_slam

You might want to give it try. It uses catkin to build, which seems to avoid many issues caused by rosmake.

Cheers.

ple13 commented

Hi,

Thanks for your help.

It doesn't work for me yet. I keep having trouble with type conversion
between Sophus matrix and eigen::affine3f.

Which Eigen version did you use to compile the package? I notice that when
I change the Eigen version, sometimes Sophus cannot be compiled.

Le

On Tue, Oct 4, 2016 at 10:48 PM, songuke notifications@github.com wrote:

Hi,

A few months ago I attempted to compile DVO on Linux Mint (Linux distro
based on Ubuntu). The step-by-step instructions for compilations are here:
https://github.com/songuke/dvo_slam

You might want to give it try. It uses catkin to build, which seems to
avoid many issues caused by rosmake.

Cheers.


You are receiving this because you authored the thread.
Reply to this email directly, view it on GitHub
#50 (comment),
or mute the thread
https://github.com/notifications/unsubscribe-auth/AOXj5OX1Pu8Dd7dihj4n4Gj1K_IZQX3zks5qwxAPgaJpZM4KODT5
.

Hi Le,

In the README.md on my repository, I did note:

"If your system has Eigen >= 3.3, don't use it with g2o. The old version of
g2o is only compatible to Eigen 3.2.8..."

You might want to try that.

2016-10-10 7:27 GMT+07:00 ple13 notifications@github.com:

Hi,

Thanks for your help.

It doesn't work for me yet. I keep having trouble with type conversion
between Sophus matrix and eigen::affine3f.

Which Eigen version did you use to compile the package? I notice that when
I change the Eigen version, sometimes Sophus cannot be compiled.

Le

On Tue, Oct 4, 2016 at 10:48 PM, songuke notifications@github.com wrote:

Hi,

A few months ago I attempted to compile DVO on Linux Mint (Linux distro
based on Ubuntu). The step-by-step instructions for compilations are
here:
https://github.com/songuke/dvo_slam

You might want to give it try. It uses catkin to build, which seems to
avoid many issues caused by rosmake.

Cheers.


You are receiving this because you authored the thread.
Reply to this email directly, view it on GitHub
<#50 (comment)
,
or mute the thread
<https://github.com/notifications/unsubscribe-auth/
AOXj5OX1Pu8Dd7dihj4n4Gj1K_IZQX3zks5qwxAPgaJpZM4KODT5>
.


You are receiving this because you commented.
Reply to this email directly, view it on GitHub
#50 (comment),
or mute the thread
https://github.com/notifications/unsubscribe-auth/AAIXslOrgU8TErFq8UeLZmVmh6zl97SFks5qyYZfgaJpZM4KODT5
.

@ple13 : Have you solved the issue?, I got the identical problem.
@songuke : I already tried your dvo_slam from: https://github.com/songuke/dvo_slam. I've checked my eigen version and it is 3.2.0. Do you have any idea why the Eigen conversion seems not working?

My OS is Ubuntu 14.04 with ROS Indigo.

I tried to check the installed eigen:

ubuntu@ubuntu:~/dvo_slam$ dpkg --get-selections | grep eigen
libeigen3-dev install
ros-indigo-eigen-conversions install
ros-indigo-eigen-stl-containers install

ros indigo has its own conversion package, will the multiple packages be the possible issue?

ple13 commented

Hi,

Thank you Songuke!!

I finally compiled the code successfully.

I guess that the Eigen type conversion errors that kept popping out was due
to the compiler I used (g++-4.7/4.8.4.9/5). It compiled the Sophus package
without any problems, however, when Sophus was used in dvo_slam, the
compiler complainted. I checked the error messages, then modified the file
so3.hpp in Sophus, and it worked.

In short, I changed these lines in /usr/local/include/Sophus/so3.hpp,
starting from line 89:


/** \brief scalar type /
using Scalar = typename Eigen::internal::traits::Scalar;
/
* \brief quaternion reference type /
using QuaternionReference =
typename Eigen::internal::traits::QuaternionType&;
/
* \brief quaternion const reference type */
using ConstQuaternionReference =
typename Eigen::internal::traits::QuaternionType const&;


into


/** \brief scalar type /
typedef typename Eigen::internal::traits::Scalar Scalar;
/
* \brief quaternion reference type /
typedef
typename Eigen::internal::traits::QuaternionType&
QuaternionReference;
/
* \brief quaternion const reference type */
typedef
typename Eigen::internal::traits::QuaternionType const&
ConstQuaternionReference;


After this small change, I could compiled the package with g++.

@mrksst: when I installed Eigen, I used cmake ..
-DCMAKE_INSTALL_PREFIX=/usr . This was to avoid the situation of having
multiple eigens in the system. Before doing that, I deleted all eigen3 in
/usr/include and /usr/local/include, then restalled it using the above
option. I hope that it works for you too.

Le, Phi Hung

On Tue, Oct 11, 2016 at 11:33 AM, mrkstt notifications@github.com wrote:

I tried to check the installed eigen:

ubuntu@ubuntu:~/dvo_slam$ dpkg --get-selections | grep eigen
libeigen3-dev install
ros-indigo-eigen-conversions install
ros-indigo-eigen-stl-containers install

ros indigo has its own conversion package, will the multiple packages be
the possible issue?


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
#50 (comment),
or mute the thread
https://github.com/notifications/unsubscribe-auth/AOXj5PVH1DtIinUlKHMIdqJi7jtf6dR7ks5qy6xkgaJpZM4KODT5
.

Hi Le @ple13,
Sounds great you have solved the issue.
I followed the code modification above and the error disappeared. I also re-installed the eigen as you suggested (my Eigen version is 3.2.8). However, I got this following error now:

ubuntu@ubuntu:~/dvo_slam$ catkin_make -DCMAKE_BUILD_TYPE=ReleaseBase path: /home/ubuntu/dvo_slam
Source space: /home/ubuntu/dvo_slam/src
Build space: /home/ubuntu/dvo_slam/build
Devel space: /home/ubuntu/dvo_slam/devel
Install space: /home/ubuntu/dvo_slam/install

Running command: "make cmake_check_build_system" in "/home/ubuntu/dvo_slam/build"

Running command: "make -j8 -l8" in "/home/ubuntu/dvo_slam/build"

[ 7%] [ 7%] Built target dvo_slam_gencfg
Built target dvo_ros_gencfg
[ 10%] Building CXX object dvo_core/CMakeFiles/dvo_core.dir/src/dense_tracking.cpp.o
In file included from /usr/local/include/sophus/sophus.hpp:31:0,
from /usr/local/include/sophus/so3.hpp:27,
from /usr/local/include/sophus/se3.hpp:27,
from /home/ubuntu/dvo_slam/src/dvo_core/src/dense_tracking.cpp:27:
/usr/local/include/sophus/ensure.hpp:60:1: error: ‘EIGEN_DEVICE_FUNC’ does not name a type
EIGEN_DEVICE_FUNC inline void defaultEnsure(const char* function,
^
/usr/local/include/sophus/so3.hpp: In member function ‘void Sophus::SO3GroupBase::normalize()’:
/usr/local/include/sophus/so3.hpp:221:5: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(length >= SophusConstants::epsilon(),
^
/usr/local/include/sophus/so3.hpp: In static member function ‘static Sophus::SO3GroupBase::Transformation Sophus::SO3GroupBase::generator(int)’:
/usr/local/include/sophus/so3.hpp:431:5: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(i >= 0 && i <= 2, "i should be in range [0,2].");
^
/usr/local/include/sophus/so3.hpp: In static member function ‘static void Sophus::SO3GroupBase::internalGenerator(int, Eigen::Quaternion<typename Eigen::internal::traits::Scalar>)’:
/usr/local/include/sophus/so3.hpp:445:5: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(i >= 0 && i <= 2, "i should be in range [0,2]");
^
/usr/local/include/sophus/so3.hpp:446:5: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(internal_gen_q != NULL,
^
/usr/local/include/sophus/so3.hpp: In static member function ‘static Sophus::SO3GroupBase::Tangent Sophus::SO3GroupBase::logAndTheta(const Sophus::SO3Group<typename Eigen::internal::traits::Scalar>&, Sophus::SO3GroupBase::Scalar
)’:
/usr/local/include/sophus/so3.hpp:551:7: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(abs(w) >= SophusConstants::epsilon(),
^
/usr/local/include/sophus/se3.hpp: In static member function ‘static Sophus::SE3GroupBase::Transformation Sophus::SE3GroupBase::generator(int)’:
/usr/local/include/sophus/se3.hpp:503:5: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(i >= 0 && i <= 5, "i should be in range [0,5].");
^
/usr/local/include/sophus/se3.hpp: In static member function ‘static void Sophus::SE3GroupBase::internalGenerator(int, Eigen::Quaternion<typename Eigen::internal::traits::Scalar>, Eigen::Matrix<typename Eigen::internal::traits::Scalar, 3, 1>)’:
/usr/local/include/sophus/se3.hpp:519:5: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(i >= 0 && i <= 5, "i should be in range [0,5]");
^
/usr/local/include/sophus/se3.hpp:520:5: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(internal_gen_q != NULL,
^
/usr/local/include/sophus/se3.hpp:522:5: error: ‘defaultEnsure’ is not a member of ‘Sophus’
SOPHUS_ENSURE(internal_gen_t != NULL,
^
make[2]: *** [dvo_core/CMakeFiles/dvo_core.dir/src/dense_tracking.cpp.o] Error 1
make[1]: *** [dvo_core/CMakeFiles/dvo_core.dir/all] Error 2
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

Seems "EIGEN_DEVICE_FUNC" and "defaultEnsure" are not recognized.
Any idea?, really thanks for suggestion.

Hi @ple13 @songuke,

I solved the error above by commenting all "SOPHUS_ENSURE", seems it's just for checking.

Then, I run:

roslaunch launch/benchmark.launch dataset:=/home/ubuntu/dataset/ rgbd_dataset_freiburg3_cabinet_validation

Output:
ros.roscpp: { Tried to advertise a service that is already advertised in this node [/dvo_vis/image/compressedDepth/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised in this node [/dvo_vis/image/compressed/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised in this node [/dvo_vis/image/theora/set_parameters] }
ros.dvo_benchmark.config: { tracker config: "First Level = 3, Last Level = 1, Max Iterations per Level = 50, Precision = 0.0001, Mu = 0.05, Use Initial Estimate = true, Use Weighting = true, Scale Estimator = TDistribution, Scale Estimator Param = 5, Influence Function = TDistribution, Influence Function Param = 5, Intensity Derivative Threshold = 0, Depth Derivative Threshold = 0" }
ros.dvo_benchmark.config: { frontend config: "UseMultiThreading: 1 MaxTranslationalDistance: 0.2 MaxRotationalDistance: 0 MinEntropyRatio: 0.6 MinEquationSystemConstraintRatio: 0.3" }
ros.dvo_benchmark.config: { backend config: "UseRobustKernel: 1 UseMultiThreading: 1 NewConstraintSearchRadius: 5 NewConstraintMinEntropyRatioCoarse: 0.03 NewConstraintMinEntropyRatioFine: 0.6 MinEquationSystemConstraintRatio: 0.3 MinConstraintDistance: 0 OptimizationUseDenseGraph: 0 OptimizationIterations: 50 OptimizationRemoveOutliers: 1 OptimizationOutlierWeightThreshold: 0.1 FinalOptimizationUseDenseGraph: 1 FinalOptimizationIterations: 1000 FinalOptimizationRemoveOutliers: 1 FinalOptimizationOutlierWeightThreshold: 0.1" }
ros.dvo_slam: { adding 0 new constraints }
ros.dvo_slam: { adding 1 new constraints }
ros.dvo_slam: { adding 2 new constraints }
ros.dvo_slam: { adding 3 new constraints }
ros.dvo_slam: { adding 4 new constraints }
ros.dvo_slam: { adding 5 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
new_kf: 0.0979787
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 9 new constraints }
ros.dvo_slam: { adding 11 new constraints }
ros.dvo_slam: { adding 7 new constraints }
ros.dvo_slam: { adding 8 new constraints }
ros.dvo_slam: { adding 9 new constraints }
match: 0.0492692
...

The only thing unsolved is I cannot see any result (empty) by running:

rosrun rviz rviz

Any idea?

Hi guys,

Thanks for all the suggestions to fix the issues.

My previous experience with rviz is that it does take a while for the
result to appear. Please also make sure the code is compiled in Release
mode.

2016-10-13 14:21 GMT+07:00 mrkstt notifications@github.com:

Hi @ple13 https://github.com/ple13 @songuke https://github.com/songuke
,

I solved the error above by commenting all "SOPHUS_ENSURE", seems it's
just for checking.

Then, I run:

roslaunch launch/benchmark.launch dataset:=/home/ubuntu/dataset/
rgbd_dataset_freiburg3_cabinet_validation

Output:
ros.roscpp: { Tried to advertise a service that is already advertised in
this node [/dvo_vis/image/compressedDepth/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised in
this node [/dvo_vis/image/compressed/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised in
this node [/dvo_vis/image/theora/set_parameters] }
ros.dvo_benchmark.config: { tracker config: "First Level = 3, Last Level =
1, Max Iterations per Level = 50, Precision = 0.0001, Mu = 0.05, Use
Initial Estimate = true, Use Weighting = true, Scale Estimator =
TDistribution, Scale Estimator Param = 5, Influence Function =
TDistribution, Influence Function Param = 5, Intensity Derivative Threshold
= 0, Depth Derivative Threshold = 0" }
ros.dvo_benchmark.config: { frontend config: "UseMultiThreading: 1
MaxTranslationalDistance: 0.2 MaxRotationalDistance: 0 MinEntropyRatio: 0.6
MinEquationSystemConstraintRatio: 0.3" }
ros.dvo_benchmark.config: { backend config: "UseRobustKernel: 1
UseMultiThreading: 1 NewConstraintSearchRadius: 5
NewConstraintMinEntropyRatioCoarse: 0.03 NewConstraintMinEntropyRatioFine:
0.6 MinEquationSystemConstraintRatio: 0.3 MinConstraintDistance: 0
OptimizationUseDenseGraph: 0 OptimizationIterations: 50
OptimizationRemoveOutliers: 1 OptimizationOutlierWeightThreshold: 0.1
FinalOptimizationUseDenseGraph: 1 FinalOptimizationIterations: 1000
FinalOptimizationRemoveOutliers: 1 FinalOptimizationOutlierWeightThreshold:
0.1" }
ros.dvo_slam: { adding 0 new constraints }
ros.dvo_slam: { adding 1 new constraints }
ros.dvo_slam: { adding 2 new constraints }
ros.dvo_slam: { adding 3 new constraints }
ros.dvo_slam: { adding 4 new constraints }
ros.dvo_slam: { adding 5 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
new_kf: 0.0979787
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 9 new constraints }
ros.dvo_slam: { adding 11 new constraints }
ros.dvo_slam: { adding 7 new constraints }
ros.dvo_slam: { adding 8 new constraints }
ros.dvo_slam: { adding 9 new constraints }
match: 0.0492692

The only thing unsolved is I cannot see any result (empty) by running:

rosrun rviz rviz

Any idea?


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
#50 (comment),
or mute the thread
https://github.com/notifications/unsubscribe-auth/AAIXsgpqjdzA8UDaf_hP89eCUdAOMW5uks5qzdv3gaJpZM4KODT5
.

ple13 commented

Hi,

When I tried to run the program, it kept asking for the file assoc.txt
however this file is not provided with the dataset. Am I suppose to sync
the depth and rgb to produce this file myself?

Le, Phi Hung

On Thu, Oct 13, 2016 at 4:32 AM, songuke notifications@github.com wrote:

Hi guys,

Thanks for all the suggestions to fix the issues.

My previous experience with rviz is that it does take a while for the
result to appear. Please also make sure the code is compiled in Release
mode.

2016-10-13 14:21 GMT+07:00 mrkstt notifications@github.com:

Hi @ple13 https://github.com/ple13 @songuke <
https://github.com/songuke>
,

I solved the error above by commenting all "SOPHUS_ENSURE", seems it's
just for checking.

Then, I run:

roslaunch launch/benchmark.launch dataset:=/home/ubuntu/dataset/
rgbd_dataset_freiburg3_cabinet_validation

Output:
ros.roscpp: { Tried to advertise a service that is already advertised in
this node [/dvo_vis/image/compressedDepth/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised in
this node [/dvo_vis/image/compressed/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised in
this node [/dvo_vis/image/theora/set_parameters] }

ros.dvo_benchmark.config: { tracker config: "First Level = 3, Last Level

1, Max Iterations per Level = 50, Precision = 0.0001, Mu = 0.05, Use
Initial Estimate = true, Use Weighting = true, Scale Estimator =
TDistribution, Scale Estimator Param = 5, Influence Function =
TDistribution, Influence Function Param = 5, Intensity Derivative
Threshold
= 0, Depth Derivative Threshold = 0" }
ros.dvo_benchmark.config: { frontend config: "UseMultiThreading: 1
MaxTranslationalDistance: 0.2 MaxRotationalDistance: 0 MinEntropyRatio:
0.6
MinEquationSystemConstraintRatio: 0.3" }
ros.dvo_benchmark.config: { backend config: "UseRobustKernel: 1
UseMultiThreading: 1 NewConstraintSearchRadius: 5
NewConstraintMinEntropyRatioCoarse: 0.03 NewConstraintMinEntropyRatioFi
ne:
0.6 MinEquationSystemConstraintRatio: 0.3 MinConstraintDistance: 0
OptimizationUseDenseGraph: 0 OptimizationIterations: 50
OptimizationRemoveOutliers: 1 OptimizationOutlierWeightThreshold: 0.1
FinalOptimizationUseDenseGraph: 1 FinalOptimizationIterations: 1000
FinalOptimizationRemoveOutliers: 1 FinalOptimizationOutlierWeight
Threshold:
0.1" }
ros.dvo_slam: { adding 0 new constraints }
ros.dvo_slam: { adding 1 new constraints }
ros.dvo_slam: { adding 2 new constraints }
ros.dvo_slam: { adding 3 new constraints }
ros.dvo_slam: { adding 4 new constraints }
ros.dvo_slam: { adding 5 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
new_kf: 0.0979787
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 9 new constraints }
ros.dvo_slam: { adding 11 new constraints }
ros.dvo_slam: { adding 7 new constraints }
ros.dvo_slam: { adding 8 new constraints }
ros.dvo_slam: { adding 9 new constraints }
match: 0.0492692

The only thing unsolved is I cannot see any result (empty) by running:

rosrun rviz rviz

Any idea?


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
<#50 (comment)
,
or mute the thread
<https://github.com/notifications/unsubscribe-auth/AAIXsgpqjdzA8UDaf_
hP89eCUdAOMW5uks5qzdv3gaJpZM4KODT5>
.


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
#50 (comment),
or mute the thread
https://github.com/notifications/unsubscribe-auth/AOXj5P_GYvG6-z7WcbnvpokYLFIaSfFuks5qzeysgaJpZM4KODT5
.

assoc.txt can be generated with this Python script:
http://vision.in.tum.de/data/datasets/rgbd-dataset/tools

Another hint to check if the program is working is to monitor
trajectory.txt. This file should be changing if DVO is doing the
calculation.

2016-10-14 1:20 GMT+07:00 ple13 notifications@github.com:

Hi,

When I tried to run the program, it kept asking for the file assoc.txt
however this file is not provided with the dataset. Am I suppose to sync
the depth and rgb to produce this file myself?

Le, Phi Hung

On Thu, Oct 13, 2016 at 4:32 AM, songuke notifications@github.com wrote:

Hi guys,

Thanks for all the suggestions to fix the issues.

My previous experience with rviz is that it does take a while for the
result to appear. Please also make sure the code is compiled in Release
mode.

2016-10-13 14:21 GMT+07:00 mrkstt notifications@github.com:

Hi @ple13 https://github.com/ple13 @songuke <
https://github.com/songuke>
,

I solved the error above by commenting all "SOPHUS_ENSURE", seems it's
just for checking.

Then, I run:

roslaunch launch/benchmark.launch dataset:=/home/ubuntu/dataset/
rgbd_dataset_freiburg3_cabinet_validation

Output:
ros.roscpp: { Tried to advertise a service that is already advertised
in
this node [/dvo_vis/image/compressedDepth/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised
in
this node [/dvo_vis/image/compressed/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised
in
this node [/dvo_vis/image/theora/set_parameters] }
ros.dvo_benchmark.config: { tracker config: "First Level = 3, Last

Level

1, Max Iterations per Level = 50, Precision = 0.0001, Mu = 0.05, Use
Initial Estimate = true, Use Weighting = true, Scale Estimator =
TDistribution, Scale Estimator Param = 5, Influence Function =
TDistribution, Influence Function Param = 5, Intensity Derivative
Threshold
= 0, Depth Derivative Threshold = 0" }
ros.dvo_benchmark.config: { frontend config: "UseMultiThreading: 1
MaxTranslationalDistance: 0.2 MaxRotationalDistance: 0 MinEntropyRatio:
0.6
MinEquationSystemConstraintRatio: 0.3" }
ros.dvo_benchmark.config: { backend config: "UseRobustKernel: 1
UseMultiThreading: 1 NewConstraintSearchRadius: 5
NewConstraintMinEntropyRatioCoarse: 0.03
NewConstraintMinEntropyRatioFi
ne:
0.6 MinEquationSystemConstraintRatio: 0.3 MinConstraintDistance: 0
OptimizationUseDenseGraph: 0 OptimizationIterations: 50
OptimizationRemoveOutliers: 1 OptimizationOutlierWeightThreshold: 0.1
FinalOptimizationUseDenseGraph: 1 FinalOptimizationIterations: 1000
FinalOptimizationRemoveOutliers: 1 FinalOptimizationOutlierWeight
Threshold:
0.1" }
ros.dvo_slam: { adding 0 new constraints }
ros.dvo_slam: { adding 1 new constraints }
ros.dvo_slam: { adding 2 new constraints }
ros.dvo_slam: { adding 3 new constraints }
ros.dvo_slam: { adding 4 new constraints }
ros.dvo_slam: { adding 5 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
new_kf: 0.0979787
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 9 new constraints }
ros.dvo_slam: { adding 11 new constraints }
ros.dvo_slam: { adding 7 new constraints }
ros.dvo_slam: { adding 8 new constraints }
ros.dvo_slam: { adding 9 new constraints }
match: 0.0492692

The only thing unsolved is I cannot see any result (empty) by running:

rosrun rviz rviz

Any idea?


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
<#50
issuecomment-253434903
,
or mute the thread
<https://github.com/notifications/unsubscribe-auth/AAIXsgpqjdzA8UDaf_
hP89eCUdAOMW5uks5qzdv3gaJpZM4KODT5>
.


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
<#50 (comment)
,
or mute the thread
<https://github.com/notifications/unsubscribe-auth/AOXj5P_GYvG6-
z7WcbnvpokYLFIaSfFuks5qzeysgaJpZM4KODT5>
.


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
#50 (comment),
or mute the thread
https://github.com/notifications/unsubscribe-auth/AAIXsrSX5wrEEnqVnug7u_YzEjb-HWrGks5qznZ4gaJpZM4KODT5
.

ple13 commented

Thanks.

It works for me.

Le, Phi Hung

On Thu, Oct 13, 2016 at 3:17 PM, songuke notifications@github.com wrote:

assoc.txt can be generated with this Python script:
http://vision.in.tum.de/data/datasets/rgbd-dataset/tools

Another hint to check if the program is working is to monitor
trajectory.txt. This file should be changing if DVO is doing the
calculation.

2016-10-14 1:20 GMT+07:00 ple13 notifications@github.com:

Hi,

When I tried to run the program, it kept asking for the file assoc.txt
however this file is not provided with the dataset. Am I suppose to sync
the depth and rgb to produce this file myself?

Le, Phi Hung

On Thu, Oct 13, 2016 at 4:32 AM, songuke notifications@github.com
wrote:

Hi guys,

Thanks for all the suggestions to fix the issues.

My previous experience with rviz is that it does take a while for the
result to appear. Please also make sure the code is compiled in Release
mode.

2016-10-13 14:21 GMT+07:00 mrkstt notifications@github.com:

Hi @ple13 https://github.com/ple13 @songuke <
https://github.com/songuke>
,

I solved the error above by commenting all "SOPHUS_ENSURE", seems
it's
just for checking.

Then, I run:

roslaunch launch/benchmark.launch dataset:=/home/ubuntu/dataset/
rgbd_dataset_freiburg3_cabinet_validation

Output:
ros.roscpp: { Tried to advertise a service that is already advertised
in
this node [/dvo_vis/image/compressedDepth/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised
in
this node [/dvo_vis/image/compressed/set_parameters] }
ros.roscpp: { Tried to advertise a service that is already advertised
in
this node [/dvo_vis/image/theora/set_parameters] }
ros.dvo_benchmark.config: { tracker config: "First Level = 3, Last

Level

1, Max Iterations per Level = 50, Precision = 0.0001, Mu = 0.05, Use
Initial Estimate = true, Use Weighting = true, Scale Estimator =
TDistribution, Scale Estimator Param = 5, Influence Function =
TDistribution, Influence Function Param = 5, Intensity Derivative
Threshold
= 0, Depth Derivative Threshold = 0" }
ros.dvo_benchmark.config: { frontend config: "UseMultiThreading: 1
MaxTranslationalDistance: 0.2 MaxRotationalDistance: 0
MinEntropyRatio:
0.6
MinEquationSystemConstraintRatio: 0.3" }
ros.dvo_benchmark.config: { backend config: "UseRobustKernel: 1
UseMultiThreading: 1 NewConstraintSearchRadius: 5
NewConstraintMinEntropyRatioCoarse: 0.03
NewConstraintMinEntropyRatioFi
ne:
0.6 MinEquationSystemConstraintRatio: 0.3 MinConstraintDistance: 0
OptimizationUseDenseGraph: 0 OptimizationIterations: 50
OptimizationRemoveOutliers: 1 OptimizationOutlierWeightThreshold:
0.1
FinalOptimizationUseDenseGraph: 1 FinalOptimizationIterations: 1000
FinalOptimizationRemoveOutliers: 1 FinalOptimizationOutlierWeight
Threshold:
0.1" }
ros.dvo_slam: { adding 0 new constraints }
ros.dvo_slam: { adding 1 new constraints }
ros.dvo_slam: { adding 2 new constraints }
ros.dvo_slam: { adding 3 new constraints }
ros.dvo_slam: { adding 4 new constraints }
ros.dvo_slam: { adding 5 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 6 new constraints }
new_kf: 0.0979787
ros.dvo_slam: { adding 6 new constraints }
ros.dvo_slam: { adding 9 new constraints }
ros.dvo_slam: { adding 11 new constraints }
ros.dvo_slam: { adding 7 new constraints }
ros.dvo_slam: { adding 8 new constraints }
ros.dvo_slam: { adding 9 new constraints }
match: 0.0492692

The only thing unsolved is I cannot see any result (empty) by
running:

rosrun rviz rviz

Any idea?


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
<#50
issuecomment-253434903
,
or mute the thread
<https://github.com/notifications/unsubscribe-
auth/AAIXsgpqjdzA8UDaf_
hP89eCUdAOMW5uks5qzdv3gaJpZM4KODT5>
.


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
<#50
issuecomment-253449258
,
or mute the thread
<https://github.com/notifications/unsubscribe-auth/AOXj5P_GYvG6-
z7WcbnvpokYLFIaSfFuks5qzeysgaJpZM4KODT5>
.


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
<#50 (comment)
,
or mute the thread
<https://github.com/notifications/unsubscribe-
auth/AAIXsrSX5wrEEnqVnug7u_YzEjb-HWrGks5qznZ4gaJpZM4KODT5>

.


You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub
#50 (comment),
or mute the thread
https://github.com/notifications/unsubscribe-auth/AOXj5BiN-1Y4SIRG94eR2pQ7Nendtk1Pks5qzoPjgaJpZM4KODT5
.