ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
4

Accuracy / resolution of ROS time

asked 2012-06-05 17:57:48 -0500

updated 2012-06-05 20:17:42 -0500

I was doing some quick profiling of the execution time of a piece of code, and noticed that I was getting different answers depending on what method I use to get the current time.

EDIT: original test removed, added test as per Eric's suggestion.

I am running on: Ubuntu, 3.0.0-17-generic

The following code is inserted in a callback function, which is called asynchronously.

struct timeval s_get, e_get;
timespec s_crt, e_crt;
ros::Time s_ros, e_ros;

gettimeofday(&s_get, NULL);
clock_gettime(CLOCK_REALTIME,  &s_crt);
s_ros = ros::Time::now();

// **** do something here... ****

gettimeofday(&e_get, NULL);
clock_gettime(CLOCK_REALTIME,  &e_crt);
e_ros = ros::Time::now();

// print results
double dur_get = ((e_get.tv_sec * 10e6 + e_get.tv_usec) -
                  (s_get.tv_sec * 10e6 + s_get.tv_usec)) * 1e-3;
double dur_crt = ((e_crt.tv_sec * 10e9 + e_crt.tv_nsec) - 
                  (s_crt.tv_sec * 10e9 + s_crt.tv_nsec)) * 1e-6;
double dur_ros = (e_ros - s_ros).toNSec() * 1e-6;

printf("Dur [ms]: %.1f \t %.1f \t %.1f \n", dur_get, dur_crt, dur_ros);

Output:

Dur [ms]: 8.5     8.5      0.0 
Dur [ms]: 6.7     6.7     10.1 
Dur [ms]: 15.9     15.9     10.1 
Dur [ms]: 6.2     6.2      0.0 
Dur [ms]: 13.6  13.6     10.1 
Dur [ms]: 15.2  15.2     20.2 
Dur [ms]: 13.0  13.0     20.2 
Dur [ms]: 10.5  10.5     10.1 
Dur [ms]: 14.2  14.2     20.2 
Dur [ms]: 11.2  11.2     10.1 
Dur [ms]: 10.5  10.5     10.2 
Dur [ms]: 10.4  10.4     10.1 
Dur [ms]: 16.4  16.4     20.1 
Dur [ms]: 11.0  11.0     10.1 
Dur [ms]: 17.6  17.6     20.2 
Dur [ms]: 12.6  12.6     20.1 
Dur [ms]: 18.5  18.5     20.1 
Dur [ms]: 18.1  18.1     20.1 
Dur [ms]: 14.8  14.8     10.1 
Dur [ms]: 5.5     5.5      0.0 
Dur [ms]: 8.5     8.5     10.1 
Dur [ms]: 11.4  11.4     10.1 
Dur [ms]: 18.4  18.4     20.2 
Dur [ms]: 14.3  14.3     10.1 
Dur [ms]: 10.8  10.8     10.1 
Dur [ms]: 7.9     7.8      0.0 
Dur [ms]: 17.2  17.2     20.2

Consclusion

gettimeofday and clock_gettime result in similar durations, but ros::Time::now() durations are different.

I noticed that if I insert the example above in a loop at startup (instead of asynchronously inside a function), and tell it to sleep a certain time each iteration, I get 0.0 ms reported duration by ROS, and the correct duration with the other 2 methods. My only explanation is that ros::spinOnce() hasn't been called, and this is interfering with ros::Time::now().

This has very little impact on my profiling. However, I sometimes use the ros time to calculate velocities or other quantities in the form x/dt. In this case, poor temporal resolution like this would make a huge difference.

Could anyone comment on this? Am I doing something wrong?

EDIT 2

I was running using ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
6

answered 2012-06-05 18:34:33 -0500

Eric Perko gravatar image

It looks like the ros::Time is using the highest precision clock it can find, so perhaps it's more accurate than gettimeofday. The relevant code for not using sim_time appears to be: time.cpp:ros_walltime(uint32_t& sec, uint32_t& nsec). If we ignore all the WIN32 stuff, looks like the relevant snippet is here:

00101 #if HAS_CLOCK_GETTIME
00102     timespec start;
00103     clock_gettime(CLOCK_REALTIME, &start);
00104     sec  = start.tv_sec;
00105     nsec = start.tv_nsec;
00106 #else
00107     struct timeval timeofday;
00108     gettimeofday(&timeofday,NULL);
00109     sec  = timeofday.tv_sec;
00110     nsec = timeofday.tv_usec * 1000;
00111 #endif

I couldn't find anything with a quick Google search comparing the two, but it might be interesting to see if you have the same results as ros::Time if you use clock_gettime instead of gettimeofday in your profiling code.

If you need to get the current time for profiling reasons even when using sim_time, you should use ros::WallTime instead of ros::Time.

edit flag offensive delete link more

Comments

Thanks for the answer Eric, I have updated the original question with a more detailed test.

Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2012-06-05 20:13:23 -0500 )edit

The issue was ros::WallTime (I was running in simulation). Once I used that, everything worked fine!

Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2012-06-05 20:19:14 -0500 )edit

Ya... those being in units of 10ms and not matching up with the jitter in the non ROS clock_gettime seemed suspicious...

Eric Perko gravatar image Eric Perko  ( 2012-06-05 20:20:46 -0500 )edit

Question Tools

Stats

Asked: 2012-06-05 17:57:48 -0500

Seen: 6,278 times

Last updated: Jun 05 '12