You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I stumbled on a datarace bug in the ActionClient class when using actionlib in a Gazebo simulation (thus having /use_sim_time=true, and an external node that publishes the /clock topic).
To be able to reproduce the bug I created two simple roslaunch files here : https://github.com/1r0b1n0/actionlib_sim_time_datarace_test
On my system, more or less 1 out of 5 times starting the fibonacci_client node will fail and return immediately.
fibonacci_client calls ros::init(...), /use_sim_time is true so ros will subscribe to /clock (in its internal thread)
One second later fibonacci_client calls ac.waitForResult(ros::Duration(30.0))
In SimpleActionClient::waitForResult(ros::Duration &) , we have the instruction : ros::Time timeout_time = ros::Time::now() + timeout; (simple_action_client:551)
Sometimes this instruction is called when ros has not yet received the /clock topic from Gazebo, so ros::Time::isValid() is false, and ros::Time::now() will return ros::Time(0,0)
some milliseconds later, ros has received its first /clock from Gazebo ( in this case /clock is at 1271.800000000), so ros::Time::now() will return ros::Time(127.8) -> SimpleActionClient will timeout and return immediately
A solution would be to call ros::Time::waitForValid() in ActionClient::waitForActionServerToStart()
Thanks,
Robin
The text was updated successfully, but these errors were encountered:
Indeed in some cases I still had some issues (but like 1 out of 200 times).
Because the application is multi-threaded, we should also wait for ros:Time::now to become valid when constructing ConnectionManager
I submitted #62 that fixes those issues for me, does it work on your side ?
Hello,
I stumbled on a datarace bug in the ActionClient class when using actionlib in a Gazebo simulation (thus having /use_sim_time=true, and an external node that publishes the /clock topic).
To be able to reproduce the bug I created two simple roslaunch files here : https://github.com/1r0b1n0/actionlib_sim_time_datarace_test
On my system, more or less 1 out of 5 times starting the fibonacci_client node will fail and return immediately.
I uploaded the log of fibonacci_client here : https://github.com/1r0b1n0/actionlib_sim_time_datarace_test/blob/master/fibonacci_client_bug.log
This is what happened :
ros::init(...)
, /use_sim_time is true so ros will subscribe to /clock (in its internal thread)ac.waitForResult(ros::Duration(30.0))
In
SimpleActionClient::waitForResult(ros::Duration &)
, we have the instruction :ros::Time timeout_time = ros::Time::now() + timeout;
(simple_action_client:551)Sometimes this instruction is called when ros has not yet received the /clock topic from Gazebo, so
ros::Time::isValid()
is false, andros::Time::now()
will returnros::Time(0,0)
ros::Time::now()
will returnros::Time(127.8)
-> SimpleActionClient will timeout and return immediatelyA solution would be to call
ros::Time::waitForValid()
inActionClient::waitForActionServerToStart()
Thanks,
Robin
The text was updated successfully, but these errors were encountered: