1. Reason
In robot applications, the sensing frequency of sensors can rarely be consistent,
For example, the odometer data can reach 50Hz, the image frequency can reach 30Hz, and the lidar data acquisition can reach 10Hz
Then the time must be out of synchronization, and some fusion algorithms need to synchronize the sensor data before fusion
what to do?
The whole tool filters or synchronizes time stamps
2. MessageFilter
Message filter message_filters are similar to a message cache
When the message reaches the message filter, it may not be output immediately, but output when certain conditions are met at a later time point
For example, a time synchronizer receives different types of messages from multiple sources
And output them only when they receive messages on each source with the same timestamp
That is, it has the effect of message synchronous output
3. Subscriber subscriber
Subscriber filter is the encapsulation of ROS subscription and provides source code for other filters
The subscriber filter cannot take the output of another filter as its input, but uses the ROS topic as its input
sub = message_filters.Subscriber("chatter", String) sub.registerCallback(callback)
Equivalent to
rospy.Subscriber("chatter", String, callback)
4. TimeSynchronizer
4.1. Time synchronizer
If absolute time synchronization is required, the timestamp is the same
The TimeSynchronizer filter synchronizes the input channel with a timestamp contained in its header
And output as a single callback. They need the same number of channels
4.2. Examples
Such as image and camera_info, images and camera information may need to be fully synchronized
4.2.1. Release documents
#!/usr/bin/env python3 import rospy # python client for importing rospy package ROS from sensor_msgs.msg import Image, CameraInfo # sensor_ Image, CameraInfo message type of msgs.msg package # Define the publisher function talker def talker(): image_pub = rospy.Publisher('image', Image, queue_size=1) # Define publisher image_pub publish image camera_info_pub = rospy.Publisher('camera_info', CameraInfo, queue_size=1) # Define publisher camera_info_pub publishes camera_info rospy.init_node('talker', anonymous=True) # Initialize node talker rate = rospy.Rate(1) # Initialize the object rate with the cycle frequency of 1HZ # Without exiting the program while not rospy.is_shutdown(): # time stamp current_time = rospy.Time.now() # Create and publish image messages image_msg = Image() image_msg.header.stamp = current_time rospy.loginfo("image:" + str(image_msg.header.stamp)) # The message is printed to the screen image_pub.publish(image_msg) # Release news # Create and publish new image messages image_msg = Image() image_msg.header.stamp = rospy.Time.now() rospy.loginfo("image:" + str(image_msg.header.stamp)) # The message is printed to the screen image_pub.publish(image_msg) # Release news # Create and publish camera_info message camera_info_msg = CameraInfo() camera_info_msg.header.stamp = current_time rospy.loginfo("camera_info:" + str(camera_info_msg.header.stamp)) # The message is printed to the screen camera_info_pub.publish(camera_info_msg) # Release news rate.sleep() # dormancy if __name__ == '__main__': try: talker() except rospy.ROSInterruptException: pass
4.2.2. Subscription file
#!/usr/bin/env python3 import rospy # python client for importing rospy package ROS import message_filters # Import message_filters packet message filters from sensor_msgs.msg import Image, CameraInfo # sensor_ Image, CameraInfo message type of msgs.msg package # Callback function def callback(data_image, data_amera_info): rospy.loginfo(rospy.get_caller_id() + "I heard %s ,%s", data_image.header.stamp, data_amera_info.header.stamp) # The message is printed to the screen def listener(): rospy.init_node('listener', anonymous=True) # Initialize node listener # Create message filter subscriber sub_image = message_filters.Subscriber("image", Image) camera_info_sub = message_filters.Subscriber("camera_info", CameraInfo) # Set the time synchronizer fs to wait for the message [sub_image, camera_info_sub], queue_size 10 sync_listener = message_filters.TimeSynchronizer([sub_image, camera_info_sub], 10) # Set callback function sync_listener.registerCallback(callback) rospy.spin() # Keep the main process looping if __name__ == '__main__': listener()
4.2.3. Operation effect
In the running effect, the topic with the same timestamp will trigger the callback function, and the image of the new timestamp will be ignored
5. ApproximateTimeSynchronizer
5.1. Approach time synchronizer
Obviously, the timestamps of different sensors can hardly be the same
Then it may be necessary to give a time error range
As like as two peas, the adaptive algorithm can match the messages based on the timestamp, and can customize the time of approaching, rather than the absolute time.
For example, for the topic "odom" 50Hz and "image" 1Hz, set the approach time to 1s through approximetime
Then you can subscribe to the message normally and synchronize the callback output
5.2. Examples
For a simple example, replace mileage and image messages with strings
5.2.1. odom release documents
#!/usr/bin/env python3 import rospy # python client for importing rospy package ROS from std_msgs.msg import String # Import STD_ String message type of msg.msg package # Define publishing function talker1 def talker(): pub = rospy.Publisher('odom', String, queue_size=1) # Define publisher pub publish odom rospy.init_node('odom_talker', anonymous=True) # Initialize node odom_talker rate = rospy.Rate(50) # Initialize the object rate with a cycle frequency of 50HZ # Without exiting the program while not rospy.is_shutdown(): hello_str = "odom %s" % rospy.get_time() rospy.loginfo(hello_str) # The message is printed to the screen pub.publish(hello_str) # Release news rate.sleep() # dormancy if __name__ == '__main__': try: talker() except rospy.ROSInterruptException: pass
5.2.2. image release file
#!/usr/bin/env python3 import rospy # python client for importing rospy package ROS from std_msgs.msg import String # Import STD_ String message type of msg.msg package # Define publishing function talker2 def talker(): pub = rospy.Publisher('image', String, queue_size=1) # Define publisher pub publish image rospy.init_node('image_talker', anonymous=True) # Initialize node image_talker rate = rospy.Rate(1) # Initialize the object rate with the cycle frequency of 1HZ # Without exiting the program while not rospy.is_shutdown(): hello_str = "image %s" % rospy.get_time() rospy.loginfo(hello_str) # The message is printed to the screen pub.publish(hello_str) # Release news rate.sleep() # dormancy if __name__ == '__main__': try: talker() except rospy.ROSInterruptException: pass
5.2.3. Topic subscription file
#!/usr/bin/env python3 import rospy # python client for importing rospy package ROS import message_filters # Import message_filters packet message filters from std_msgs.msg import String # Import STD_ String message type of msg.msg package # Callback function def callback(data_odom, data_image): rospy.loginfo(rospy.get_caller_id() + "I heard %s ,%s", data_odom.data, data_image.data) # The message is printed to the screen def listener(): rospy.init_node('listener', anonymous=True) # Initialize node listener # Create message filter subscriber sub_odom = message_filters.Subscriber("odom", String) sub_image = message_filters.Subscriber("image", String) # Set the proximity time synchronizer fs to wait for the message [sub_odom, sub_image], queue_size 10 and approach time 1s, allow_headerless allows non timestamp header.stamp comparison, using ROS time sync_listener = message_filters.ApproximateTimeSynchronizer([sub_odom, sub_image], 10, 1, allow_headerless=True) # Set callback function sync_listener.registerCallback(callback) rospy.spin() # Keep the main process looping if __name__ == '__main__': listener()
Because the mileage and image messages are replaced by strings, and there is no timestamp header.stamp, set allow_headerless=True
Generally, header.stamp is still used, and the default is allow_headerless=False
5.2.4. Operation effect
Barrel effect: the execution frequency of the subscriber is 1Hz. Wait until both odom and image are obtained, and a callback is triggered. At this time, the topic timestamps of odom and image are close
On the left is the odom publisher, in the middle is the image publisher, and on the right is the subscription
thank you