File tree Expand file tree Collapse file tree 4 files changed +212
-21
lines changed Expand file tree Collapse file tree 4 files changed +212
-21
lines changed Original file line number Diff line number Diff line change @@ -27,6 +27,7 @@ find_package(rclcpp REQUIRED)
27
27
find_package (rosbag2_cpp REQUIRED )
28
28
find_package (rosbag2_storage REQUIRED )
29
29
find_package (sensor_msgs REQUIRED )
30
+ find_package (OpenCV REQUIRED core imgproc )
30
31
31
32
if (${rosbag2_cpp_VERSION_MAJOR} GREATER 0 OR ${rosbag2_cpp_VERSION_MINOR} GREATER 9 )
32
33
add_definitions (-DUSE_NEW_ROSBAG_WRITE_INTERFACE )
@@ -68,6 +69,7 @@ target_link_libraries(bag_to_frames
68
69
rclcpp::rclcpp
69
70
rosbag2_cpp::rosbag2_cpp
70
71
rosbag2_storage::rosbag2_storage
72
+ opencv_core opencv_imgproc
71
73
${sensor_msgs_TARGETS} )
72
74
73
75
target_compile_features (bag_to_frames PRIVATE cxx_std_17 )
@@ -78,11 +80,13 @@ target_include_directories(bag_to_frames PRIVATE include)
78
80
#
79
81
add_executable (compress_bag src/compress_bag.cpp )
80
82
target_link_libraries (compress_bag
83
+ cv_bridge::cv_bridge
81
84
ffmpeg_encoder_decoder::ffmpeg_encoder_decoder
82
85
${ffmpeg_image_transport_msgs_TARGETS}
83
86
rclcpp::rclcpp
84
87
rosbag2_cpp::rosbag2_cpp
85
88
rosbag2_storage::rosbag2_storage
89
+ opencv_core opencv_imgproc
86
90
${sensor_msgs_TARGETS} )
87
91
target_compile_features (compress_bag PRIVATE cxx_std_17 )
88
92
target_include_directories (compress_bag PRIVATE include )
Original file line number Diff line number Diff line change @@ -70,6 +70,7 @@ Use ``compress_bag`` to encode a video stored as Image messages into FFMPEGPacke
70
70
ros2 run ffmpeg_image_transport_tools compress_bag -i input_bag -o output_bag -t /first_image_topic -t /next_image_topic [-O encoder=hevc_vaapi] [-s start_time] [-e end_time]
71
71
```
72
72
There are various other encoder options you can set. Run with the `` -h `` option to see them all.
73
+ You can also check for the quality of the encoding be immediately decoding the packet with the `` -q `` switch (quality check). With h264 typically you'll get an average absolute difference error of about 2.0 (on a scale of 0 to255).
73
74
74
75
## License
75
76
Original file line number Diff line number Diff line change 16
16
<test_depend >ament_cmake_clang_format</test_depend >
17
17
18
18
<depend >cv_bridge</depend >
19
- <depend >rclcpp</depend >
20
19
<depend >ffmpeg_encoder_decoder</depend >
21
20
<depend >ffmpeg_image_transport_msgs</depend >
21
+ <depend >libopencv-imgproc-dev</depend >
22
22
<depend >rosbag2_cpp</depend >
23
+ <depend >rclcpp</depend >
23
24
<depend >rosbag2_storage</depend >
24
25
<depend >sensor_msgs</depend >
25
26
You can’t perform that action at this time.
0 commit comments