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

ros::Walltime differs from chrono::clock?

asked 2023-01-10 04:45:00 -0600

tang gravatar image

Hi! I recently wanted to improve the computational efficiency of IPOPT solver and my costumed mpc_local_planner. Before that my mpc_local_node was taking 0.3-0.5s per iteration, which obviously does not meet the requirements of real-time control.

So I checked the running time of each function of the code and found that IPOPT actually only uses 20-40ms to calculate the optimal solution.

Total seconds in IPOPT                               = 0.025

And within the same function I used four different time output methods and found that ros::walltime and chrono::clock are exactly ten times different. Is chrono::clock the correct time? And ros::walltime is slowed down by a factor of 10 for some reason?

Here is my Code for time output:

    ros::Time end1 = ros::Time::now();
    ros::WallTime wall_end = ros::WallTime::now();
    auto t_end = std::chrono::high_resolution_clock::now();
    cout << "Duration_loop(ros Time): " << end1.sec - begin1.sec << "." << end1.nsec - begin1.nsec << "s" << std::endl;
    cout << "Duration_loop(ros WallTime): " << wall_end << ", " << wall_end.sec - wall_begin.sec << "." << wall_end.nsec - wall_begin.nsec << "s" << std::endl;
    std::cout << "Duration loop(CPU Time): "  << float( clock () - begin_time_2 ) /  CLOCKS_PER_SEC << "s" << std::endl;
    std::cout << "Duration loop(Chrono CPU Time): " << std::chrono::duration<double, std::milli>(t_end-t_start).count() << "ms"<< std::endl;

And the Output (chrono time is in ms):

Duration_loop(ros Time): 0.43000000s
Duration_loop(ros WallTime): 1673347284.124544067, 0.43919478s
Duration loop(CPU Time): 0.033641s
Duration loop(Chrono CPU Time): 43.9134ms

I use gazebo and use_sim_time = true, so there are some differences between ros::Time and ros::Walltime.

Could someone help me, and thank you very much in advance!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2023-01-11 10:05:08 -0600

Mike Scheutzow gravatar image

cout << "Duration_loop(ros Time): " << end1.sec - begin1.sec << "." << end1.nsec - begin1.nsec << "s" << std::endl;

Both the integer and decimal sides of this calculation are not valid. The correct way to calculate this is:

double d = (end1 - begin1).toSec();
edit flag offensive delete link more

Comments

It works! Thank you very much for the explanation.

tang gravatar image tang  ( 2023-01-11 15:23:13 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2023-01-10 04:45:00 -0600

Seen: 171 times

Last updated: Jan 11 '23