Changes to make it work with MRPT 1.9

- Added C++14 flag to CMakeLists.txt
- Fixed conversion of CPoses
This commit is contained in:
Francisco Moreno
2017-08-03 18:38:12 +02:00
parent a076caae6e
commit 7d91aed999
3 changed files with 11 additions and 6 deletions

View File

@@ -1,5 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(rf2o_laser_odometry)
set (CMAKE_CXX_STANDARD 14) # Require C++14
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)

View File

@@ -26,15 +26,19 @@
// MRPT related headers
#include <mrpt/version.h>
#if MRPT_VERSION>=0x130
# include <mrpt/obs/CObservation2DRangeScan.h>
# include <mrpt/obs/CObservation2DRangeScan.h>
# include <mrpt/obs/CObservationOdometry.h>
using namespace mrpt::obs;
#else
# include <mrpt/slam/CObservation2DRangeScan.h>
# include <mrpt/slam/CObservation2DRangeScan.h>
# include <mrpt/slam/CObservationOdometry.h>
using namespace mrpt::slam;
#endif
#include <mrpt/system/threads.h>
#if MRPT_VERSION<0x150
# include <mrpt/system/threads.h>
#endif
#include <mrpt/system/os.h>
#include <mrpt/poses/CPose3D.h>
#include <mrpt/utils.h>

View File

@@ -144,8 +144,8 @@ void CLaserOdometry2D::Init()
//Set the initial pose
laser_pose = CPose2D(robotInitialPose + LaserPoseOnTheRobot);
laser_oldpose = CPose2D(robotInitialPose + LaserPoseOnTheRobot);
laser_pose = robotInitialPose + LaserPoseOnTheRobot;
laser_oldpose = robotInitialPose + LaserPoseOnTheRobot;
// Init module (internal)
@@ -943,7 +943,7 @@ void CLaserOdometry2D::PoseUpdate()
laser_oldpose = laser_pose;
math::CMatrixDouble33 aux_acu = acu_trans;
poses::CPose2D pose_aux_2D(acu_trans(0,2), acu_trans(1,2), kai_loc(2)/fps);
laser_pose = laser_pose + pose_aux_2D;
laser_pose = laser_pose + CPose3D(pose_aux_2D);