mirror of
https://github.com/MAPIRlab/rf2o_laser_odometry.git
synced 2023-04-06 19:28:55 +08:00
replace mrpt::utils::CTicTac by ros::Time
This commit is contained in:
@@ -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_;
|
||||
|
||||
@@ -175,7 +175,8 @@ bool CLaserOdometry2D::odometryCalculation(const sensor_msgs::LaserScan& scan)
|
||||
for (unsigned int i = 0; i<width; i++)
|
||||
range_wf(i) = scan.ranges[i];
|
||||
|
||||
m_clock.Tic();
|
||||
ros::Time start = ros::Time::now();
|
||||
|
||||
createImagePyramid();
|
||||
|
||||
//Coarse-to-fine scheme
|
||||
@@ -225,9 +226,9 @@ bool CLaserOdometry2D::odometryCalculation(const sensor_msgs::LaserScan& scan)
|
||||
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
|
||||
PoseUpdate();
|
||||
|
||||
Reference in New Issue
Block a user