How to create topics and synchronize them when recording a bagfile.
Hello everyone,
thanks for taking the time to check my post. So let me describe what I want to do.
- For starters I have a bag file containing a topic which carries a directory path at each message, the important part of the topic are the timestamps.
- The path leads to a video file.
- I take the frames of the video and create an image topic. Note there are 4 videos so the output is 4 Image topics.
The question is how to get them synchronized. I tried creating 4 topics with the same timestamp at each topic but when I recorded them they seem not to be in sync. Here is my code:
#!/usr/bin/env python
import rosbag
import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import message_filters
# Declare the bag file which recorded the data paths.
bag = rosbag.Bag("econ_vid_paths.bag")
'''
Initialize the node with the name "Image_publisher" and the publishers that will
contain the image messages
'''
rospy.init_node('Image_publisher')
cam_0_publisher = rospy.Publisher('/econ/image_raw/cam_0', Image, queue_size = 100)
cam_1_publisher = rospy.Publisher('/econ/image_raw/cam_1', Image, queue_size = 100)
cam_2_publisher = rospy.Publisher('/econ/image_raw/cam_2', Image, queue_size = 100)
cam_3_publisher = rospy.Publisher('/econ/image_raw/cam_3', Image, queue_size = 100)
# Create an object that converts between OpenCV images and ROS image messages.
bridge = CvBridge()
# Open video files.
cap0 = cv2.VideoCapture('/mnt/28007d94-f5ac-4179-b807-b9ec1cf293c7/econVideo_2021-06-11-17-13-51_0.mkv')
cap1 = cv2.VideoCapture('/mnt/28007d94-f5ac-4179-b807-b9ec1cf293c7/econVideo_2021-06-11-17-13-51_1.mkv')
cap2 = cv2.VideoCapture('/mnt/28007d94-f5ac-4179-b807-b9ec1cf293c7/econVideo_2021-06-11-17-13-51_2.mkv')
cap3 = cv2.VideoCapture('/mnt/28007d94-f5ac-4179-b807-b9ec1cf293c7/econVideo_2021-06-11-17-13-51_3.mkv')
# Create frame_number variable, this will work as a counter for the frames.
frame_number = 0;
for topic, msg, t in bag.read_messages(topics=['/sync_vid_publisher/econ_vid']):
# Take retrieve value (retX) and frames, if retX is 0 then there is no valid frame.
ret0, frame0 = cap0.read()
ret1, frame1 = cap1.read()
ret2, frame2 = cap2.read()
ret3, frame3 = cap3.read()
if ret0+ret1+ret2+ret3==4: # Check if every camera has a valid frame.
timestamp_secs = msg.header.stamp.secs
timestamp_nsecs = msg.header.stamp.nsecs
video_message_0 = bridge.cv2_to_imgmsg(frame0, encoding="bgr8")
video_message_0.header.stamp.secs = timestamp_secs
video_message_0.header.stamp.nsecs = timestamp_nsecs
cam_0_publisher.publish(video_message_0)
video_message_1 = bridge.cv2_to_imgmsg(frame1, encoding="bgr8")
video_message_1.header.stamp.secs = timestamp_secs
video_message_1.header.stamp.nsecs = timestamp_nsecs
cam_1_publisher.publish(video_message_1)
video_message_2 = bridge.cv2_to_imgmsg(frame2, encoding="bgr8")
video_message_2.header.stamp.secs = timestamp_secs
video_message_2.header.stamp.nsecs = timestamp_nsecs
cam_2_publisher.publish(video_message_2)
video_message_3 = bridge.cv2_to_imgmsg(frame2, encoding="bgr8")
video_message_3.header.stamp.secs = timestamp_secs
video_message_3.header.stamp.nsecs = timestamp_nsecs
cam_3_publisher.publish(video_message_3)
print('Frame :', frame_number, 'published.')
frame_number+=1
By doing this I thought that the topics are going to be synchronized as they have the same timestamp but when I recorded the messages and looked at the contents in rqt I noticed that they are not synchronized. Although, when I echo each timestamp from the topics (rostopic echo /econ/image_raw/cam_1/header/stamp
) they are exactly the same. So why are they not recorded in sync ? I record them using the following: rosbag record -b 0 /econ/image_raw/cam_0 /econ/image_raw/cam_1 /econ/image_raw/cam_2 /econ/image_raw ...
I edited the title to make it less vague.