Git Product home page Git Product logo

mrpt / mrpt Goto Github PK

View Code? Open in Web Editor NEW
1.9K 115.0 622.0 290.56 MB

:zap: The Mobile Robot Programming Toolkit (MRPT)

Home Page: https://docs.mrpt.org/reference/latest/

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

Shell 0.07% CMake 1.85% C++ 71.18% C 22.32% NSIS 0.01% Makefile 0.01% MATLAB 0.03% Python 4.44% Batchfile 0.04% GLSL 0.06%
mrpt c-plus-plus mobile-robotics slam autonomous-driving computer-vision mobile-robots maps robot-programming robot-motion-estimate robot-framework particle-filter robotics

mrpt's Introduction

The MRPT project

CI Check clang-format

DOI

1. Introduction

Mobile Robot Programming Toolkit (MRPT) provides C++ libraries aimed at researchers in mobile robotics and computer vision. Libraries include SLAM solutions, 2D and 3D spatial transformations, SE(2)/SE(3) Lie groups, probability density functions (pdfs) over points, landmarks, poses and maps, Bayesian inference (Kalman filters, particle filters), image processing, obstacle avoidance, etc. MRPT also provides GUI apps for camera calibration, dataset inspection, and much more.

2. Resources

3. Install

3.1. Ubuntu/Debian

Install simply with sudo apt install libmrpt-dev mrpt-apps, but check first what MRPT version exists in your Ubuntu or Debian (tracker) distribution.

If you want a more recent version, check out this PPA for nightly builds from the develop branch, or this one for stable releases.

    sudo add-apt-repository ppa:joseluisblancoc/mrpt   # develop branch
    #sudo add-apt-repository ppa:joseluisblancoc/mrpt-stable   # master (stable releases) branch
    sudo apt install libmrpt-dev mrpt-apps

Supported distributions:

  • Ubuntu 18.04 LTS (Bionic), Ubuntu 20.04 LTS (Focal), or newer.

3.2. Build from sources

See build documentation (source).

3.3. Windows precompiled versions

Executables (.exes and .dlls) and development libraries (.hs and .libs) included:

Nightly built Windows installer

3.4. As a ROS1/ROS2 package

MRPT is also shipped as a ros1 & ros2 package named mrpt2, so it can be installed via:

sudo apt install ros-$ROS_DISTRO-mrpt2

mrpt2 status in ROS build farms:

Distro develop branch Stable release Next builds
ROS1 Noetic @ u20.04 Build Status Version Build Status
ROS2 Humble @ u22.04 Build Status Version Build Status
ROS2 Iron @ u22.04 Build Status Version Build Status
ROS2 Rolling @ u24.04 Build Status Version Build Status
EOL Distro Last release
ROS1 Melodic @ u18.04 Version
ROS2 Foxy @ u20.04 Version

4. License

MRPT is released under the new BSD license.

Contributors

5. Versions in repositories

Repology

mrpt's People

Contributors

alibend avatar arashpartow avatar bellonemauro avatar bergercookie avatar corot avatar dependabot[bot] avatar edufdez avatar emilkhatib avatar famoreno avatar gyengera avatar hlzz avatar jbriales avatar jgmonroy avatar jlblancoc avatar jolting avatar jotaraul avatar lasdasdas avatar lisgein avatar logrus avatar marianojt88 avatar miguelcastillon avatar mlopezantequera avatar nikolausdemmel avatar olzhas avatar piponazo avatar raghavendersahdev avatar randvoorhies avatar sem23 avatar swt2c avatar yuya-oc avatar

Stargazers

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

Watchers

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

mrpt's Issues

setup failed;

mrpt is not installing on my pc as setup is repeatedly failing due to error opening the installation log file to which access is denied to me.Kindly help me out with this situation as I need the software urgently.Thanks in advance.

mrpt seems to expect an old jpeglib

With MRPT 1.1.0 on a Linux-System with 32 bit architecture I get the following error message during runtime:

"Wrong JPEG library version: library is 62,caller expects 80"

The error appears when I try to save a 3d-Observation to a file.

CSensoryFrame SF;
cam.getNextObservation(obs,there_is_obs,hard_error);
CObservation3DRangeScanPtr obs_3d = (mrpt::slam::CObservation3DRangeScanPtr) obs.duplicateGetSmartPtr();
SF.insert(obs_3d);

mrpt_f << SF;

This code works well on a Linux-System with 64 bit architecture and MRPT 1.0.2.

There is no libjpeg.so.62 installed in the system. libjpeg.so is a link to libjpeg.so.8.0.2
During configuration the cmake-gui checks that libjpeg is installed.

The system libraries did not change after configuration and compilation of mrpt.

With ldd I see that my program uses the libjpeg.so.8.0.2 from the system.

I see that in the mrpt source directory there is a path

/libs/base/src/utils/jpeglib
wich seems to include the 62 version of jpeg.
Perhaps this is the clue?

Installing a 6.2 libjpeg packet parallel to the 8.0.2 does not help.
Reconfiguration and recompilation of MRPT does not help either.

As I am unable to login into the issue tracker I like to send you this informations via e-mail.

It would be great if you could help.

Best regards

Markus Wenzel

kinect-3d-view/kinect-3d-slam is crashing on ARM

What steps will reproduce the problem?

  1. Compile/Install mrpt with Kinect support
  2. Run Kinect-3d-view
  3. Will get SIGSEGV

Stack trace from gdb:

Program received signal SIGBUS, Bus error.
[Switching to Thread 0x2f9032b0 (LWP 6370)]
0x2adccc94 in mrpt::opengl::COctreePointRenderermrpt::opengl::CPointCloudColoured::internal_recursive_split(unsigned int, bool) ()
from /usr/lib/libmrpt-opengl.so.0.9
(gdb) bt
#0 0x2adccc94 in mrpt::opengl::COctreePointRenderermrpt::opengl::CPointCloudColoured::internal_recursive_split(unsigned int, bool) ()

from /usr/lib/libmrpt-opengl.so.0.9
#1 0x2adc7aac in mrpt::opengl::CPointCloudColoured::render() const ()

from /usr/lib/libmrpt-opengl.so.0.9
#2 0x2ad9d410 in mrpt::opengl::gl_utils::renderSetOfObjects(std::deque<mrpt::opengl::CRenderizablePtr, std::allocatormrpt::opengl::CRenderizablePtr > const&) () from /usr/lib/libmrpt-opengl.so.0.9
#3 0x00035000 in ?? ()
#4 0x00035000 in ?? ()

Backtrace stopped: previous frame identical to this frame (corrupt stack?)
(gdb)

We use Ubuntu on UDOO board (armv7). We tried it also on Raspberry Pi (armv6). We tried also armel/armhf. On Raspberry PI the Kinect read of Depth/RGB was faked by fakenect, but we still get the same exception as on UDOO. On UDOO the data from Kinect are read and displayed, but it crashes on above function.

We had tried our builds and also official build. So version GIT/1.0.2/0.9 was tried.

We tried to compile on X86 platform and it worked. So only on ARM is it not working.

getPCLPointCloud output cannot be displayed by PCL CloudViewer

Code that works:

pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = pclTool.ConvertMatToPointCloud(xyzImg, bgrImg);
if (!pclTool.viewer->wasStopped()) {
                      pclTool.DisplayPointCloud(cloud, "cloud1");
}

Code that doesn't work (displays a black screen):

pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = pclTool.ConvertMatToPointCloud(xyzImg, bgrImg);
mrpt::slam::CColouredPointsMap tmpCpm;
tmpCpm.setFromPCLPointCloudRGB(*cloud);
if (!pclTool.viewer->wasStopped()) {
                      pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpCloud(new pcl::PointCloud<pcl::PointXYZRGB>());
                      tmpCpm.getPCLPointCloud(*tmpCloud);
                      pclTool.DisplayPointCloud(tmpCloud, "cloud2");
}

Phidgets libs

TO DO: Better detection of Phidgets libs in both Windows & Linux.

error compiling MRPT from svn [EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET]

I've just updated my MRPT version from svn and re-compiled and I got this error:

[ 61%] Building CXX object libs/vision/CMakeFiles/mrpt-vision.dir/src/CDifodo.cpp.o
In file included from /home/mauro/Downloads/MRPT/mrpt/libs/vision/include/mrpt/vision/CDifodo.h:15:0,
from /home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:11:
/usr/include/eigen3/Eigen/Sparse:19:2: error: #error The sparse module API is not stable yet. To use it anyway, please define the EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET preprocessor token.
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp: In member function ‘void mrpt::vision::CDifodo::solveDepthSystem()’:
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:332:10: error: ‘Triplet’ was not declared in this scope
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:332:23: error: template argument 1 is invalid
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:332:23: error: template argument 2 is invalid
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:332:25: error: expected unqualified-id before ‘>’ token
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:357:5: error: ‘coord’ was not declared in this scope
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:357:29: error: expected primary-expression before ‘float’
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:358:29: error: expected primary-expression before ‘float’
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:359:29: error: expected primary-expression before ‘float’
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:360:29: error: expected primary-expression before ‘float’
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:361:29: error: expected primary-expression before ‘float’
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:362:29: error: expected primary-expression before ‘float’
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:354:17: warning: unused variable ‘dxcomp’ [-Wunused-variable]
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:355:17: warning: unused variable ‘dycomp’ [-Wunused-variable]
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:370:4: error: ‘class Eigen::SparseMatrix’ has no member named ‘setFromTriplets’
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:370:20: error: ‘coord’ was not declared in this scope
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:375:2: error: ‘SimplicialLDLT’ was not declared in this scope
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:375:37: error: expected primary-expression before ‘>’ token
/home/mauro/Downloads/MRPT/mrpt/libs/vision/src/CDifodo.cpp:375:39: error: ‘SparseCholesky’ was not declared in this scope
make[2]: *** [libs/vision/CMakeFiles/mrpt-vision.dir/src/CDifodo.cpp.o] Error 1
make[1]: *** [libs/vision/CMakeFiles/mrpt-vision.dir/all] Error 2
make: *** [all] Error 2

