From 43d0c05e0f40db91501e7a13814ac8e13579d128 Mon Sep 17 00:00:00 2001 From: Jeremie Deray Date: Tue, 15 Aug 2017 15:49:35 +0200 Subject: [PATCH] replace mrpt::utils::CTicTac by ros::Time --- include/rf2o_laser_odometry/CLaserOdometry2D.h | 4 +--- src/CLaserOdometry2D.cpp | 7 ++++--- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/include/rf2o_laser_odometry/CLaserOdometry2D.h b/include/rf2o_laser_odometry/CLaserOdometry2D.h index 27915e6..91e783f 100644 --- a/include/rf2o_laser_odometry/CLaserOdometry2D.h +++ b/include/rf2o_laser_odometry/CLaserOdometry2D.h @@ -160,9 +160,7 @@ protected: double lin_speed, ang_speed; - //mrpt::gui::CDisplayWindowPlots window; - mrpt::utils::CTicTac m_clock; - float m_runtime; + ros::Duration m_runtime; ros::Time last_odom_time, current_scan_time; MatrixS31 kai_abs_; diff --git a/src/CLaserOdometry2D.cpp b/src/CLaserOdometry2D.cpp index 24c6339..91ec354 100644 --- a/src/CLaserOdometry2D.cpp +++ b/src/CLaserOdometry2D.cpp @@ -175,7 +175,8 @@ bool CLaserOdometry2D::odometryCalculation(const sensor_msgs::LaserScan& scan) for (unsigned int i = 0; i