[joint_state_publisher] Handle time moving backwards
Without this patch, joint_state_publisher dies whenever the ROS time moves backwards (e.g., when running `rosbag play --clock --loop`).
This commit is contained in:
parent
0a6b4915ce
commit
306e52ef8d
|
@ -238,7 +238,10 @@ class JointStatePublisher():
|
|||
msg.effort[i] = joint['effort']
|
||||
|
||||
self.pub.publish(msg)
|
||||
r.sleep()
|
||||
try:
|
||||
r.sleep()
|
||||
except rospy.exceptions.ROSTimeMovedBackwardsException:
|
||||
pass
|
||||
|
||||
def update(self, delta):
|
||||
for name, joint in self.free_joints.iteritems():
|
||||
|
|
Loading…
Reference in New Issue