Skip to content

Commit

Permalink
[jsk_rosbag_tools] Fixed a bug when the specified fps is less than th…
Browse files Browse the repository at this point in the history
…e fps of the topic in rosbag.
  • Loading branch information
iory authored and knorth55 committed Jul 5, 2022
1 parent 55578a4 commit 1efbfc6
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 2 deletions.
4 changes: 2 additions & 2 deletions jsk_rosbag_tools/python/jsk_rosbag_tools/bag_to_video.py
Original file line number Diff line number Diff line change
Expand Up @@ -136,14 +136,14 @@ def bag_to_video(input_bagfile,
if show_progress_bar:
progress.update(1)
aligned_stamp = stamp - start_stamp
# write the current image until the next frame's timestamp.
while current_time < aligned_stamp:
current_time += dt
writer.write_frame(cur_img)
# set current image.
cur_img = resize_keeping_aspect_ratio_wrt_target_size(
cv2.cvtColor(bgr_img, cv2.COLOR_BGR2RGB),
width=width, height=height)
writer.write_frame(cur_img)
current_time += dt
writer.close()

if show_progress_bar:
Expand Down
27 changes: 27 additions & 0 deletions jsk_rosbag_tools/tests/test_bag_to_video.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
import rospkg
import rospy

from jsk_rosbag_tools.video import get_video_duration


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

def test_bag_to_video_fps(self):
rospack = rospkg.RosPack()
path = rospack.get_path('jsk_rosbag_tools')

topic = '/head_camera/rgb/throttled/image_rect_color/compressed'
output_path = osp.join(path, 'tests', 'output', 'video', 'video.mp4')
video_bag_path = osp.join(path, 'samples', 'data',
'20220530173950_go_to_kitchen_rosbag.bag')

# case 1: fps is smaller than topic's Hz.
fps = 1
cmd = 'rosrun jsk_rosbag_tools bag_to_video.py {} -o {} ' \
'--fps {} --image-topic {}'.format(
video_bag_path, output_path, fps, topic)
self._check_command(cmd)
self.assertTrue(abs(get_video_duration(output_path) - 40.0) < 1.0)

# case 2: fps is larger than topic's Hz.
fps = 60
cmd = 'rosrun jsk_rosbag_tools bag_to_video.py {} -o {} ' \
'--fps {} --image-topic {}'.format(
video_bag_path, output_path, fps, topic)
self._check_command(cmd)
self.assertTrue(abs(get_video_duration(output_path) - 40.0) < 1.0)

def test_bag_to_video_and_video_to_bag_and_compress(self):
rospack = rospkg.RosPack()
path = rospack.get_path('jsk_rosbag_tools')
Expand Down

0 comments on commit 1efbfc6

Please sign in to comment.