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

ros timer bug?

asked 2017-08-18 06:34:53 -0500

TwoBid gravatar image

updated 2017-09-04 04:02:00 -0500

Hi,

I'm currently writing a simple application to publish a message only for certain time. For that I used a oneshoot timer which is setting a flag. The outcome was that the flag and so the timer event was triggered almost at the beginning of the application, although I set a long Duration period. Than I tried an example from the wki link with a similar behavior.

void callback1(const ros::TimerEvent&) {
  ROS_INFO("Callback 1 triggered");
}

void callback2(const ros::TimerEvent&) {  
  ROS_INFO("Callback 2 triggered"); 
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "test");
  ros::NodeHandle n;

  ros::Timer timer1 = n.createTimer(ros::Duration(0.1), callback1);
  ros::Timer timer2 = n.createTimer(ros::Duration(1.0), callback2);
  ros::spin();

  return 0;
}

Result of this Code is the following:

[ INFO] [1503044891.821472262, 1979.528000000]: Callback 1 triggered
[ INFO] [1503044891.821598505, 1979.528000000]: Callback 2 triggered
[ INFO] [1503044891.821659684, 1979.528000000]: Callback 1 triggered
[ INFO] [1503044891.821695171, 1979.528000000]: Callback 2 triggered
[ INFO] [1503044891.922356425, 1979.629000000]: Callback 1 triggered
[ INFO] [1503044892.021857347, 1979.728000000]: Callback 1 triggered
[ INFO] [1503044892.121675024, 1979.828000000]: Callback 1 triggered
[ INFO] [1503044892.221838279, 1979.928000000]: Callback 1 triggered
[ INFO] [1503044892.323168866, 1980.028000000]: Callback 1 triggered
[ INFO] [1503044892.445560190, 1980.128000000]: Callback 1 triggered
[ INFO] [1503044892.546153145, 1980.228000000]: Callback 1 triggered
[ INFO] [1503044892.647412716, 1980.329000000]: Callback 1 triggered
[ INFO] [1503044892.747397039, 1980.428000000]: Callback 1 triggered
[ INFO] [1503044892.848747723, 1980.528000000]: Callback 2 triggered
[ INFO] [1503044892.848827195, 1980.528000000]: Callback 1 triggered
[ INFO] [1503044892.950519122, 1980.628000000]: Callback 1 triggered
[ INFO] [1503044893.050009460, 1980.728000000]: Callback 1 triggered

Where I would expect that trigger 2 should occur after one second.

Am I doing something wrong or is this a known issue?

To resolve that I'm waiting before the timer creation for like 200ms.

Thanks for the help, cheers Robert

edit retag flag offensive close merge delete

Comments

I tried this in Kinetic on Ubuntu 16.04 and it triggers properly.

lucasw gravatar image lucasw  ( 2017-08-19 08:31:14 -0500 )edit

I can reproduce my error when I use gazebo and launch an empty world. When I use the code above with initially executed roscore, it works! Can someone confirm that?

TwoBid gravatar image TwoBid  ( 2017-08-30 05:56:43 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2017-09-02 10:23:51 -0500

lucasw gravatar image

updated 2017-09-02 19:07:59 -0500

I haven't tried out empty world yet, but I did set up a more stripped down test that uses a sim clock from a python script https://github.com/lucasw/simple_sim_...

rosparam set /use_sim_time true
rosrun sim_clock timer_test
rosrun sim_clock sim_clock.py


...
  << ", wall: " << ros::WallTime::now() - wall_start
  << ", now: " << ros::Time::now() - start
  << ", expected: " << (e.current_expected - start).toSec()
  << ", real: " << (e.current_real - start).toSec()
...


[ INFO] [/test] [/home/lucasw/catkin_ws/src/simple_sim_ros/sim_clock/src/timer_test.cpp]:[40] [, wall: 1504364679.261232420, now: 0.230000000]
callback 1, wall: 0.10244, now: 0.10, expected: 0.1, real: 0.1
callback 1, wall: 0.20321, now: 0.20, expected: 0.2, real: 0.2
callback 1, wall: 0.30502, now: 0.30, expected: 0.3, real: 0.3
callback 1, wall: 0.40672, now: 0.40, expected: 0.4, real: 0.4
callback 1, wall: 0.50889, now: 0.50, expected: 0.5, real: 0.5
callback 1, wall: 0.60994, now: 0.60, expected: 0.6, real: 0.6
callback 1, wall: 0.71131, now: 0.70, expected: 0.7, real: 0.7
callback 1, wall: 0.81358, now: 0.80, expected: 0.8, real: 0.8
callback 1, wall: 0.91572, now: 0.90, expected: 0.9, real: 0.9
callback 2, wall: 1.01783, now: 1.00, expected: 1, real: 1
callback 1, wall: 1.01788, now: 1.00, expected: 1, real: 1
...

The odd thing I see is the sim time is 0.23 when it should be much closer to 0 after the sleep:

  ros::init(argc, argv, "test");
  ros::NodeHandle n;

  // don't get the wall time until a clock has been received
  ros::Duration(0.0001).sleep();
  start = ros::Time::now();
  wall_start = ros::WallTime::now();
  ROS_INFO_STREAM("wall: " << wall_start
      << ", now: " << start);

I'm curious what gazebo is doing with publishing /clock at start time (I'll try out empty.world and update this later) - it could be that it publish it once but then takes a second to initialize other things (and repeats that once more?).

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2017-08-18 06:34:53 -0500

Seen: 773 times

Last updated: Sep 04 '17