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_;
|
||||
|
||||
Reference in New Issue
Block a user