KFSLAM working?

I use a slightly modified MRPT 1.1.0 version and get the following error. Can you reproduce it?

C:\Dev\MRPT\1.1.0\share\mrpt\config_files\kf-slam>C:\Dev\MRPT\1.1.0\bin\Release
kf-slam.exe C:\Dev\MRPT\1.1.0\share\mrpt\config_files\kf-slam\EKF-SLAM_test.ini

kf-slam - Part of the MRPT

MRPT C++ Library: MRPT 1.1.0 - BUILD DATE Mar 3 2014

RAWLOG FILE:

../../datasets/kf-slam_demo.rawlog

----------- [TKF_options] ------------

method = kfEKFNaive
verbose = Y
IKF_iterations = 5
enable_profiler = N

----------- [CRangeBearingKFSLAM::TOptions] ------------

doPartitioningExperiment = N
partitioningMethod = 0
data_assoc_method = assocNN
data_assoc_metric = metricMaha
data_assoc_IC_chi2_thres = 0.990000
data_assoc_IC_metric = metricMaha
data_assoc_IC_ml_threshold = 0.000000

Mean pose:
(x,y,z,qr,qx,qy,qz)=(0.0000,0.0000,0.0000,1.0000,0.0000,0.0000,0.0000)

of landmarks in the map: 24

Step 0 - Rawlog entries processed: 3

=============== MRPT EXCEPTION =============
mrpt::slam::CRangeBearingKFSLAM::OnNormalizeStateVector, line 687:
Vehicle pose quaternion norm is not >0!!
mrpt::slam::CRangeBearingKFSLAM::OnNormalizeStateVector, line 695:
mrpt::bayes::CKalmanFilterCapable<7,3,3,7,double>::runOneKalmanIteration, line 1
520:
mrpt::slam::CRangeBearingKFSLAM::processActionObservation, line 253:

Program finished for an exception!!
Press any key to continue...

Crash in test MonteCarlo2D.RunSampleDataset under 32 bits builds

From buildlog in Ubuntu PPA machines:

