Skip to content
Snippets Groups Projects
Commit f347e1f7 authored by Arnaud Degroote's avatar Arnaud Degroote
Browse files

[wip/mrpt] Upgrade to 1.2.2

From the Changelog

***** Version 1.2.2: Released 12-SEP-2014 *****
    * Changes in apps:
          o SceneViewer3D:
                # New menu "File" -> "Import" -> "3D model" which supports many
                  standard formats (via mrpt::opengl::CAssimpModel)
    * New classes:
          o [mrpt-hwdrivers]
                # mrpt::hwdrivers::CRoboPeakLidar to interface Robo Peak LIDAR
                  scanners.
          o [mrpt-opengl]
                # mrpt::opengl::CAssimpModel for rendering complex 3D models
                  (many supported formats) in OpenGL scenes.
    * Changes in classes:
          o Consistency in all "laser scan" classes: angular increments between
            rays are now FOV/(N-1) instead of FOV/N.
          o [mrpt-base]
                # New method mrpt::utils::CImage::loadTGA()
                # IMPORTANT: Changed behavior of CSerializable/CObject macros
                  (see bugfix below), introducing the new macros
                  DEFINE_SERIALIZABLE_POST_*. May require changes in user code
                  if serializable classes are defined:
                      # Previous version:
                        DEFINE_SERIALIZABLE_PRE_*(...)
                        class XXX {
                        DEFINE_SERIALIZABLE(XXX)
                        };
                      # Must be changed in this version to:
                        DEFINE_SERIALIZABLE_PRE_*(...)
                        class XXX {
                        DEFINE_SERIALIZABLE(XXX)
                        };
                        DEFINE_SERIALIZABLE_POST_*(...)
          o [mrpt-hwdrivers]
                # Bumblebee2 Linux support in mrpt::hwdrivers::
                  CImageGrabber_FlyCapture2 via Triclops (by Jesus Briales)
          o [mrpt-maps]
                # New method mrpt::slam::COccupancyGridMap2D::getRawMap()
                # New method mrpt::slam::CColouredPointsMap::
                  getPCLPointCloudXYZRGB()
          o [mrpt-opengl]
                # mrpt::opengl::CMyGLCanvasBase (affects all 3D rendering
                  classes): better handling of internal timers for smoother
                  updates while rendering in multithreading apps.
          o [mrpt-srba]
                # New method to recover the global coordinates graph-slam
                  problem for a RBA map: mrpt::srba::RbaEngine::
                  get_global_graphslam_problem() (see example [MRPT]-
                  examples\srba-tutorials\tutorial-srba-how-to-recover-global-
                  map.cpp)
    * BUG FIXES:
          o mrpt::utils::CImage constructor from a matrix crashed.
          o Unit tests: Named semaphores are not tested anymore if it's
            detected that the kernel version doesn't support them (Fix Debian
            758725).
          o mrpt::synch::CSemaphore [Linux]: didn't call sem_unlink().
          o mrpt::gui::CDisplayWindow3D didn't implement get/set FOV.
          o Valgrind: Fixed potential unaligned memory access warning in point
            clouds.
          o Fix build error with AppleClang 5.1 (Closes #71).
          o mrpt::utils::CClientTCPSocket: Use a connection success check that
            works on all platforms
          o Important bug fixed regarding a missing dynamic_cast<> in smart
            pointers casting. See above possible implications in user code.
            properly (Patch by Joe Burmeister).
===============================================================================
***** Version 1.2.1: Released 10-JUL-2014 *****
    * Changes in classes:
          o [mrpt-base]
                # All points and poses now have a method setToNaN(), e.g.
                  mrpt::poses::CPose3D::setToNaN()
          o [mrpt-hwdrivers]
                # mrpt::hwdrivers::COpenNI2Sensor now has better support for
                  opening several RGBD cameras (by Kenzaburo Miyawaki &amp;
                  Eduardo Fernandez)
    * Build system:
          o Fix compilation of SRBA with DEBUG_GARBAGE_FILL_ALL_NUMS=1
          o Fix de-serialization error in mrpt::reactivenav::CLogFileRecord
            (and new unit tests added to avoid regressions).
          o Several Debian bugs closed (see packaging/debian/changelog),
            including build errors in uncommon platforms (MIPS, kFreeBSD, etc.)
===============================================================================
***** Version 1.2.0: Released 25-JUN-2014 *****
    * Most important changes:
          o Public header files (.h) have undergone a serious refactoring to
            minimize unnecesary dependencies and reduce compile time and memory
            as much as possible. As a side effect, user code might need to add
            new #include<> lines. This change justifies the new minor version
            series 1.2.X.
          o MRPT now cleanly builds in clang and OSX.
          o Support for new camera drivers (OpenNI2, DUO3D).
          o Many bug fixes.
    * Detailed list of changes:
          o Changes in apps:
                # rawlog-edit:
                      # New operations: &ndash;export-odometry-txt,
                        &ndash;recalc-odometry
                      # New flag: &ndash;rectify-centers-coincide
          o New examples:
                # kitti_dataset2rawlog
          o New classes:
                # [mrpt-base]
                      # mrpt::math::ContainerType<CONTAINER>::element_t to
                        allow handling either Eigen or STL containers
                        seamlessly.
                      # mrpt::utils::CConfigFilePrefixer
                # [mrpt-hwdrivers]
                      # mrpt::hwdrivers::COpenNI2Sensor: Interface to OpenNI2
                        cameras, capable of reading from an array of OpenNI2
                        RGBD cameras (By Eduardo Fernandez)
                      # mrpt::hwdrivers::CDUO3DCamera: Interface to DUO3D
                        cameras (By Francisco Angel Moreno)
                      # mrpt::hwdrivers::CGPS_NTRIP: A combination of GPS
                        receiver + NTRIP receiver capable of submitting GGA
                        frames to enable RTCM 3.0
                # [mrpt-obs]
                      # mrpt::slam::CObservation6DFeatures
          o Changes in classes:
                # [mrpt-base]
                      # Robust kernel templates moved from mrpt::vision to
                        mrpt::math. See mrpt::math::RobustKernel<>. Added unit
                        tests for robust kernels.
                      # CPose3D has new SE(3) methods: mrpt::poses::CPose3D::
                        jacob_dexpeD_de(), mrpt::poses::CPose3D::
                        jacob_dAexpeD_de()
                      # More efficient mrpt::utils::OctetVectorToObject()
                        (avoid memory copy).
                      # Fixed const-correctness of mrpt::utils::CImage::
                        forceLoad() and mrpt::utils::CImage::unload()
                # [mrpt-hwdrivers]
                      # mrpt::hwdrivers::CCameraSensor: Added a hook for user
                        code to run before saving external image files: mrpt::
                        hwdrivers::CCameraSensor::addPreSaveHook()
                      # mrpt::hwdrivers::CNationalInstrumentsDAQ now supports
                        analog and digital outputs.
                      # New method mrpt::hwdrivers::CNTRIPClient::
                        sendBackToServer()
                # [mrpt-srba]
                      # Now also implements SE(3) relative graph-slam.
                # [mrpt-vision]
                      # mrpt::vision::checkerBoardStereoCalibration: More
                        robust handling of stereo calibration patterns. OpenCV
                        sometimes detects corners in the wrong order between
                        (left/right) images, so we detect the situation and fix
                        it.
                      # mrpt::vision::findMultipleChessboardsCorners():
                            # Now enforces a consistent counterclockwise XYZ
                              coordinate frame at each detected chessboard.
                            # Much more robust in distingishing quads of
                              different sizes.
          o Build system / public API:
                # Fixes to build in OS X - Patch by Randolph Voorhies.
                # Removed most "using namespace" from public headers, as good
                  practice.
                # Refactoring of MRPT headers.
                      # <mrpt/utils/stl_extensions.h> has been split into:
                            # <mrpt/utils/stl_serialization.h>
                            # <mrpt/utils/circular_buffer.h>
                            # <mrpt/utils/list_searchable.h>
                            # <mrpt/utils/bimap.h>
                            # <mrpt/utils/map_as_vector.h>
                            # <mrpt/utils/traits_map.h>
                            # <mrpt/utils/stl_serialization.h>
                            # <mrpt/utils/printf_vector.h>
                            # <mrpt/utils/stl_containers_utils.h>
                            # <mrpt/utils/ci_less.h>
                # Deleted methods and functions:
                      # mrpt::system::breakpoint()
                      # mrpt::vector_float is now mrpt::math::CVectorFloat,
                        mrpt::vector_double is mrpt::math::CVectorDouble, for
                        name consistency. Also, using Eigen::VectorXf is
                        preferred for new code.
                      # mrpt::CImage::rectifyImage() with parameters as
                        separate vectors.
                      # mrpt::slam::CPointsMap::getPoint() with mrpt::poses::
                        CPoint3D arguments.
                      # mrpt::vision::correctDistortion() -> use CImage method
                        instead
                      # All previous deprecated functions.
                # Embedded Eigen updated to version 3.2.1 (commit) (commit)
          o BUG FIXES:
                # RawlogViewer app: Fixed abort while converting SF->obs.only
                  datasets when there is no odometry.
                # mrpt::slam::CSensoryFrame: The cached point map is now
                  invalidated with any change to the list of observations so
                  it's rebuild upon next call.
                # New implementation of mrpt::synch::CSemaphore avoids crashes
                  in OS X - by Randolph Voorhies.
                # mrpt::opengl::CArrow was always drawn of normalized length.
                # FlyCapture2 monocular &amp; stereo cameras could return an
                  incorrect timestamp (only in Linux?).
                # mrpt::system::createDirectory() returned false (error) when
                  the directory already existed.
                # mrpt::vision::CStereoRectifyMap::rectify() didn't update the
                  left &amp; right camera poses inside mrpt::slam::
                  CObservationStereoImages objects while rectifying.
                # RawLogViewer: Operation "convert to SF format" didn't take
                  into account odometry observations.
                # Fix build errors with GCC 4.9
                # Fix crash of mrpt::hwdrivers::CIMUXSens_MT4's destructor when
                  it fails to scan and open a device.
                # Fix potential crash in mrpt::slam::
                  data_association_full_covariance with JCBB when no
                  individually compatible matching exists (commit)
parent 51b2f624
No related branches found
No related tags found
No related merge requests found
......@@ -3,7 +3,7 @@
#
DISTNAME= mrpt-${VERSION}
VERSION= 1.1.0
VERSION= 1.2.2
CATEGORIES= wip
MASTER_SITES= ${MASTER_SITE_SOURCEFORGE:=mrpt/}
MASTER_REPOSITORY= https://github.com/jlblancoc/mrpt
......
@comment Mon Apr 28 10:46:12 CEST 2014
@comment Fri Oct 3 09:32:21 CEST 2014
bin/2d-slam-demo
bin/DifOdometry-Datasets
bin/GridmapNavSimul
......@@ -45,6 +45,7 @@ include/mrpt/base/include/mrpt/compress.h
include/mrpt/base/include/mrpt/compress/zip.h
include/mrpt/base/include/mrpt/math.h
include/mrpt/base/include/mrpt/math/CArray.h
include/mrpt/base/include/mrpt/math/CArrayNumeric.h
include/mrpt/base/include/mrpt/math/CBinaryRelation.h
include/mrpt/base/include/mrpt/math/CHistogram.h
include/mrpt/base/include/mrpt/math/CLevenbergMarquardt.h
......@@ -61,29 +62,37 @@ include/mrpt/base/include/mrpt/math/CQuaternion.h
include/mrpt/base/include/mrpt/math/CSparseMatrix.h
include/mrpt/base/include/mrpt/math/CSparseMatrixTemplate.h
include/mrpt/base/include/mrpt/math/CSplineInterpolator1D.h
include/mrpt/base/include/mrpt/math/CVectorTemplate.h
include/mrpt/base/include/mrpt/math/KDTreeCapable.h
include/mrpt/base/include/mrpt/math/MatrixBlockSparseCols.h
include/mrpt/base/include/mrpt/math/data_utils.h
include/mrpt/base/include/mrpt/math/distributions.h
include/mrpt/base/include/mrpt/math/eigen_frwds.h
include/mrpt/base/include/mrpt/math/eigen_plugins.h
include/mrpt/base/include/mrpt/math/eigen_plugins_impl.h
include/mrpt/base/include/mrpt/math/fourier.h
include/mrpt/base/include/mrpt/math/geometry.h
include/mrpt/base/include/mrpt/math/homog_matrices.h
include/mrpt/base/include/mrpt/math/interp_fit.h
include/mrpt/base/include/mrpt/math/jacobians.h
include/mrpt/base/include/mrpt/math/kmeans.h
include/mrpt/base/include/mrpt/math/lightweight_geom_data.h
include/mrpt/base/include/mrpt/math/math_frwds.h
include/mrpt/base/include/mrpt/math/matrix_adaptors.h
include/mrpt/base/include/mrpt/math/matrix_serialization.h
include/mrpt/base/include/mrpt/math/model_search.h
include/mrpt/base/include/mrpt/math/model_search_impl.h
include/mrpt/base/include/mrpt/math/num_jacobian.h
include/mrpt/base/include/mrpt/math/ops_containers.h
include/mrpt/base/include/mrpt/math/ops_matrices.h
include/mrpt/base/include/mrpt/math/ops_vectors.h
include/mrpt/base/include/mrpt/math/point_poses2vectors.h
include/mrpt/base/include/mrpt/math/ransac.h
include/mrpt/base/include/mrpt/math/ransac_applications.h
include/mrpt/base/include/mrpt/math/robust_kernels.h
include/mrpt/base/include/mrpt/math/slerp.h
include/mrpt/base/include/mrpt/math/transform_gaussian.h
include/mrpt/base/include/mrpt/math/utils.h
include/mrpt/base/include/mrpt/math/wrap2pi.h
include/mrpt/base/include/mrpt/math_mrpt.h
include/mrpt/base/include/mrpt/otherlibs/CSparse/cs.h
include/mrpt/base/include/mrpt/otherlibs/do_opencv_includes.h
......@@ -151,6 +160,7 @@ include/mrpt/base/include/mrpt/poses/CPoses2DSequence.h
include/mrpt/base/include/mrpt/poses/CPoses3DSequence.h
include/mrpt/base/include/mrpt/poses/CRobot2DPoseEstimator.h
include/mrpt/base/include/mrpt/poses/SE_traits.h
include/mrpt/base/include/mrpt/poses/poses_frwds.h
include/mrpt/base/include/mrpt/random.h
include/mrpt/base/include/mrpt/random/RandomGenerators.h
include/mrpt/base/include/mrpt/synch.h
......@@ -171,12 +181,14 @@ include/mrpt/base/include/mrpt/system/os.h
include/mrpt/base/include/mrpt/system/parallelization.h
include/mrpt/base/include/mrpt/system/string_utils.h
include/mrpt/base/include/mrpt/system/threads.h
include/mrpt/base/include/mrpt/system/vector_loadsave.h
include/mrpt/base/include/mrpt/utils.h
include/mrpt/base/include/mrpt/utils/CCanvas.h
include/mrpt/base/include/mrpt/utils/CClientTCPSocket.h
include/mrpt/base/include/mrpt/utils/CConfigFile.h
include/mrpt/base/include/mrpt/utils/CConfigFileBase.h
include/mrpt/base/include/mrpt/utils/CConfigFileMemory.h
include/mrpt/base/include/mrpt/utils/CConfigFilePrefixer.h
include/mrpt/base/include/mrpt/utils/CConsoleRedirector.h
include/mrpt/base/include/mrpt/utils/CDebugOutputCapable.h
include/mrpt/base/include/mrpt/utils/CDynamicGrid.h
......@@ -227,34 +239,45 @@ include/mrpt/base/include/mrpt/utils/TParameters.h
include/mrpt/base/include/mrpt/utils/TPixelCoord.h
include/mrpt/base/include/mrpt/utils/TStereoCamera.h
include/mrpt/base/include/mrpt/utils/TTypeName.h
include/mrpt/base/include/mrpt/utils/TTypeName_impl.h
include/mrpt/base/include/mrpt/utils/adapters.h
include/mrpt/base/include/mrpt/utils/aligned_containers.h
include/mrpt/base/include/mrpt/utils/bimap.h
include/mrpt/base/include/mrpt/utils/bits.h
include/mrpt/base/include/mrpt/utils/boost_join.h
include/mrpt/base/include/mrpt/utils/ci_less.h
include/mrpt/base/include/mrpt/utils/circular_buffer.h
include/mrpt/base/include/mrpt/utils/color_maps.h
include/mrpt/base/include/mrpt/utils/compiler_fixes.h
include/mrpt/base/include/mrpt/utils/core_defs.h
include/mrpt/base/include/mrpt/utils/crc.h
include/mrpt/base/include/mrpt/utils/exceptions.h
include/mrpt/base/include/mrpt/utils/list_searchable.h
include/mrpt/base/include/mrpt/utils/map_as_vector.h
include/mrpt/base/include/mrpt/utils/md5.h
include/mrpt/base/include/mrpt/utils/metaprogramming.h
include/mrpt/base/include/mrpt/utils/metaprogramming_serialization.h
include/mrpt/base/include/mrpt/utils/mrptEvent.h
include/mrpt/base/include/mrpt/utils/mrpt_inttypes.h
include/mrpt/base/include/mrpt/utils/mrpt_macros.h
include/mrpt/base/include/mrpt/utils/mrpt_stdint.h
include/mrpt/base/include/mrpt/utils/msvc_inttypes.h
include/mrpt/base/include/mrpt/utils/net_utils.h
include/mrpt/base/include/mrpt/utils/printf_vector.h
include/mrpt/base/include/mrpt/utils/pstdint.h
include/mrpt/base/include/mrpt/utils/round.h
include/mrpt/base/include/mrpt/utils/safe_pointers.h
include/mrpt/base/include/mrpt/utils/stl_containers_utils.h
include/mrpt/base/include/mrpt/utils/stl_extensions.h
include/mrpt/base/include/mrpt/utils/stl_serialization.h
include/mrpt/base/include/mrpt/utils/traits_map.h
include/mrpt/base/include/mrpt/utils/types.h
include/mrpt/base/include/mrpt/utils/unittests.h
include/mrpt/base/include/mrpt/utils/types_math.h
include/mrpt/base/include/mrpt/utils/types_simple.h
include/mrpt/base/include/mrpt/utils/utils_defs.h
include/mrpt/bayes/include/mrpt/bayes.h
include/mrpt/bayes/include/mrpt/bayes/CKalmanFilterCapable.h
include/mrpt/bayes/include/mrpt/bayes/CKalmanFilterCapable_impl.h
include/mrpt/bayes/include/mrpt/bayes/CRejectionSamplingCapable.h
include/mrpt/detectors/include/mrpt/detectors.h
include/mrpt/detectors/include/mrpt/detectors/CCascadeClassifierDetection.h
......@@ -274,6 +297,7 @@ include/mrpt/graphs/include/mrpt/graphs/dijkstra.h
include/mrpt/graphslam/include/mrpt/graphslam.h
include/mrpt/graphslam/include/mrpt/graphslam/levmarq.h
include/mrpt/graphslam/include/mrpt/graphslam/levmarq_impl.h
include/mrpt/graphslam/include/mrpt/graphslam/link_pragmas.h
include/mrpt/graphslam/include/mrpt/graphslam/types.h
include/mrpt/gui/include/mrpt/gui.h
include/mrpt/gui/include/mrpt/gui/CBaseGUIWindow.h
......@@ -309,9 +333,11 @@ include/mrpt/hwdrivers/include/mrpt/hwdrivers/CBoardIR.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CBoardSonars.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CCANBusReader.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CCameraSensor.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CDUO3DCamera.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CEnoseModular.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CFFMPEG_InputStream.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CGPSInterface.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CGPS_NTRIP.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CGenericSensor.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CGyroKVHDSP3000.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CHokuyoURG.h
......@@ -330,11 +356,15 @@ include/mrpt/hwdrivers/include/mrpt/hwdrivers/CLMS100eth.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CNTRIPClient.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CNTRIPEmitter.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CNationalInstrumentsDAQ.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/COpenNI2Generic.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/COpenNI2Sensor.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/COpenNI2_RGBD360.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CPhidgetInterfaceKitProximitySensors.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CPtuBase.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CPtuDPerception.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CPtuHokuyo.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CRaePID.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CRoboPeakLidar.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CRoboticHeadInterface.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CRovio.h
include/mrpt/hwdrivers/include/mrpt/hwdrivers/CSerialPort.h
......@@ -412,6 +442,7 @@ include/mrpt/mrpt-config/mrpt/config.h
include/mrpt/mrpt-config/mrpt/version.h
include/mrpt/obs/include/mrpt/obs.h
include/mrpt/obs/include/mrpt/obs/link_pragmas.h
include/mrpt/obs/include/mrpt/obs/obs_frwds.h
include/mrpt/obs/include/mrpt/slam/CAction.h
include/mrpt/obs/include/mrpt/slam/CActionCollection.h
include/mrpt/obs/include/mrpt/slam/CActionRobotMovement2D.h
......@@ -422,6 +453,7 @@ include/mrpt/obs/include/mrpt/slam/CObservation.h
include/mrpt/obs/include/mrpt/slam/CObservation2DRangeScan.h
include/mrpt/obs/include/mrpt/slam/CObservation3DRangeScan.h
include/mrpt/obs/include/mrpt/slam/CObservation3DRangeScan_project3D_impl.h
include/mrpt/obs/include/mrpt/slam/CObservation6DFeatures.h
include/mrpt/obs/include/mrpt/slam/CObservationBatteryState.h
include/mrpt/obs/include/mrpt/slam/CObservationBeaconRanges.h
include/mrpt/obs/include/mrpt/slam/CObservationBearingRange.h
......@@ -433,6 +465,7 @@ include/mrpt/obs/include/mrpt/slam/CObservationIMU.h
include/mrpt/obs/include/mrpt/slam/CObservationImage.h
include/mrpt/obs/include/mrpt/slam/CObservationOdometry.h
include/mrpt/obs/include/mrpt/slam/CObservationRFID.h
include/mrpt/obs/include/mrpt/slam/CObservationRGBD360.h
include/mrpt/obs/include/mrpt/slam/CObservationRange.h
include/mrpt/obs/include/mrpt/slam/CObservationRawDAQ.h
include/mrpt/obs/include/mrpt/slam/CObservationReflectivity.h
......@@ -448,6 +481,7 @@ include/mrpt/obs/include/mrpt/slam/carmen_log_tools.h
include/mrpt/opengl/include/mrpt/opengl.h
include/mrpt/opengl/include/mrpt/opengl/C3DSScene.h
include/mrpt/opengl/include/mrpt/opengl/CArrow.h
include/mrpt/opengl/include/mrpt/opengl/CAssimpModel.h
include/mrpt/opengl/include/mrpt/opengl/CAxis.h
include/mrpt/opengl/include/mrpt/opengl/CBox.h
include/mrpt/opengl/include/mrpt/opengl/CCamera.h
......@@ -493,6 +527,7 @@ include/mrpt/opengl/include/mrpt/opengl/graph_tools.h
include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h
include/mrpt/opengl/include/mrpt/opengl/link_pragmas.h
include/mrpt/opengl/include/mrpt/opengl/opengl_fonts.h
include/mrpt/opengl/include/mrpt/opengl/opengl_frwds.h
include/mrpt/opengl/include/mrpt/opengl/pose_pdfs.h
include/mrpt/opengl/include/mrpt/opengl/stock_objects.h
include/mrpt/opengl/include/otherlibs/freeglut/GL/freeglut.h
......@@ -520,7 +555,6 @@ include/mrpt/reactivenav/include/mrpt/reactivenav/CReactiveNavigationSystem.h
include/mrpt/reactivenav/include/mrpt/reactivenav/CReactiveNavigationSystem3D.h
include/mrpt/reactivenav/include/mrpt/reactivenav/link_pragmas.h
include/mrpt/reactivenav/include/mrpt/reactivenav/motion_planning_utils.h
include/mrpt/scanmatching/include/mrpt/scan_matching.h
include/mrpt/scanmatching/include/mrpt/scanmatching.h
include/mrpt/scanmatching/include/mrpt/scanmatching/link_pragmas.h
include/mrpt/scanmatching/include/mrpt/scanmatching/scan_matching.h
......@@ -566,6 +600,7 @@ include/mrpt/srba/include/mrpt/srba/impl/eval_overall_error.h
include/mrpt/srba/include/mrpt/srba/impl/export_dot.h
include/mrpt/srba/include/mrpt/srba/impl/export_opengl.h
include/mrpt/srba/include/mrpt/srba/impl/export_opengl_landmark_renderers.h
include/mrpt/srba/include/mrpt/srba/impl/get_global_graphslam_problem.h
include/mrpt/srba/include/mrpt/srba/impl/jacobians.h
include/mrpt/srba/include/mrpt/srba/impl/lev-marq_solvers.h
include/mrpt/srba/include/mrpt/srba/impl/optimize_edges.h
......@@ -617,51 +652,53 @@ include/mrpt/vision/include/mrpt/vision/descriptor_pairing.h
include/mrpt/vision/include/mrpt/vision/link_pragmas.h
include/mrpt/vision/include/mrpt/vision/multiDesc_utils.h
include/mrpt/vision/include/mrpt/vision/pinhole.h
include/mrpt/vision/include/mrpt/vision/robust_kernels.h
include/mrpt/vision/include/mrpt/vision/tracking.h
include/mrpt/vision/include/mrpt/vision/types.h
include/mrpt/vision/include/mrpt/vision/utils.h
lib/libassimp-mrpt.so
lib/libassimp-mrpt.so.3
lib/libassimp-mrpt.so.3.1.1
lib/libmrpt-base.so
lib/libmrpt-base.so.1.1
lib/libmrpt-base.so.1.2
lib/libmrpt-base.so.${PKGVERSION}
lib/libmrpt-detectors.so
lib/libmrpt-detectors.so.1.1
lib/libmrpt-detectors.so.1.2
lib/libmrpt-detectors.so.${PKGVERSION}
lib/libmrpt-gui.so
lib/libmrpt-gui.so.1.1
lib/libmrpt-gui.so.1.2
lib/libmrpt-gui.so.${PKGVERSION}
lib/libmrpt-hmtslam.so
lib/libmrpt-hmtslam.so.1.1
lib/libmrpt-hmtslam.so.1.2
lib/libmrpt-hmtslam.so.${PKGVERSION}
lib/libmrpt-hwdrivers.so
lib/libmrpt-hwdrivers.so.1.1
lib/libmrpt-hwdrivers.so.1.2
lib/libmrpt-hwdrivers.so.${PKGVERSION}
lib/libmrpt-kinematics.so
lib/libmrpt-kinematics.so.1.1
lib/libmrpt-kinematics.so.1.2
lib/libmrpt-kinematics.so.${PKGVERSION}
lib/libmrpt-maps.so
lib/libmrpt-maps.so.1.1
lib/libmrpt-maps.so.1.2
lib/libmrpt-maps.so.${PKGVERSION}
lib/libmrpt-obs.so
lib/libmrpt-obs.so.1.1
lib/libmrpt-obs.so.1.2
lib/libmrpt-obs.so.${PKGVERSION}
lib/libmrpt-opengl.so
lib/libmrpt-opengl.so.1.1
lib/libmrpt-opengl.so.1.2
lib/libmrpt-opengl.so.${PKGVERSION}
lib/libmrpt-reactivenav.so
lib/libmrpt-reactivenav.so.1.1
lib/libmrpt-reactivenav.so.1.2
lib/libmrpt-reactivenav.so.${PKGVERSION}
lib/libmrpt-scanmatching.so
lib/libmrpt-scanmatching.so.1.1
lib/libmrpt-scanmatching.so.1.2
lib/libmrpt-scanmatching.so.${PKGVERSION}
lib/libmrpt-slam.so
lib/libmrpt-slam.so.1.1
lib/libmrpt-slam.so.1.2
lib/libmrpt-slam.so.${PKGVERSION}
lib/libmrpt-topography.so
lib/libmrpt-topography.so.1.1
lib/libmrpt-topography.so.1.2
lib/libmrpt-topography.so.${PKGVERSION}
lib/libmrpt-vision.so
lib/libmrpt-vision.so.1.1
lib/libmrpt-vision.so.1.2
lib/libmrpt-vision.so.${PKGVERSION}
lib/pkgconfig/mrpt-base.pc
lib/pkgconfig/mrpt-bayes.pc
......@@ -688,8 +725,12 @@ share/applications/navlog-viewer.desktop
share/applications/prrtnavigatordemo.desktop
share/applications/rawlogviewer.desktop
share/applications/reactivenavdemo.desktop
share/applications/robotic-arm-kinematics.desktop
share/applications/sceneviewer.desktop
share/applications/stereocameracalib.desktop
share/man/man1/2d-slam-demo.1.gz
share/man/man1/DifOdometry-Camera.1.gz
share/man/man1/DifOdometry-Datasets.1.gz
share/man/man1/GridmapNavSimul.1.gz
share/man/man1/RawLogViewer.1.gz
share/man/man1/ReactiveNav3D-Demo.1.gz
......@@ -738,6 +779,7 @@ share/mrpt/config_files/README.txt
share/mrpt/config_files/grid-matching/gridmatch_example.ini
share/mrpt/config_files/hmt-slam/freidburg.ini
share/mrpt/config_files/hmt-slam/malaga.ini
share/mrpt/config_files/icp-graph-slam/icp-graph-slam.ini
share/mrpt/config_files/icp-slam/icp-gas-mapping.ini
share/mrpt/config_files/icp-slam/icp-slam_demo_LM.ini
share/mrpt/config_files/icp-slam/icp-slam_demo_classic.ini
......@@ -765,9 +807,11 @@ share/mrpt/config_files/rawlog-grabber/PhidgetIK.ini
share/mrpt/config_files/rawlog-grabber/RFID.ini
share/mrpt/config_files/rawlog-grabber/SICK_LMS_500k.ini
share/mrpt/config_files/rawlog-grabber/SICK_LMS_serial.ini
share/mrpt/config_files/rawlog-grabber/SICK_custom_rs422_USB.ini
share/mrpt/config_files/rawlog-grabber/Wifi.ini
share/mrpt/config_files/rawlog-grabber/activmedia_robot.ini
share/mrpt/config_files/rawlog-grabber/camera_1394.ini
share/mrpt/config_files/rawlog-grabber/camera_duo3d.ini
share/mrpt/config_files/rawlog-grabber/camera_opencv.ini
share/mrpt/config_files/rawlog-grabber/camera_pgr_flycap.ini
share/mrpt/config_files/rawlog-grabber/camera_pgr_flycap_stereo.ini
......@@ -778,9 +822,13 @@ share/mrpt/config_files/rawlog-grabber/hokuyo_UTM.ini
share/mrpt/config_files/rawlog-grabber/hokuyo_UXM.ini
share/mrpt/config_files/rawlog-grabber/kinect.ini
share/mrpt/config_files/rawlog-grabber/ntrip_emitter.ini
share/mrpt/config_files/rawlog-grabber/openNI2.ini
share/mrpt/config_files/rawlog-grabber/patrolbot_enoses.ini
share/mrpt/config_files/rawlog-grabber/ptuHokuyo.ini
share/mrpt/config_files/rawlog-grabber/ptuHokuyoCamera.ini
share/mrpt/config_files/rawlog-grabber/rgbd360.ini
share/mrpt/config_files/rawlog-grabber/rgbd_2sensors.ini
share/mrpt/config_files/rawlog-grabber/rgbd_4sensors.ini
share/mrpt/config_files/rawlog-grabber/roadbot-all.ini
share/mrpt/config_files/rawlog-grabber/rtkgps-lasers.ini
share/mrpt/config_files/rawlog-grabber/swissranger_cam.ini
......@@ -863,4 +911,5 @@ share/pixmaps/mrpt_icon.ico
share/pixmaps/navlog-viewer.xpm
share/pixmaps/rawlogviewer.xpm
share/pixmaps/reactivenav.xpm
share/pixmaps/robotic-arm-kinematics.xpm
share/pixmaps/sceneviewer.xpm
SHA1 (mrpt-1.1.0.tar.gz) = e8a8f67831171aa0f57478663173824fd14ed8ff
RMD160 (mrpt-1.1.0.tar.gz) = 76d5af8142a541fcb22101254c7650cfe1dde776
Size (mrpt-1.1.0.tar.gz) = 21879287 bytes
SHA1 (mrpt-1.2.2.tar.gz) = 30936e4af61539b976d213415b82c7a0c3aae4a9
RMD160 (mrpt-1.2.2.tar.gz) = aa24a73048655e82d9c381bcbbcb07a4ad97995c
Size (mrpt-1.2.2.tar.gz) = 22496370 bytes
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment