Node not receiving update after simulated time is update on /clock topic.
Hello,
I am playing a bit with simulated time in ROS. I have one node that serves as the clock server, and another node that will do some calculations. At times it happens that if I start the calculator node, and then the clock server, the calculator node never gets the updated time.
More in detail: I have roscore running in one terminal, the clock server in a second, and the calculator in a third. For both clock server and calculator I do the following when running them
Terminal 2
rosparam set /use_sim_time True
rosrun package clock
Terminal 3
rosparam set /use_sim_time True
rosrun package calculator
The code for the clock is as follows:
#!/usr/bin/env python
import rospy
import time
from rosgraph_msgs.msg import Clock
def simulation_clock(simulation_duration, time_step):
pub = rospy.Publisher('/clock', Clock, queue_size=10)
rospy.init_node('clock_agent', anonymous=True)
step = rospy.Time.now()
msg = Clock()
while not rospy.is_shutdown() and step.secs < simulation_duration:
step.secs += 1
msg.clock = step
pub.publish(msg)
time.sleep(time_step)
print "Simulated time is: %d" % rospy.get_rostime().secs
if __name__ == '__main__':
try:
duration = 10000
time_step = 1 #seconds
simulation_clock(duration, time_step)
except rospy.ROSInterruptException:
pass
The code for the calculator is as follows:
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
class Agent():
def __init__(self, ID, init_state):
rospy.init_node('agent', anonymous=True)
while rospy.Time.now().secs == 0:
pass
print "Simulated time is: %d" % rospy.get_rostime().secs
if __name__ == '__main__':
try:
instance = Agent(1, 0)
except rospy.ROSInterruptException:
pass
On the first start of roscore, if I run the calculator and then the clock I will get the updated time on the calculator line. However, if I shutdown the calculator and clock, and try to restart, the order matters, i.e., if I first start the clock and then the calculator, the latter will get the updated value. Whereas if I start the calculator and then the clock, the calculator doesn't get the updated clock value.
Any idea what's going on, what I am missing?
Thanks!
hw