[==========] Running 5 tests from 3 test cases.
[----------] Global test environment set-up.
[----------] 1 test from MonteCarlo2D
[ RUN ] MonteCarlo2D.RunSampleDataset
test_mrpt_slam: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:131: Eigen::CwiseBinaryOp<BinaryOp, Lhs, Rhs>::CwiseBinaryOp(const Lhs&, const Rhs&, const BinaryOp&) [with BinaryOp = Eigen::internal::scalar_product_op<float, float>; Lhs = const Eigen::ArrayWrapper<const Eigen::Map<Eigen::Matrix<float, -1, 1>, 0, Eigen::Stride<0, 0> > >; Rhs = const Eigen::ArrayWrapper<const Eigen::Matrix<float, -1, 1> >]: Assertion `aLhs.rows() == aRhs.rows() && aLhs.cols() == aRhs.cols()' failed.
Aborted

building on OS X 10.9

there are some problems when building for OS X 10.9 (clang-500.2.79).

It seems that it has to do primarily with linking.
Editing this line to allow not only GCC makes it possible to proceed further, but then I get undefined references to (so it seems) OpenCV (even though it is installed):

--  Has OpenCV (Image manipulation)          : Yes (System) [Version: 2.4.6.1, Has non-free: 1]

Error log:

Linking CXX shared library ../../lib/libmrpt-vision.dylib
clang: warning: argument unused during compilation: '-pthread'
Undefined symbols for architecture x86_64:
  "cv::FeatureDetector::detect(cv::Mat const&, std::vector<cv::KeyPoint, std::allocator<cv::KeyPoint> >&, cv::Mat const&) const", referenced from:
      mrpt::vision::CFeatureExtraction::extractFeaturesFAST(mrpt::utils::CImage const&, mrpt::vision::CFeatureList&, unsigned int, unsigned int, mrpt::vision::TImageROI const&, mrpt::math::CMatrixTemplate<bool> const*) const in CFeatureExtraction_FAST.cpp.o
      mrpt::vision::CFeatureExtraction::extractFeaturesSIFT(mrpt::utils::CImage const&, mrpt::vision::CFeatureList&, unsigned int, unsigned int, mrpt::vision::TImageROI const&) const in CFeatureExtraction_SIFT.cpp.o
  "cv::DescriptorExtractor::compute(cv::Mat const&, std::vector<cv::KeyPoint, std::allocator<cv::KeyPoint> >&, cv::Mat&) const", referenced from:
      mrpt::vision::CFeatureExtraction::extractFeaturesSIFT(mrpt::utils::CImage const&, mrpt::vision::CFeatureList&, unsigned int, unsigned int, mrpt::vision::TImageROI const&) const in CFeatureExtraction_SIFT.cpp.o
ld: symbol(s) not found for architecture x86_64
clang: error: linker command failed with exit code 1 (use -v to see invocation)
make[2]: *** [lib/libmrpt-vision.1.0.3.dylib] Error 1
make[1]: *** [libs/vision/CMakeFiles/mrpt-vision.dir/all] Error 2
make: *** [all] Error 2

Error with macro ASSERT_NOT_EQUAL_

Hi, I have installed mrpt v1.02 and I want compile the examples of srba but the compiler give me the following error:

Error 1 error C2678: binary '<<' : no operator found which takes a left-hand operand of type 'std::basic_ostream<char,std::char_traits>' (or there is no acceptable conversion) c:\program files (x86)\mrpt-1.0.2\libs\srba\include\mrpt\srba\impl\spantree_update_symbolic.h 143 1 tutorial-srba-stereo-se3

I'm using MVS2013. Any idea of what's wrong with me?
Thanks,
Maikel

TO DO: rawlog-edit new op

Allow recalculating odometry increments from encoders and new odometry parameters with rawlog-edit.

FTBFS in Visual Studio 2013

Description:

libs\hwdrivers\src\CImpinjRFID.cpp(74): error C2678: binary '<<' : no operator found which takes a left-hand operand of type 'std::basic_ostream<char,std::char_traits>' (or there is no acceptable conversion)

Compilation issues

Hello!

I encountered a few compilation problems:

Scanning dependencies of target prrt-navigator-demo
[ 70%] Building CXX object apps/prrt-navigator-demo/CMakeFiles/prrt-navigator-demo.dir/prrtnavdemoApp.cpp.o
In file included from /home/lefty/Stahování/mrpt-1.1.0/apps/prrt-navigator-demo/prrtnavdemoMain.h:27:0,
                 from /home/lefty/Stahování/mrpt-1.1.0/apps/prrt-navigator-demo/prrtnavdemoApp.cpp:14:
/home/lefty/Stahování/mrpt-1.1.0/libs/reactivenav/include/mrpt/reactivenav/CPRRTNavigator.h:12:23: fatal error: mrpt/maps.h: File or directory not found
 #include <mrpt/maps.h>
  • pf-localization
Linking CXX executable ../../bin/pf-localization
[ 74%] Built target pf-localization
Scanning dependencies of target ReactiveNavigationDemo
[ 74%] Building CXX object apps/ReactiveNavigationDemo/CMakeFiles/ReactiveNavigationDemo.dir/ReactiveNavigationDemoApp.cpp.o
[ 75%] Building CXX object apps/ReactiveNavigationDemo/CMakeFiles/ReactiveNavigationDemo.dir/ReactiveNavigationDemoMain.cpp.o
/home/lefty/Stahování/mrpt-1.1.0/apps/ReactiveNavigationDemo/ReactiveNavigationDemoMain.cpp:84:23: fatal error: mrpt/maps.h: Adresář nebo soubor neexistuje
 #include <mrpt/maps.h>
                       ^

After that, I gave up. I will try it again tonight.

src dir: /home/lefty/Stahování/mrpt-1.1.0/
build dir: /home/lefty/matfyz/bakalarka/mrpt-1.1.0/

config: http://pastebin.com/fk60k22N

Export odometry

Need new function on rawlogedit to export odometry data from rawlog to txt for postprocessing

FTBS MSVC11: conflicting usb.h files?

It seems usb.h files are conflicting between Windows SDK & libusb??

\libs\hwdrivers\src\xSens_MT4\xcommunication\src\usbinterface.cpp(638): error C2039: 'PipeType' : is not a member of '_WINUSB_PIPE_INFORMATION'
5> C:\Program Files (x86)\Windows Kits\8.0\Include\shared\winusbio.h(79) : see declaration of '_WINUSB_PIPE_INFORMATION'

Building on the MaxOSX: ambigous function call

Error is as follows:
[ 70%] Building CXX object libs/hwdrivers/CMakeFiles/mrpt-hwdrivers.dir/src/aria/src/ArAction.cpp.o
In file included from //mrpt-git/libs/hwdrivers/src/aria/src/ArAction.cpp:12:
In file included from //mrpt-git/libs/hwdrivers/src/aria/include/ArResolver.h:14:
In file included from //mrpt-git/libs/hwdrivers/src/aria/include/ArActionDesired.h:13:
//mrpt-git/libs/hwdrivers/src/aria/include/ariaUtil.h:773:31: error: call to 'abs' is ambiguous
if (ms < 0 && (unsigned)std::abs(ms) > timeThis)
^~~~~~~~
/Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/bin/../lib/c++/v1/cmath:660:1: note: candidate function
abs(float __x) _NOEXCEPT {return fabsf(__x);}
^
/Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/bin/../lib/c++/v1/cmath:664:1: note: candidate function
abs(double __x) _NOEXCEPT {return fabs(__x);}
^
/Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/bin/../lib/c++/v1/cmath:668:1: note: candidate function
abs(long double __x) _NOEXCEPT {return fabsl(__x);}
^
1 error generated.
make[2]: *** [libs/hwdrivers/CMakeFiles/mrpt-hwdrivers.dir/src/aria/src/ArAction.cpp.o] Error 1
make[1]: *** [libs/hwdrivers/CMakeFiles/mrpt-hwdrivers.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....

---- until - here ----
Solved by casting ms to double in file
libs/hwdrivers/src/aria/include/ariaUtil.h
line 773
if (ms < 0 && (unsigned)std::abs((double)ms) > timeThis)

After that - build succeeded.

Missing keystroke events in the CDisplayWindow class

What steps will reproduce the problem?

  1. Create a CDisplayWindow object
  2. Subscribe to events
  3. Push any key on the window

What is the expected output? What do you see instead?

Should receive events, but it won't.

libwxgtk*.so seem to leak

As detected by valgrind at program final clean up:

==3865== Invalid read of size 8
==3865== at 0x63EB547: wcscmp (wcscmp.S:230)
==3865== by 0x76BE269: wxHashTableBase::DoDelete(wchar_t const_, long) (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x76D29FB: wxClassInfo::Unregister() (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x6384479: cxa_finalize (cxa_finalize.c:55)
==3865== by 0x9F32F52: ??? (in /home/jlblanco/code/mrpt-release/lib/libmrpt-gui.so.1.1.1)
==3865== by 0x400FF26: dl_fini (dl-fini.c:253)
==3865== by 0x6384070: run_exit_handlers (exit.c:77)
==3865== by 0x63840F4: exit (exit.c:99)
==3865== by 0x6369DEB: (below main) (libc-start.c:294)
==3865== Address 0x1917bc38 is 24 bytes inside a block of size 28 alloc'd
==3865== at 0x4C2AFE7: operator new[](unsigned long) (in /usr/lib/valgrind/vgpreload_memcheck-amd64-linux.so)
==3865== by 0x76BDC87: wxHashTableBase_Node::wxHashTableBase_Node(wchar_t const
, void
, wxHashTableBase
) (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x76BDE9A: wxHashTableBase::DoPut(wchar_t const
, long, void
) (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x76D2BEC: wxClassInfo::Register() (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x9F32563: _GLOBAL__sub_I_mathplot.cpp (in /home/jlblanco/code/mrpt-release/lib/libmrpt-gui.so.1.1.1)
==3865== by 0x400F855: call_init.part.0 (dl-init.c:84)
==3865== by 0x400F90F: _dl_init (dl-init.c:55)
==3865== by 0x4001669: ??? (in /lib/x86_64-linux-gnu/ld-2.17.so)
==3865==
==3865== Invalid read of size 8

Grab displayed image on CDisplayWindow3D

Hello,

First of all I want to thank for your great work on MRPT.
It's a huge help on my project.

I hope it is the right place to ask this question.

I would like to know how to grab the current image displaying on a CDisplayWindow3D.
I tried getLastWindowImage() but although it returns true and an image with the right size, the image is all gray with one white block at the top left ( saved image with CImage::saveToFile )
When i try with getLastWindowImagePtr(), I always obtain a null pointer...
My code is basically :
class myClass :
{
public :
myClass(){
m_3DWnd = new CDisplayWindow3D("Title",1280,1024) ;
m_3DWnd->captureImagesStart();
};

   void main_function
  {
                     for(;;)
                     {
                       /* operations to create newData */                              
                       updateDisplay( newData );
                      }
                      m_3DWnd->captureImagesStop();
  };

  void updateDisplay
  {
       COpenGLScenePtr &scenePtr = m_3DWnd->get3DSceneAndLock();
       COpenGLScenePtr newScene = COpenGLScene::Create();


        /* Add  some stuff to newScene  */

       scenePtr = newScene;
       m_3DWnd->unlockAccess3DScene();
       m_3DWnd->forceRepaint();
  };
   private :
    CDisplayWindow3D* m_3DWnd;

};

What I am doing wrong ?
Thank you in advance

Can't compile a minimal external app with GCC 4.8 unless 'SUITESPARSE_USE_FIND_MODULE' is set to 'OFF' when compiling MRPT

Unless I disable SUITESPARSE_USE_FIND_MODULE when compiling MRPT, my external apps (not in the MRPT directory tree) won't compile. (on commit jlblancoc@3c64c26 & gcc version 4.8.1 (Ubuntu/Linaro 4.8.1-10ubuntu9))

This is a minimal 'non-working' example:

CMakeLists.txt:

cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
project(minex)
FIND_PACKAGE(MRPT REQUIRED base;gui;slam)

add_executable(minex minex.cpp)
TARGET_LINK_LIBRARIES(minex
        ${MRPT_LIBS}  # This is filled by FIND_PACKAGE(MRPT ...)
        ""
        )

minex.cpp:

#include <mrpt/base.h>
int main (){
return (0);
}

make output

In file included from /home/mlopez/templibs/mrpt/libs/base/include/mrpt/math.h:42:0,
                 from /home/mlopez/templibs/mrpt/libs/base/include/mrpt/base.h:24,
                 from /home/mlopez/templibs/minimal_example/minex.cpp:1:
/home/mlopez/templibs/mrpt/libs/base/include/mrpt/math/CSparseMatrix.h:24:17: fatal error: cs.h: No such file or directory
 # include "cs.h"
                 ^
compilation terminated.
make[2]: *** [CMakeFiles/minex.dir/minex.cpp.o] Error 1
make[1]: *** [CMakeFiles/minex.dir/all] Error 2
make: *** [all] Error 2

After recompiling mrpt with SUITESPARSE_USE_FIND_MODULE = OFF, I can compile the app.

libwxgtk*.so seem to leak

Example output from valgrind:

==3865== Invalid read of size 8
==3865== at 0x63EB547: wcscmp (wcscmp.S:230)
==3865== by 0x76BE269: wxHashTableBase::DoDelete(wchar_t const_, long) (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x76D29FB: wxClassInfo::Unregister() (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x6384479: cxa_finalize (cxa_finalize.c:55)
==3865== by 0x9F32F52: ??? (in /home/jlblanco/code/mrpt-release/lib/libmrpt-gui.so.1.1.1)
==3865== by 0x400FF26: dl_fini (dl-fini.c:253)
==3865== by 0x6384070: run_exit_handlers (exit.c:77)
==3865== by 0x63840F4: exit (exit.c:99)
==3865== by 0x6369DEB: (below main) (libc-start.c:294)
==3865== Address 0x1917bc38 is 24 bytes inside a block of size 28 alloc'd
==3865== at 0x4C2AFE7: operator new[](unsigned long) (in /usr/lib/valgrind/vgpreload_memcheck-amd64-linux.so)
==3865== by 0x76BDC87: wxHashTableBase_Node::wxHashTableBase_Node(wchar_t const
, void
, wxHashTableBase
) (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x76BDE9A: wxHashTableBase::DoPut(wchar_t const
, long, void
) (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x76D2BEC: wxClassInfo::Register() (in /usr/lib/x86_64-linux-gnu/libwx_baseu-2.8.so.0.8.0)
==3865== by 0x9F32563: _GLOBAL__sub_I_mathplot.cpp (in /home/jlblanco/code/mrpt-release/lib/libmrpt-gui.so.1.1.1)
==3865== by 0x400F855: call_init.part.0 (dl-init.c:84)
==3865== by 0x400F90F: _dl_init (dl-init.c:55)
==3865== by 0x4001669: ??? (in /lib/x86_64-linux-gnu/ld-2.17.so)
==3865==
==3865== Invalid read of size 8

...

Extension of the mrpt::utils::TRuntimeClassId to support classes from different namespaces having identical names

(Original report in Google code: https://code.google.com/p/mrpt/issues/detail?id=23 )

Reported by [email protected], Mar 1, 2012
If two objects from classes with identical names but different namespace are used, the run-time type identification is not able differ them, as only the classes' name but not their namespace is integrated in their class ID. Instead, the classes' namespace should be integrated, too. An example:

#define IMPLEMENTS_MRPT_OBJECT2(class_name, base, NameSpace, NameSpaceBase) \
            mrpt::utils::CObject* NameSpace::class_name::CreateObject() \
                { return static_cast<mrpt::utils::CObject*>( new NameSpace::class_name ); } \
            NameSpace::class_name##Ptr NameSpace::class_name::Create() \
                { return NameSpace::class_name##Ptr( new NameSpace::class_name ); } \
            const mrpt::utils::TRuntimeClassId* NameSpace::class_name::_GetBaseClass() \
                { return CLASS_ID_NAMESPACE(base, NameSpaceBase); } \
            mrpt::utils::TRuntimeClassId NameSpace::class_name::class##class_name = { \
                #NameSpace"::"#class_name, NameSpace::class_name::CreateObject, &class_name::_GetBaseClass }; \
            const mrpt::utils::TRuntimeClassId *NameSpace::class_name::classinfo = & NameSpace::class_name::class##class_name; \
            const mrpt::utils::TRuntimeClassId* NameSpace::class_name::GetRuntimeClass() const \
            { return CLASS_ID_NAMESPACE(class_name,NameSpace); } \
            mrpt::utils::CLASSINIT NameSpace::class_name::_init_##class_name(CLASS_ID_NAMESPACE(base, NameSpaceBase)); \
            mrpt::utils::CObject * NameSpace::class_name::duplicate() const \
            { return static_cast<mrpt::utils::CObject*>( new NameSpace::class_name(*this) ); }

Fix dpkg-shlibdeps warnings

More selective linking of .so files, to fix all these warnings:


dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-base1.2/usr/lib/x86_64-linux-gnu/libmrpt-base.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-opengl1.2.substvars debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-opengl1.2/usr/lib/x86_64-linux-gnu/libmrpt-opengl.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-gui1.2.substvars debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-gui1.2/usr/lib/x86_64-linux-gnu/libmrpt-gui.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-obs1.2.substvars debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libmrpt-opengl.so.1.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-obs1.2/usr/lib/x86_64-linux-gnu/libmrpt-obs.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-maps1.2.substvars debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-maps1.2/usr/lib/x86_64-linux-gnu/libmrpt-maps.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-hwdrivers1.2.substvars debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hwdrivers1.2/usr/lib/x86_64-linux-gnu/libmrpt-hwdrivers.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-vision1.2.substvars debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-vision1.2/usr/lib/x86_64-linux-gnu/libmrpt-vision.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-scanmatching1.2.substvars debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libpthread.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-scanmatching1.2/usr/lib/x86_64-linux-gnu/libmrpt-scanmatching.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-topography1.2.substvars debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libmrpt-opengl.so.1.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-topography1.2/usr/lib/x86_64-linux-gnu/libmrpt-topography.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-detectors1.2.substvars debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libmrpt-scanmatching.so.1.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libmrpt-vision.so.1.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libmrpt-slam.so.1.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-detectors1.2/usr/lib/x86_64-linux-gnu/libmrpt-detectors.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-slam1.2.substvars debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-slam1.2/usr/lib/x86_64-linux-gnu/libmrpt-slam.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-reactivenav1.2.substvars debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libmrpt-opengl.so.1.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-reactivenav1.2/usr/lib/x86_64-linux-gnu/libmrpt-reactivenav.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-hmtslam1.2.substvars debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libmrpt-scanmatching.so.1.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libmrpt-vision.so.1.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-hmtslam1.2/usr/lib/x86_64-linux-gnu/libmrpt-hmtslam.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps -Tdebian/libmrpt-kinematics1.2.substvars debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libdc1394.so.22 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_video.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libz.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_flann.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libwx_gtk2u_core-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libwx_gtk2u_gl-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libGLU.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libGL.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libswscale.so.2 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libftdi.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_videostab.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libavformat.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_photo.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libavcodec.so.55 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_stitching.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_calib3d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libjpeg.so.8 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_superres.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libusb-0.1.so.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_objdetect.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libwx_baseu-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libwx_gtk2u_aui-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libwx_gtk2u_html-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_gpu.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libwx_gtk2u_adv-3.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libavutil.so.53 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libglut.so.3 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_features2d.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_contrib.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libusb-1.0.so.0 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_highgui.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_ocl.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against librt.so.1 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_imgproc.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_legacy.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_core.so.2.4 (it uses none of the library's symbols)
dpkg-shlibdeps: warning: package could avoid a useless dependency if debian/libmrpt-kinematics1.2/usr/lib/x86_64-linux-gnu/libmrpt-kinematics.so.1.2.0 was not linked against libopencv_ml.so.2.4 (it uses none of the library's symbols)

OSX bayesianTracking

I have the next error when i try to compile te bayesianTracking example

In file included from /Users/aslan/Documents/mrpt-git/samples/bayesianTracking/test.cpp:14:
/usr/local/include/mrpt/bayes/include/mrpt/bayes/CKalmanFilterCapable.h:1438:8: error: invalid use of incomplete type 'detail::CRunOneKalmanIteration_addNewLandmarks'
detail::CRunOneKalmanIteration_addNewLandmarks()(this, Z, data_association,R);
^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/local/include/mrpt/bayes/include/mrpt/bayes/CKalmanFilterCapable.h:56:10: note: forward declaration of 'mrpt::bayes::detail::CRunOneKalmanIteration_addNewLandmarks'
struct CRunOneKalmanIteration_addNewLandmarks;
^
In file included from /Users/aslan/Documents/mrpt-git/samples/bayesianTracking/test.cpp:22:
/usr/local/include/mrpt/base/include/mrpt/math/distributions.h:204:6: error: no viable overloaded '
='
Hc_=1.0/ mrpt::math::maximum(Hc);
~~^ ~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2 errors generated.
make[2]: *_* [CMakeFiles/bayesianTracking.dir/test.o] Error 1
make[1]: *** [CMakeFiles/bayesianTracking.dir/all] Error 2
make: *** [all] Error 2

I am working on Maveriks 10.9.4

Fix "fatal error LNK1281: Unable to generate SAFESEH image" in x86 with ffmpeg

Fix this error, linking against ffmpeg libs in x86:

4>avcodec.lib(dlmlbs00093.o) : error LNK2026: module unsafe for SAFESEH image.
4>avcodec.lib(dlmlbs00140.o) : error LNK2026: module unsafe for SAFESEH image.
...
1.0.3\mrpt-1.0.3-msvc11-x32\bin\Debug\libmrpt-hwdrivers103-dbg.dll : fatal error LNK1281: Unable to generate SAFESEH image.

Unable to convert from PCL XYZRGB to CColouredPointsMap

Here's my code:

    mrpt::utils::PointCloudAdapter<pcl::PointCloud<pcl::PointXYZRGB>> pca(*cloud);
    mrpt::slam::CColouredPointsMap cpm;
    cpm.setFromPCLPointCloudRGB(pca);

Inheritance suggests that this should work (as PointCloudAdapter does inherit from POINTCLOUD), but when compiling on VC++2010, I get this. Is this how I'm supposed to be doing the conversion?

Unnamed semaphores do not work on OS X

Unfortunately, Apple isn't fully POSIX compliant, as they don't implement unnamed semaphores through the POSIX interface. sem_init is implemented, but will always fail with ENOSYS (function not implemented). This causes an exception to be thrown in CSemaphore_LIN.cpp on line 80.

I have created an implementation of an Apple specific semaphore (CSemaphore_APP.cpp), but have not had time to fully test it yet: https://github.com/randvoorhies/mrpt/tree/osx-semaphore-fix. I would feel more comfortable doing a pull request if there were unit tests for CSemaphore.

As a side note, MRPT might want to consider using Boost's platform-independent semaphore implementation: http://www.boost.org/doc/libs/1_55_0/doc/html/interprocess/synchronization_mechanisms.html

CMake system: check apps deps

Disabling the compilation of some MRPT module/library should imply automatically disabling the building of dependent apps.
Related bug: #48

Problems when MRPT autodetect SSE optimization level

I'm using Ubuntu 14.04 (64 bits) and my processor is an AMD Phenom(tm) II X6 1035T. My problem arises as a consequence of a bad self-detection of SSE optimization level when "MRPT_AUTODETECT_SSE" is ticked as a CMake option. Removing this option and setting "DISABLE_SSE4" by hand solves this problem.

I have discovered this issue after not being able to execute any program including a Window for visualizing 3D Scenes (I got SIGSEGV) in release mode, whereas everything worked fine in debug mode.

Processor info:

processor : 0-5
vendor_id : AuthenticAMD
cpu family : 16
model : 10
model name : AMD Phenom(tm) II X6 1035T Processor
stepping : 0
microcode : 0x10000bf
cpu MHz : 800.000
cache size : 512 KB
physical id : 0
siblings : 6
core id : 0
cpu cores : 6
apicid : 0
initial apicid : 0
fpu : yes
fpu_exception : yes
cpuid level : 6
wp : yes
flags : fpu vme de pse tsc msr pae mce cx8 apic sep mtrr pge mca cmov pat pse36 clflush mmx fxsr sse sse2 ht syscall nx mmxext fxsr_opt pdpe1gb rdtscp lm 3dnowext 3dnow constant_tsc rep_good nopl nonstop_tsc extd_apicid aperfmperf pni monitor cx16 popcnt lahf_lm cmp_legacy svm extapic cr8_legacy abm sse4a misalignsse 3dnowprefetch osvw ibs skinit wdt cpb hw_pstate npt lbrv svm_lock nrip_save pausefilter
bogomips : 5200.33
TLB size : 1024 4K pages
clflush size : 64
cache_alignment : 64
address sizes : 48 bits physical, 48 bits virtual
power management: ts ttp tm stc 100mhzsteps hwpstate cpb

pbmap compile fails on MSVC++10

The precompiled header for all source files in pbmap does not appear to be working in VC++ 2010. Disabling precompiled headers fixed this.

After this, Miscellaneous.h (lines 168 and 196) and Plane.cpp (lines 467-469) don't compile because of ambiguous method parameters. Casting all the parameters to double fixes this.

Building error

After the cmake command, I run make and:

[ 8%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CCanvas.cpp.o
[ 8%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CLog.cpp.o
[ 9%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/TColor.cpp.o
[ 9%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/TCamera.cpp.o
[ 9%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CReferencedMemBlock.cpp.o
[ 9%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/types.cpp.o
[ 9%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CFileInputStream.cpp.o
[ 9%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/TMatchingPair.cpp.o
[ 9%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CRobotSimulator.cpp.o
[ 9%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CConfigFile.cpp.o
[ 10%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CEnhancedMetaFile_LIN.cpp.o
[ 10%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/TStereoCamera.cpp.o
[ 10%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CFileGZInputStream.cpp.o
[ 10%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CDynamicGrid.cpp.o
[ 10%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CSimpleDatabase.cpp.o
[ 10%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CPropertiesValuesList.cpp.o
[ 10%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CMemoryChunk.cpp.o
[ 10%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/md5.cpp.o
[ 11%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CStartUpClassesRegister.cpp.o
[ 11%] Building CXX object libs/base/CMakeFiles/mrpt-base.dir/src/utils/CImage_JPEG_streams.cpp.o
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:1750:53: error: ‘cv::EM’ has not been declared
CvEMParams( int nclusters, int cov_mat_type=cv::EM::COV_MAT_DIAGONAL,
^
/usr/include/opencv2/legacy/legacy.hpp:1751:36: error: ‘cv::EM’ has not been declared
int start_step=cv::EM::START_AUTO_STEP,
^
/usr/include/opencv2/legacy/legacy.hpp:1767:1: error: expected class-name before ‘{’ token
{
^
/usr/include/opencv2/legacy/legacy.hpp:1770:34: error: ‘cv::EM’ has not been declared
enum { COV_MAT_SPHERICAL=cv::EM::COV_MAT_SPHERICAL,
^
/usr/include/opencv2/legacy/legacy.hpp:1771:34: error: ‘cv::EM’ has not been declared
COV_MAT_DIAGONAL =cv::EM::COV_MAT_DIAGONAL,
^
/usr/include/opencv2/legacy/legacy.hpp:1772:34: error: ‘cv::EM’ has not been declared
COV_MAT_GENERIC =cv::EM::COV_MAT_GENERIC };
^
/usr/include/opencv2/legacy/legacy.hpp:1775:29: error: ‘cv::EM’ has not been declared
enum { START_E_STEP=cv::EM::START_E_STEP,
^
/usr/include/opencv2/legacy/legacy.hpp:1776:29: error: ‘cv::EM’ has not been declared
START_M_STEP=cv::EM::START_M_STEP,
^
/usr/include/opencv2/legacy/legacy.hpp:1777:32: error: ‘cv::EM’ has not been declared
START_AUTO_STEP=cv::EM::START_AUTO_STEP };
^
/usr/include/opencv2/legacy/legacy.hpp:1825:5: error: ‘EM’ in namespace ‘cv’ does not name a type
cv::EM emObj;
^
/usr/include/opencv2/legacy/legacy.hpp: In member function ‘double CvEM::getLikelihood() const’:
/usr/include/opencv2/legacy/legacy.hpp:1807:58: error: ‘emObj’ was not declared in this scope
CV_WRAP inline double getLikelihood() const { return emObj.isTrained() ? logLikelihood : DBL_MAX; }
^
/usr/include/opencv2/legacy/legacy.hpp: At global scope:
/usr/include/opencv2/legacy/legacy.hpp:1880:28: error: ‘vector’ has not been declared
CV_OUT vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:1880:34: error: expected ‘,’ or ‘...’ before ‘<’ token
CV_OUT vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:1882:27: error: ‘vector’ does not name a type
void operator()(const vector& pyr,
^
/usr/include/opencv2/legacy/legacy.hpp:1882:33: error: expected ‘,’ or ‘...’ before ‘<’ token
void operator()(const vector& pyr,
^
/usr/include/opencv2/legacy/legacy.hpp:1885:51: error: ‘vector’ has not been declared
void getMostStable2D(const Mat& image, CV_OUT vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:1885:57: error: expected ‘,’ or ‘...’ before ‘<’ token
void getMostStable2D(const Mat& image, CV_OUT vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:1909:26: error: ‘vector’ does not name a type
FernClassifier(const vector<vector >& points,
^
/usr/include/opencv2/legacy/legacy.hpp:1909:32: error: expected ‘,’ or ‘...’ before ‘<’ token
FernClassifier(const vector<vector >& points,
^
/usr/include/opencv2/legacy/legacy.hpp:1923:44: error: ‘vector’ does not name a type
const vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:1923:50: error: expected ‘,’ or ‘...’ before ‘<’ token
const vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:1931:30: error: ‘vector’ does not name a type
virtual void train(const vector<vector >& points,
^
/usr/include/opencv2/legacy/legacy.hpp:1931:36: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual void train(const vector<vector >& points,
^
/usr/include/opencv2/legacy/legacy.hpp:1941:57: error: ‘vector’ has not been declared
virtual int operator()(const Mat& img, Point2f kpt, vector& signature) const;
^
/usr/include/opencv2/legacy/legacy.hpp:1941:63: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual int operator()(const Mat& img, Point2f kpt, vector& signature) const;
^
/usr/include/opencv2/legacy/legacy.hpp:1942:46: error: ‘vector’ has not been declared
virtual int operator()(const Mat& patch, vector& signature) const;
^
/usr/include/opencv2/legacy/legacy.hpp:1942:52: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual int operator()(const Mat& patch, vector& signature) const;
^
/usr/include/opencv2/legacy/legacy.hpp:1993:5: error: ‘vector’ does not name a type
vector features;
^
/usr/include/opencv2/legacy/legacy.hpp:1994:5: error: ‘vector’ does not name a type
vector classCounters;
^
/usr/include/opencv2/legacy/legacy.hpp:1995:5: error: ‘vector’ does not name a type
vector posteriors;
^
/usr/include/opencv2/legacy/legacy.hpp:2035:16: error: ‘vector’ has not been declared
void train(vector const& base_set, RNG &rng,
^
/usr/include/opencv2/legacy/legacy.hpp:2035:22: error: expected ‘,’ or ‘...’ before ‘<’ token
void train(vector const& base_set, RNG &rng,
^
/usr/include/opencv2/legacy/legacy.hpp:2037:16: error: ‘vector’ has not been declared
void train(vector const& base_set, RNG &rng,
^
/usr/include/opencv2/legacy/legacy.hpp:2037:22: error: expected ‘,’ or ‘...’ before ‘<’ token
void train(vector const& base_set, RNG &rng,
^
/usr/include/opencv2/legacy/legacy.hpp:2037:10: error: ‘void cv::RandomizedTree::train(int)’ cannot be overloaded
void train(vector const& base_set, RNG &rng,
^
/usr/include/opencv2/legacy/legacy.hpp:2035:10: error: with ‘void cv::RandomizedTree::train(int)’
void train(vector const& base_set, RNG &rng,
^
/usr/include/opencv2/legacy/legacy.hpp:2072:5: error: ‘vector’ does not name a type
vector nodes_;
^
/usr/include/opencv2/legacy/legacy.hpp:2075:5: error: ‘vector’ does not name a type
vector leaf_counts_;
^
/usr/include/opencv2/legacy/legacy.hpp:2145:16: error: ‘vector’ has not been declared
void train(vector const& base_set,
^
/usr/include/opencv2/legacy/legacy.hpp:2145:22: error: expected ‘,’ or ‘...’ before ‘<’ token
void train(vector const& base_set,
^
/usr/include/opencv2/legacy/legacy.hpp:2152:16: error: ‘vector’ has not been declared
void train(vector const& base_set,
^
/usr/include/opencv2/legacy/legacy.hpp:2152:22: error: expected ‘,’ or ‘...’ before ‘<’ token
void train(vector const& base_set,
^
/usr/include/opencv2/legacy/legacy.hpp:2152:10: error: ‘void cv::RTreeClassifier::train(int)’ cannot be overloaded
void train(vector const& base_set,
^
/usr/include/opencv2/legacy/legacy.hpp:2145:10: error: with ‘void cv::RTreeClassifier::train(int)’
void train(vector const& base_set,
^
/usr/include/opencv2/legacy/legacy.hpp:2189:5: error: ‘vector’ does not name a type
vector trees_;
^
/usr/include/opencv2/legacy/legacy.hpp:2359:5: error: ‘string’ does not name a type
string m_feature_name; // the name of the feature associated with the descriptor
^
/usr/include/opencv2/legacy/legacy.hpp:2385:67: error: ‘string’ does not name a type
OneWayDescriptorBase(CvSize patch_size, int pose_count, const string &pca_filename, const string &train_path = string(), const string &images_list = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2385:95: error: ‘string’ does not name a type
OneWayDescriptorBase(CvSize patch_size, int pose_count, const string &pca_filename, const string &train_path = string(), const string &images_list = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2385:132: error: ‘string’ does not name a type
OneWayDescriptorBase(CvSize patch_size, int pose_count, const string &pca_filename, const string &train_path = string(), const string &images_list = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2415:58: error: ‘vector’ does not name a type
void CreateDescriptorsFromImage(IplImage* src, const vector& features);
^
/usr/include/opencv2/legacy/legacy.hpp:2415:64: error: expected ‘,’ or ‘...’ before ‘<’ token
void CreateDescriptorsFromImage(IplImage* src, const vector& features);
^
/usr/include/opencv2/legacy/legacy.hpp:2439:49: error: ‘vector’ has not been declared
void FindDescriptor(IplImage* patch, int n, vector& desc_idxs, vector& pose_idxs,
^
/usr/include/opencv2/legacy/legacy.hpp:2439:55: error: expected ‘,’ or ‘...’ before ‘<’ token
void FindDescriptor(IplImage* patch, int n, vector& desc_idxs, vector& pose_idxs,
^
/usr/include/opencv2/legacy/legacy.hpp:2468:61: error: ‘vector’ does not name a type
void InitializeDescriptors(IplImage* train_image, const vector& features,
^
/usr/include/opencv2/legacy/legacy.hpp:2468:67: error: expected ‘,’ or ‘...’ before ‘<’ token
void InitializeDescriptors(IplImage* train_image, const vector& features,
^
/usr/include/opencv2/legacy/legacy.hpp:2519:12: error: ‘string’ does not name a type
static string GetPCAFilename () { return "pca.yml"; }
^
/usr/include/opencv2/legacy/legacy.hpp:2385:123: error: ‘string’ was not declared in this scope
OneWayDescriptorBase(CvSize patch_size, int pose_count, const string &pca_filename, const string &train_path = string(), const string &images_list = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2385:123: note: suggested alternative:
In file included from /usr/include/c++/4.8/iosfwd:39:0,
from /usr/include/c++/4.8/ios:38,
from /usr/include/c++/4.8/istream:38,
from /usr/include/c++/4.8/sstream:38,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/mrpt_macros.h:14,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/core_defs.h:15,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/utils_defs.h:13,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/CImage.h:12,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:12:
/usr/include/c++/4.8/bits/stringfwd.h:62:33: note: ‘std::string’
typedef basic_string string;
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2385:161: error: ‘string’ was not declared in this scope
OneWayDescriptorBase(CvSize patch_size, int pose_count, const string &pca_filename, const string &train_path = string(), const string &images_list = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2385:161: note: suggested alternative:
In file included from /usr/include/c++/4.8/iosfwd:39:0,
from /usr/include/c++/4.8/ios:38,
from /usr/include/c++/4.8/istream:38,
from /usr/include/c++/4.8/sstream:38,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/mrpt_macros.h:14,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/core_defs.h:15,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/utils_defs.h:13,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/CImage.h:12,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:12:
/usr/include/c++/4.8/bits/stringfwd.h:62:33: note: ‘std::string’
typedef basic_string string;
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2571:69: error: ‘string’ does not name a type
OneWayDescriptorObject(CvSize patch_size, int pose_count, const string &pca_filename,
^
/usr/include/opencv2/legacy/legacy.hpp:2572:34: error: ‘string’ does not name a type
const string &train_path = string (), const string &images_list = string (),
^
/usr/include/opencv2/legacy/legacy.hpp:2572:72: error: ‘string’ does not name a type
const string &train_path = string (), const string &images_list = string (),
^
/usr/include/opencv2/legacy/legacy.hpp:2584:35: error: ‘vector’ does not name a type
void SetLabeledFeatures(const vector& features) {m_train_features = features;};
^
/usr/include/opencv2/legacy/legacy.hpp:2584:41: error: expected ‘,’ or ‘...’ before ‘<’ token
void SetLabeledFeatures(const vector& features) {m_train_features = features;};
^
/usr/include/opencv2/legacy/legacy.hpp:2585:5: error: ‘vector’ does not name a type
vector& GetLabeledFeatures() {return m_train_features;};
^
/usr/include/opencv2/legacy/legacy.hpp:2586:11: error: ‘vector’ does not name a type
const vector& GetLabeledFeatures() const {return m_train_features;};
^
/usr/include/opencv2/legacy/legacy.hpp:2587:5: error: ‘vector’ does not name a type
vector GetLabeledFeatures() const;
^
/usr/include/opencv2/legacy/legacy.hpp:2600:67: error: ‘vector’ does not name a type
void InitializeObjectDescriptors(IplImage* train_image, const vector& features,
^
/usr/include/opencv2/legacy/legacy.hpp:2600:73: error: expected ‘,’ or ‘...’ before ‘<’ token
void InitializeObjectDescriptors(IplImage* train_image, const vector& features,
^
/usr/include/opencv2/legacy/legacy.hpp:2609:5: error: ‘vector’ does not name a type
vector m_train_features; // train features
^
/usr/include/opencv2/legacy/legacy.hpp:2572:63: error: ‘string’ was not declared in this scope
const string &train_path = string (), const string &images_list = string (),
^
/usr/include/opencv2/legacy/legacy.hpp:2572:63: note: suggested alternative:
In file included from /usr/include/c++/4.8/iosfwd:39:0,
from /usr/include/c++/4.8/ios:38,
from /usr/include/c++/4.8/istream:38,
from /usr/include/c++/4.8/sstream:38,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/mrpt_macros.h:14,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/core_defs.h:15,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/utils_defs.h:13,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/CImage.h:12,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:12:
/usr/include/c++/4.8/bits/stringfwd.h:62:33: note: ‘std::string’
typedef basic_string string;
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2572:102: error: ‘string’ was not declared in this scope
const string &train_path = string (), const string &images_list = string (),
^
/usr/include/opencv2/legacy/legacy.hpp:2572:102: note: suggested alternative:
In file included from /usr/include/c++/4.8/iosfwd:39:0,
from /usr/include/c++/4.8/ios:38,
from /usr/include/c++/4.8/istream:38,
from /usr/include/c++/4.8/sstream:38,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/mrpt_macros.h:14,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/core_defs.h:15,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/utils_defs.h:13,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/CImage.h:12,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:12:
/usr/include/c++/4.8/bits/stringfwd.h:62:33: note: ‘std::string’
typedef basic_string string;
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp: In member function ‘void cv::OneWayDescriptorObject::SetLabeledFeatures(int)’:
/usr/include/opencv2/legacy/legacy.hpp:2584:64: error: ‘m_train_features’ was not declared in this scope
void SetLabeledFeatures(const vector& features) {m_train_features = features;};
^
/usr/include/opencv2/legacy/legacy.hpp:2584:83: error: ‘features’ was not declared in this scope
void SetLabeledFeatures(const vector& features) {m_train_features = features;};
^
/usr/include/opencv2/legacy/legacy.hpp: At global scope:
/usr/include/opencv2/legacy/legacy.hpp:2622:1: error: expected class-name before ‘{’ token
{
^
/usr/include/opencv2/legacy/legacy.hpp:2636:16: error: ‘string’ has not been declared
string pcaFilename = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2637:16: error: ‘string’ has not been declared
string trainPath = string(), string trainImagesList = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2637:45: error: ‘string’ has not been declared
string trainPath = string(), string trainImagesList = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2643:9: error: ‘string’ does not name a type
string pcaFilename;
^
/usr/include/opencv2/legacy/legacy.hpp:2644:9: error: ‘string’ does not name a type
string trainPath;
^
/usr/include/opencv2/legacy/legacy.hpp:2645:9: error: ‘string’ does not name a type
string trainImagesList;
^
/usr/include/opencv2/legacy/legacy.hpp:2667:17: error: ‘GenericDescriptorMatcher’ was not declared in this scope
virtual Ptr clone( bool emptyTrainData=false ) const;
^
/usr/include/opencv2/legacy/legacy.hpp:2667:41: error: template argument 1 is invalid
virtual Ptr clone( bool emptyTrainData=false ) const;
^
/usr/include/opencv2/legacy/legacy.hpp:2676:55: error: ‘vector’ has not been declared
virtual void knnMatchImpl( const Mat& queryImage, vector& queryKeypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2676:61: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual void knnMatchImpl( const Mat& queryImage, vector& queryKeypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2679:58: error: ‘vector’ has not been declared
virtual void radiusMatchImpl( const Mat& queryImage, vector& queryKeypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2679:64: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual void radiusMatchImpl( const Mat& queryImage, vector& queryKeypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2636:44: error: ‘string’ was not declared in this scope
string pcaFilename = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2636:44: note: suggested alternative:
In file included from /usr/include/c++/4.8/iosfwd:39:0,
from /usr/include/c++/4.8/ios:38,
from /usr/include/c++/4.8/istream:38,
from /usr/include/c++/4.8/sstream:38,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/mrpt_macros.h:14,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/core_defs.h:15,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/utils_defs.h:13,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/CImage.h:12,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:12:
/usr/include/c++/4.8/bits/stringfwd.h:62:33: note: ‘std::string’
typedef basic_string string;
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2637:42: error: ‘string’ was not declared in this scope
string trainPath = string(), string trainImagesList = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2637:42: note: suggested alternative:
In file included from /usr/include/c++/4.8/iosfwd:39:0,
from /usr/include/c++/4.8/ios:38,
from /usr/include/c++/4.8/istream:38,
from /usr/include/c++/4.8/sstream:38,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/mrpt_macros.h:14,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/core_defs.h:15,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/utils_defs.h:13,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/CImage.h:12,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:12:
/usr/include/c++/4.8/bits/stringfwd.h:62:33: note: ‘std::string’
typedef basic_string string;
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2637:77: error: ‘string’ was not declared in this scope
string trainPath = string(), string trainImagesList = string(),
^
/usr/include/opencv2/legacy/legacy.hpp:2637:77: note: suggested alternative:
In file included from /usr/include/c++/4.8/iosfwd:39:0,
from /usr/include/c++/4.8/ios:38,
from /usr/include/c++/4.8/istream:38,
from /usr/include/c++/4.8/sstream:38,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/mrpt_macros.h:14,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/core_defs.h:15,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/utils_defs.h:13,
from /home/romulo/mrpt-git/libs/base/include/mrpt/utils/CImage.h:12,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:12:
/usr/include/c++/4.8/bits/stringfwd.h:62:33: note: ‘std::string’
typedef basic_string string;
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2650:58: error: call to ‘cv::OneWayDescriptorMatcher::Params::Params(int, cv::Size, int, int, int, float, float, float)’ uses the default argument for parameter 3, which is not yet defined
OneWayDescriptorMatcher( const Params& params=Params() );
^
/usr/include/opencv2/legacy/legacy.hpp:2650:58: error: call to ‘cv::OneWayDescriptorMatcher::Params::Params(int, cv::Size, int, int, int, float, float, float)’ uses the default argument for parameter 4, which is not yet defined
/usr/include/opencv2/legacy/legacy.hpp:2650:58: error: call to ‘cv::OneWayDescriptorMatcher::Params::Params(int, cv::Size, int, int, int, float, float, float)’ uses the default argument for parameter 5, which is not yet defined
/usr/include/opencv2/legacy/legacy.hpp:2695:1: error: expected class-name before ‘{’ token
{
^
/usr/include/opencv2/legacy/legacy.hpp:2709:23: error: ‘string’ does not name a type
Params( const string& filename );
^
/usr/include/opencv2/legacy/legacy.hpp:2720:9: error: ‘string’ does not name a type
string filename;
^
/usr/include/opencv2/legacy/legacy.hpp:2736:17: error: ‘GenericDescriptorMatcher’ was not declared in this scope
virtual Ptr clone( bool emptyTrainData=false ) const;
^
/usr/include/opencv2/legacy/legacy.hpp:2736:41: error: template argument 1 is invalid
virtual Ptr clone( bool emptyTrainData=false ) const;
^
/usr/include/opencv2/legacy/legacy.hpp:2739:55: error: ‘vector’ has not been declared
virtual void knnMatchImpl( const Mat& queryImage, vector& queryKeypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2739:61: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual void knnMatchImpl( const Mat& queryImage, vector& queryKeypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2742:58: error: ‘vector’ has not been declared
virtual void radiusMatchImpl( const Mat& queryImage, vector& queryKeypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2742:64: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual void radiusMatchImpl( const Mat& queryImage, vector& queryKeypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2748:70: error: ‘vector’ has not been declared
float& bestProb, int& bestMatchIdx, vector& signature );
^
/usr/include/opencv2/legacy/legacy.hpp:2748:76: error: expected ‘,’ or ‘...’ before ‘<’ token
float& bestProb, int& bestMatchIdx, vector& signature );
^
/usr/include/opencv2/legacy/legacy.hpp:2762:40: error: ‘string’ does not name a type
CalonderDescriptorExtractor( const string& classifierFile );
^
/usr/include/opencv2/legacy/legacy.hpp:2773:49: error: ‘vector’ has not been declared
virtual void computeImpl( const Mat& image, vector& keypoints, Mat& descriptors ) const;
^
/usr/include/opencv2/legacy/legacy.hpp:2773:55: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual void computeImpl( const Mat& image, vector& keypoints, Mat& descriptors ) const;
^
/usr/include/opencv2/legacy/legacy.hpp:2780:1: error: prototype for ‘cv::CalonderDescriptorExtractor::CalonderDescriptorExtractor(const string&)’ does not match any in class ‘cv::CalonderDescriptorExtractor’
CalonderDescriptorExtractor::CalonderDescriptorExtractor(const std::string& classifier_file)
^
/usr/include/opencv2/legacy/legacy.hpp:2762:5: error: candidate is: cv::CalonderDescriptorExtractor::CalonderDescriptorExtractor(const int&)
CalonderDescriptorExtractor( const string& classifierFile );
^
/usr/include/opencv2/legacy/legacy.hpp:2787:50: error: ‘vector’ has not been declared
vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2787:56: error: expected ‘,’ or ‘...’ before ‘<’ token
vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp: In member function ‘virtual void cv::CalonderDescriptorExtractor::computeImpl(const cv::Mat&, int) const’:
/usr/include/opencv2/legacy/legacy.hpp:2791:39: error: ‘keypoints’ was not declared in this scope
KeyPointsFilter::runByImageBorder(keypoints, image.size(), BORDER_SIZE);
^
/usr/include/opencv2/legacy/legacy.hpp:2794:5: error: ‘descriptors’ was not declared in this scope
descriptors.create((int)keypoints.size(), classifier
.classes(), cv::DataType::type);
^
/usr/include/opencv2/legacy/legacy.hpp:2802:58: error: expected primary-expression before ‘>’ token
classifier_.getSignature( &ipl, descriptors.ptr((int)i));
^
/usr/include/opencv2/legacy/legacy.hpp: In member function ‘virtual bool cv::CalonderDescriptorExtractor::empty() const’:
/usr/include/opencv2/legacy/legacy.hpp:2817:24: error: ‘const class cv::RTreeClassifier’ has no member named ‘trees_’
return classifier_.trees_.empty();
^
/usr/include/opencv2/legacy/legacy.hpp: At global scope:
/usr/include/opencv2/legacy/legacy.hpp:2841:32: error: ‘vector’ does not name a type
PlanarObjectDetector(const vector& pyr, int npoints=300,
^
/usr/include/opencv2/legacy/legacy.hpp:2841:38: error: expected ‘,’ or ‘...’ before ‘<’ token
PlanarObjectDetector(const vector& pyr, int npoints=300,
^
/usr/include/opencv2/legacy/legacy.hpp:2849:30: error: ‘vector’ does not name a type
virtual void train(const vector& pyr, int npoints=300,
^
/usr/include/opencv2/legacy/legacy.hpp:2849:36: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual void train(const vector& pyr, int npoints=300,
^
/usr/include/opencv2/legacy/legacy.hpp:2856:30: error: ‘vector’ does not name a type
virtual void train(const vector& pyr, const vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2856:36: error: expected ‘,’ or ‘...’ before ‘<’ token
virtual void train(const vector& pyr, const vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2856:18: error: ‘virtual void cv::PlanarObjectDetector::train(int)’ cannot be overloaded
virtual void train(const vector& pyr, const vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2849:18: error: with ‘virtual void cv::PlanarObjectDetector::train(int)’
virtual void train(const vector& pyr, int npoints=300,
^
/usr/include/opencv2/legacy/legacy.hpp:2864:5: error: ‘vector’ does not name a type
vector getModelPoints() const;
^
/usr/include/opencv2/legacy/legacy.hpp:2871:61: error: ‘vector’ has not been declared
bool operator()(const Mat& image, CV_OUT Mat& H, CV_OUT vector& corners) const;
^
/usr/include/opencv2/legacy/legacy.hpp:2871:67: error: expected ‘,’ or ‘...’ before ‘<’ token
bool operator()(const Mat& image, CV_OUT Mat& H, CV_OUT vector& corners) const;
^
/usr/include/opencv2/legacy/legacy.hpp:2872:27: error: ‘vector’ does not name a type
bool operator()(const vector& pyr, const vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2872:33: error: expected ‘,’ or ‘...’ before ‘<’ token
bool operator()(const vector& pyr, const vector& keypoints,
^
/usr/include/opencv2/legacy/legacy.hpp:2879:5: error: ‘vector’ does not name a type
vector modelPoints;
^
/usr/include/opencv2/legacy/legacy.hpp:2927:38: error: variable or field ‘cvInitSubdivDelaunay2D’ declared void
CVAPI(void) cvInitSubdivDelaunay2D( CvSubdiv2D* subdiv, CvRect rect );
^
/usr/include/opencv2/legacy/legacy.hpp:2927:38: error: ‘CvSubdiv2D’ was not declared in this scope
/usr/include/opencv2/legacy/legacy.hpp:2927:50: error: ‘subdiv’ was not declared in this scope
CVAPI(void) cvInitSubdivDelaunay2D( CvSubdiv2D* subdiv, CvRect rect );
^
/usr/include/opencv2/legacy/legacy.hpp:2927:65: error: expected primary-expression before ‘rect’
CVAPI(void) cvInitSubdivDelaunay2D( CvSubdiv2D* subdiv, CvRect rect );
^
In file included from /opt/ros/indigo/include/opencv2/core/core_c.h:48:0,
from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:29,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2930:1: error: ‘CvSubdiv2D’ does not name a type
CVAPI(CvSubdiv2D
) cvCreateSubdiv2D( int subdiv_type, int header_size,
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2937:12: error: ‘CvSubdiv2D’ does not name a type
CV_INLINE CvSubdiv2D
cvCreateSubdivDelaunay2D( CvRect rect, CvMemStorage* storage )
^
In file included from /opt/ros/indigo/include/opencv2/core/core_c.h:48:0,
from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:29,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2948:1: error: ‘CvSubdiv2DPoint’ does not name a type
CVAPI(CvSubdiv2DPoint
) cvSubdivDelaunay2DInsert( CvSubdiv2D subdiv, CvPoint2D32f pt);
^
/usr/include/opencv2/legacy/legacy.hpp:2953:1: error: ‘CvSubdiv2DPointLocation’ does not name a type
CVAPI(CvSubdiv2DPointLocation) cvSubdiv2DLocate(
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2959:37: error: variable or field ‘cvCalcSubdivVoronoi2D’ declared void
CVAPI(void) cvCalcSubdivVoronoi2D( CvSubdiv2D* subdiv );
^
/usr/include/opencv2/legacy/legacy.hpp:2959:37: error: ‘CvSubdiv2D’ was not declared in this scope
/usr/include/opencv2/legacy/legacy.hpp:2959:49: error: ‘subdiv’ was not declared in this scope
CVAPI(void) cvCalcSubdivVoronoi2D( CvSubdiv2D* subdiv );
^
/usr/include/opencv2/legacy/legacy.hpp:2963:38: error: variable or field ‘cvClearSubdivVoronoi2D’ declared void
CVAPI(void) cvClearSubdivVoronoi2D( CvSubdiv2D* subdiv );
^
/usr/include/opencv2/legacy/legacy.hpp:2963:38: error: ‘CvSubdiv2D’ was not declared in this scope
/usr/include/opencv2/legacy/legacy.hpp:2963:50: error: ‘subdiv’ was not declared in this scope
CVAPI(void) cvClearSubdivVoronoi2D( CvSubdiv2D* subdiv );
^
In file included from /opt/ros/indigo/include/opencv2/core/core_c.h:48:0,
from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:29,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2967:1: error: ‘CvSubdiv2DPoint’ does not name a type
CVAPI(CvSubdiv2DPoint) cvFindNearestPoint2D( CvSubdiv2D_ subdiv, CvPoint2D32f pt );
^
In file included from /home/romulo/mrpt-git/libs/base/include/mrpt/otherlibs/do_opencv_includes.h:42:0,
from /home/romulo/mrpt-git/libs/base/src/utils/CImage_JPEG_streams.cpp:16:
/usr/include/opencv2/legacy/legacy.hpp:2972:12: error: ‘CvSubdiv2DEdge’ does not name a type
CV_INLINE CvSubdiv2DEdge cvSubdiv2DNextEdge( CvSubdiv2DEdge edge )
^
/usr/include/opencv2/legacy/legacy.hpp:2978:12: error: ‘CvSubdiv2DEdge’ does not name a type
CV_INLINE CvSubdiv2DEdge cvSubdiv2DRotateEdge( CvSubdiv2DEdge edge, int rotate )
^
/usr/include/opencv2/legacy/legacy.hpp:2983:12: error: ‘CvSubdiv2DEdge’ does not name a type
CV_INLINE CvSubdiv2DEdge cvSubdiv2DSymEdge( CvSubdiv2DEdge edge )
^
/usr/include/opencv2/legacy/legacy.hpp:2988:12: error: ‘CvSubdiv2DEdge’ does not name a type
CV_INLINE CvSubdiv2DEdge cvSubdiv2DGetEdge( CvSubdiv2DEdge edge, CvNextEdgeType type )
^
/usr/include/opencv2/legacy/legacy.hpp:2996:12: error: ‘CvSubdiv2DPoint’ does not name a type
CV_INLINE CvSubdiv2DPoint* cvSubdiv2DEdgeOrg( CvSubdiv2DEdge edge )
^
/usr/include/opencv2/legacy/legacy.hpp:3003:12: error: ‘CvSubdiv2DPoint’ does not name a type
CV_INLINE CvSubdiv2DPoint* cvSubdiv2DEdgeDst( CvSubdiv2DEdge edge )
^
/usr/include/opencv2/legacy/legacy.hpp:3014:29: error: variable or field ‘icvDrawMosaic’ declared void
CVAPI(void) icvDrawMosaic( CvSubdiv2D* subdiv, IplImage* src, IplImage* dst );
^
/usr/include/opencv2/legacy/legacy.hpp:3014:29: error: ‘CvSubdiv2D’ was not declared in this scope
/usr/include/opencv2/legacy/legacy.hpp:3014:41: error: ‘subdiv’ was not declared in this scope
CVAPI(void) icvDrawMosaic( CvSubdiv2D* subdiv, IplImage* src, IplImage* dst );
^
/usr/include/opencv2/legacy/legacy.hpp:3014:57: error: expected primary-expression before ‘’ token
CVAPI(void) icvDrawMosaic( CvSubdiv2D
subdiv, IplImage* src, IplImage* dst );
^
/usr/include/opencv2/legacy/legacy.hpp:3014:59: error: ‘src’ was not declared in this scope
CVAPI(void) icvDrawMosaic( CvSubdiv2D* subdiv, IplImage* src, IplImage* dst );
^
/usr/include/opencv2/legacy/legacy.hpp:3014:72: error: expected primary-expression before ‘’ token
CVAPI(void) icvDrawMosaic( CvSubdiv2D
subdiv, IplImage* src, IplImage* dst );
^
/usr/include/opencv2/legacy/legacy.hpp:3014:74: error: ‘dst’ was not declared in this scope
CVAPI(void) icvDrawMosaic( CvSubdiv2D* subdiv, IplImage* src, IplImage* dst );
^
/usr/include/opencv2/legacy/legacy.hpp:3018:32: error: ‘CvSubdiv2D’ was not declared in this scope
CVAPI(int) icvSubdiv2DCheck( CvSubdiv2D* subdiv );
^
/usr/include/opencv2/legacy/legacy.hpp:3018:44: error: ‘subdiv’ was not declared in this scope
CVAPI(int) icvSubdiv2DCheck( CvSubdiv2D* subdiv );
^
make[2]: *** [libs/base/CMakeFiles/mrpt-base.dir/src/utils/CImage_JPEG_streams.cpp.o] Error 1
make[1]: *** [libs/base/CMakeFiles/mrpt-base.dir/all] Error 2
make: *** [all] Error 2

How I can fix it?

How can I work on MRPT samples as Eclipse projects?

Hello everyone,
I have been trying to integrate MRPT projects on Eclipse Indigo software. I first tried the three different ways about Eclipse given in "Compiling MRPT" section, however I couldn't manage to obtain the result.

For NetBeans 8.0, I have used this method:

  • Copy a sample folder (for example graph_slam_demo) to somewhere else (for example gs_demo).
  • CMake it using cmake-gui,
  • Menu File -> New Project…: C/C++ -> C/C++ Project with Existing Sources.
  • Click next and select the MRPT root dir which contains the CMakeList.txt file.
    It successfully works this way, by means of importing, compiling and "running". But when it comes to Eclipse again, with this method:
  • Copy a sample folder (for example graph_slam_demo) to somewhere else.
  • CMake it using cmake-gui,
  • File -> Import... : Existing Projects into Workspace -> Browse "The folder above"

Most of the samples can be imported as a project (for example, the imported project appears as "EXAMPLE_graph_slam_demo@gs_demo"), however almost none of them have binaries, therefore I cannot run those examples. Even if some have the binaries, I can compile and run those but i get this error log when the program tries to use graphics:

Error: Unable to initialize gtk, is DISPLAY set properly?
** (MRPT:8099): WARNING **: Command line `dbus-launch --autolaunch=cf0fccd607b7ba15bad9beb400000011 --binary-syntax --close-stderr' exited with non-zero exit status 1: Autolaunch error: X11 initialization failed.\n
[WxSubsystem::createOneInstanceMainThread] Timeout waiting wxApplication to start up!
Error: Unable to initialize gtk, is DISPLAY set properly?
[WxSubsystem::createOneInstanceMainThread] Timeout waiting wxApplication to start up!
Error: Unable to initialize gtk, is DISPLAY set properly?
[WxSubsystem::createOneInstanceMainThread] Timeout waiting wxApplication to start up!
Close any window to end...

