Skip to content

Commit d6b2c23

Browse files
ioryknorth55
authored andcommitted
[jsk_rosbag_tools] Fixed a bug when the specified fps is less than the fps of the topic in rosbag.
1 parent 13ad22b commit d6b2c23

File tree

2 files changed

+29
-2
lines changed

2 files changed

+29
-2
lines changed

jsk_rosbag_tools/python/jsk_rosbag_tools/bag_to_video.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -136,14 +136,14 @@ def bag_to_video(input_bagfile,
136136
if show_progress_bar:
137137
progress.update(1)
138138
aligned_stamp = stamp - start_stamp
139+
# write the current image until the next frame's timestamp.
139140
while current_time < aligned_stamp:
140141
current_time += dt
141142
writer.write_frame(cur_img)
143+
# set current image.
142144
cur_img = resize_keeping_aspect_ratio_wrt_target_size(
143145
cv2.cvtColor(bgr_img, cv2.COLOR_BGR2RGB),
144146
width=width, height=height)
145-
writer.write_frame(cur_img)
146-
current_time += dt
147147
writer.close()
148148

149149
if show_progress_bar:

jsk_rosbag_tools/tests/test_bag_to_video.py

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,8 @@
77
import rospkg
88
import rospy
99

10+
from jsk_rosbag_tools.video import get_video_duration
11+
1012

1113
PKG = 'jsk_rosbag_tools'
1214
NAME = 'test_bag_to_video'
@@ -29,6 +31,31 @@ def _check_command(self, cmd):
2931
rospy.logerr('command {} failed.'.format(cmd))
3032
raise RuntimeError('command {} failed.'.format(cmd))
3133

34+
def test_bag_to_video_fps(self):
35+
rospack = rospkg.RosPack()
36+
path = rospack.get_path('jsk_rosbag_tools')
37+
38+
topic = '/head_camera/rgb/throttled/image_rect_color/compressed'
39+
output_path = osp.join(path, 'tests', 'output', 'video', 'video.mp4')
40+
video_bag_path = osp.join(path, 'samples', 'data',
41+
'20220530173950_go_to_kitchen_rosbag.bag')
42+
43+
# case 1: fps is smaller than topic's Hz.
44+
fps = 1
45+
cmd = 'rosrun jsk_rosbag_tools bag_to_video.py {} -o {} ' \
46+
'--fps {} --image-topic {}'.format(
47+
video_bag_path, output_path, fps, topic)
48+
self._check_command(cmd)
49+
self.assertTrue(abs(get_video_duration(output_path) - 40.0) < 1.0)
50+
51+
# case 2: fps is larger than topic's Hz.
52+
fps = 60
53+
cmd = 'rosrun jsk_rosbag_tools bag_to_video.py {} -o {} ' \
54+
'--fps {} --image-topic {}'.format(
55+
video_bag_path, output_path, fps, topic)
56+
self._check_command(cmd)
57+
self.assertTrue(abs(get_video_duration(output_path) - 40.0) < 1.0)
58+
3259
def test_bag_to_video_and_video_to_bag_and_compress(self):
3360
rospack = rospkg.RosPack()
3461
path = rospack.get_path('jsk_rosbag_tools')

0 commit comments

Comments
 (0)