diff --git a/include/rf2o_laser_odometry/CLaserOdometry2D.h b/include/rf2o_laser_odometry/CLaserOdometry2D.h index 4f70b5b..7feb83a 100644 --- a/include/rf2o_laser_odometry/CLaserOdometry2D.h +++ b/include/rf2o_laser_odometry/CLaserOdometry2D.h @@ -25,10 +25,11 @@ #if MRPT_VERSION>=0x130 # include # include - using namespace mrpt::obs; + typedef mrpt::obs::CObservation2DRangeScan CObservation2DRangeScan; #else # include # include + typedef mrpt::poses::CObservation2DRangeScan CObservation2DRangeScan; #endif @@ -166,7 +167,7 @@ protected: void solveSystemNonLinear(); void filterLevelSolution(); void PoseUpdate(); - void Reset(mrpt::poses::CPose3D ini_pose, mrpt::poses::CObservation2DRangeScan scan); + void Reset(mrpt::poses::CPose3D ini_pose, CObservation2DRangeScan scan); }; #endif diff --git a/src/CLaserOdometry2D.cpp b/src/CLaserOdometry2D.cpp index 5d3d0a0..d3dc87d 100644 --- a/src/CLaserOdometry2D.cpp +++ b/src/CLaserOdometry2D.cpp @@ -708,7 +708,7 @@ void CLaserOdometry2D::solveSystemNonLinear() std::cout << endl << "[rf2o] COV_ODO: " << cov_odo << endl; } -void CLaserOdometry2D::Reset(mrpt::poses::CPose3D ini_pose, mrpt::poses::CObservation2DRangeScan scan) +void CLaserOdometry2D::Reset(mrpt::poses::CPose3D ini_pose, CObservation2DRangeScan scan) { //Set the initial pose laser_pose = ini_pose;