What I understand is, if manual "make" without an IDE or running in NetBeans gives success, this problem must be about my usage of Eclipse.
I look forward to your help, thanks a lot :)

Port to C++14

To be done (in 2017? -> yes) when it's safe to assume everyone has a decent C++14 compiler.

This implies:

  • Deprecate support for Ubuntu precise (and also trusty but only in PPA, for the next item:)
  • Use modern CMake 3.1+ C++ compiler features: target_compile_features, WriteCompilerDetectionHeader, set (CMAKE_CXX_STANDARD 11), etc.
  • Smart pointers: forget about stlplus and move to C++11 smart pointers.
  • Threads: move to std::thread, unless there are strong reasons not to do so.
  • Switch tfest/indiv-compat-decls.h to <functional>
  • CMake: use EXPORT, etc.
  • Direct use of Eigen? Moved to its own issue: #496
  • Semaphore -> http://stackoverflow.com/a/27852868
  • MRPT_OVERRIDE -> override
  • CPipe : avoid deprecated auto_ptr<>
  • Search and rewrite all areas having an #if MRPT_HAS_CXX11
  • Drop mrpt::synch::CAtomicCounter in favor of C++11 std::atomic.
  • Prefer nullptr
  • MRPT_NO_THROWS ==> C++11.
  • Make all destructors noexcept
  • Consider replacing uint32_t enums with correct C++11 typed enums. E.g. in GNSS_BINARY_MSG_DEFINITION_START
  • Review usages of mrpt::utils::delete_safe and consider changing them to use C++11 smart pointers.
  • Foo::Create with make_shared ()
  • std::function typedefs or similar for ZMQ wrappers: See #231
  • Support move semantics (read below)
  • typedefs ==> using
  • Add constexpr to geometry constructors, etc.
  • alignas instead of Eigen align macros
  • Simplify ctors via member initialization in headers, e.g. int a { 0 }; or int a = 0;
  • Replace copy_ptr<>, etc. with simple using ... partial template specializations.
  • Use using FP=... to define functors.
  • Use template<> using ... instead of current aligned STL containers. ==> Nope: it would break existing code, it's not worth (Nov 3, 2017)
  • Replace std::vector of fixed length with std::array. E.g. ReactiveNav classes, etc.
  • Make sure all move ctors and move = operators are declared noexcept. Otherwise, they will not be eligible for "real move".
  • refactor type traits
  • Use weak_ptr for m_frame_tf API in ReactiveNav

Minimum compilers (see this table)

  • MSVC 15 aka 14.1 (2017)
  • GCC 4.8 (?)
  • CLANG 3.3 (?)

Minimum CMake version: 3.1

Debian pkg build error: missing COPYING

pbuilder output error:

-- Found Doxygen: /usr/bin/doxygen (found version "1.8.6")
CMake Error at /usr/share/cmake-2.8/Modules/CPack.cmake:395 (message):
CPack license resource file: "/tmp/buildd/mrpt-1.1.1/COPYING" could not be
found.

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.