Skip to content

Commit e89e936

Browse files
committed
added quality test/decoding
1 parent 410c246 commit e89e936

File tree

4 files changed

+212
-21
lines changed

4 files changed

+212
-21
lines changed

CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ find_package(rclcpp REQUIRED)
2727
find_package(rosbag2_cpp REQUIRED)
2828
find_package(rosbag2_storage REQUIRED)
2929
find_package(sensor_msgs REQUIRED)
30+
find_package(OpenCV REQUIRED core imgproc)
3031

3132
if(${rosbag2_cpp_VERSION_MAJOR} GREATER 0 OR ${rosbag2_cpp_VERSION_MINOR} GREATER 9)
3233
add_definitions(-DUSE_NEW_ROSBAG_WRITE_INTERFACE)
@@ -68,6 +69,7 @@ target_link_libraries(bag_to_frames
6869
rclcpp::rclcpp
6970
rosbag2_cpp::rosbag2_cpp
7071
rosbag2_storage::rosbag2_storage
72+
opencv_core opencv_imgproc
7173
${sensor_msgs_TARGETS})
7274

7375
target_compile_features(bag_to_frames PRIVATE cxx_std_17)
@@ -78,11 +80,13 @@ target_include_directories(bag_to_frames PRIVATE include)
7880
#
7981
add_executable(compress_bag src/compress_bag.cpp)
8082
target_link_libraries(compress_bag
83+
cv_bridge::cv_bridge
8184
ffmpeg_encoder_decoder::ffmpeg_encoder_decoder
8285
${ffmpeg_image_transport_msgs_TARGETS}
8386
rclcpp::rclcpp
8487
rosbag2_cpp::rosbag2_cpp
8588
rosbag2_storage::rosbag2_storage
89+
opencv_core opencv_imgproc
8690
${sensor_msgs_TARGETS})
8791
target_compile_features(compress_bag PRIVATE cxx_std_17)
8892
target_include_directories(compress_bag PRIVATE include)

README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,7 @@ Use ``compress_bag`` to encode a video stored as Image messages into FFMPEGPacke
7070
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]
7171
```
7272
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).
7374

7475
## License
7576

package.xml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,10 +16,11 @@
1616
<test_depend>ament_cmake_clang_format</test_depend>
1717

1818
<depend>cv_bridge</depend>
19-
<depend>rclcpp</depend>
2019
<depend>ffmpeg_encoder_decoder</depend>
2120
<depend>ffmpeg_image_transport_msgs</depend>
21+
<depend>libopencv-imgproc-dev</depend>
2222
<depend>rosbag2_cpp</depend>
23+
<depend>rclcpp</depend>
2324
<depend>rosbag2_storage</depend>
2425
<depend>sensor_msgs</depend>
2526

0 commit comments

Comments
 (0)