replace mrpt::utils::CTicTac by ros::Time

This commit is contained in:
Jeremie Deray
2017-08-15 15:49:35 +02:00
parent f84885b47d
commit 43d0c05e0f
2 changed files with 5 additions and 6 deletions

View File

@@ -160,9 +160,7 @@ protected:
double lin_speed, ang_speed; double lin_speed, ang_speed;
//mrpt::gui::CDisplayWindowPlots window; ros::Duration m_runtime;
mrpt::utils::CTicTac m_clock;
float m_runtime;
ros::Time last_odom_time, current_scan_time; ros::Time last_odom_time, current_scan_time;
MatrixS31 kai_abs_; MatrixS31 kai_abs_;

View File

@@ -175,7 +175,8 @@ bool CLaserOdometry2D::odometryCalculation(const sensor_msgs::LaserScan& scan)
for (unsigned int i = 0; i<width; i++) for (unsigned int i = 0; i<width; i++)
range_wf(i) = scan.ranges[i]; range_wf(i) = scan.ranges[i];
m_clock.Tic(); ros::Time start = ros::Time::now();
createImagePyramid(); createImagePyramid();
//Coarse-to-fine scheme //Coarse-to-fine scheme
@@ -225,9 +226,9 @@ bool CLaserOdometry2D::odometryCalculation(const sensor_msgs::LaserScan& scan)
filterLevelSolution(); filterLevelSolution();
} }
m_runtime = 1000*m_clock.Tac(); m_runtime = ros::Time::now() - start;
ROS_INFO_COND(verbose, "[rf2o] execution time (ms): %f", m_runtime); ROS_INFO_COND(verbose, "[rf2o] execution time (ms): %f", (1000*m_runtime.toNSec()));
//Update poses //Update poses
PoseUpdate(); PoseUpdate();