Skip to content

Commit 8b3b574

Browse files
support falling back to alternative decoders, rename parameters, add tests etc
* adopt the new ffmpeg_encoder_api which allows for probing of decoders. The decoder parameter can now contain a list of comma-separated decoders which will be tried in order. * adds gtests to the repo * reformat to the black python formatter * add arguments to some example launch files * allow arbitrary AVOptions setting via av_option * remove parameters "preset", "tune", "delay", and "crf" (must now be set via "av_options") * remove some default values (like bit_rate) to force user to set them explicitly * change the parameter names: remove the leading ".", so now the parameters are named specify "camera.image_raw.." as opposed to ".camera.image_raw..." * adapt to new ffmpeg_encoder_decoder API * change name of parameter from encoding->encoder * provide encoding when initializing encoder (new encoder/decoder API) * handle new API for image transport 6.3.0 * deal with Humble bug: topic is passed in without being prefixed by the namespace, but then namespace is removed! * package splitting functions into utilities file
1 parent 4aaf47e commit 8b3b574

16 files changed

+888
-281
lines changed

CMakeLists.txt

Lines changed: 21 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -37,13 +37,22 @@ find_package(sensor_msgs REQUIRED)
3737
find_package(std_msgs REQUIRED)
3838

3939

40+
if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.0.0")
41+
add_definitions(-DIMAGE_TRANSPORT_RESOLVES_BASE_TOPIC)
42+
endif()
43+
if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.3.0")
44+
add_definitions(-DIMAGE_TRANSPORT_USE_QOS)
45+
endif()
46+
4047
set(LIBRARY_NAME ${PROJECT_NAME}_component)
4148

4249
add_library(
4350
${LIBRARY_NAME}
4451
SHARED
4552
src/ffmpeg_publisher.cpp
4653
src/ffmpeg_subscriber.cpp
54+
src/parameter_definition.cpp
55+
src/utils.cpp
4756
src/manifest.cpp)
4857

4958
target_include_directories(${LIBRARY_NAME} PUBLIC
@@ -94,10 +103,10 @@ pluginlib_export_plugin_description_file(image_transport ffmpeg_plugins.xml)
94103

95104
if(BUILD_TESTING)
96105
find_package(ament_cmake REQUIRED)
106+
find_package(ament_cmake_black REQUIRED)
97107
find_package(ament_cmake_copyright REQUIRED)
98108
find_package(ament_cmake_cppcheck REQUIRED)
99109
find_package(ament_cmake_cpplint REQUIRED)
100-
find_package(ament_cmake_flake8 REQUIRED)
101110
find_package(ament_cmake_lint_cmake REQUIRED)
102111
find_package(ament_cmake_clang_format REQUIRED)
103112
find_package(ament_cmake_xmllint REQUIRED)
@@ -109,13 +118,20 @@ if(BUILD_TESTING)
109118
ament_copyright()
110119
ament_cppcheck(LANGUAGE c++)
111120
ament_cpplint(FILTERS "-build/include,-runtime/indentation_namespace")
112-
ament_flake8()
113121
ament_lint_cmake()
114-
if(NOT $ENV{ROS_DISTRO} STREQUAL "galactic")
115-
ament_pep257()
116-
endif()
117122
ament_clang_format(CONFIG_FILE .clang-format)
123+
ament_black()
118124
ament_xmllint()
125+
126+
find_package(ament_cmake_gtest REQUIRED)
127+
ament_add_gtest(${PROJECT_NAME}_test test/test_1.cpp
128+
WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/test)
129+
target_include_directories(${PROJECT_NAME}_test PUBLIC
130+
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
131+
$<INSTALL_INTERFACE:include>)
132+
target_link_libraries(${PROJECT_NAME}_test
133+
${sensor_msgs_TARGETS} rclcpp::rclcpp image_transport::image_transport)
134+
119135
endif()
120136

121137
ament_package()

README.md

Lines changed: 63 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
# ROS2 image transport for ffmpeg/libav
22

33
This ROS2 image transport plugin supports encoding/decoding with the FFMpeg
4-
library, for example encoding h264 and h265 or HEVC, using
4+
library, for example encoding h264 and h265/hevc, using
55
Nvidia or other hardware acceleration when available.
66

77
The publisher plugin of the transport produces
@@ -20,6 +20,7 @@ Continuous integration is tested under Ubuntu with the following ROS2 distros:
2020

2121
[![Build Status](https://build.ros2.org/buildStatus/icon?job=Hdev__ffmpeg_image_transport__ubuntu_jammy_amd64&subject=Humble)](https://build.ros2.org/job/Hdev__ffmpeg_image_transport__ubuntu_jammy_amd64/)
2222
[![Build Status](https://build.ros2.org/buildStatus/icon?job=Jdev__ffmpeg_image_transport__ubuntu_noble_amd64&subject=Jazzy)](https://build.ros2.org/job/Jdev__ffmpeg_image_transport__ubuntu_noble_amd64/)
23+
[![Build Status](https://build.ros2.org/buildStatus/icon?job=Kdev__ffmpeg_image_transport__ubuntu_noble_amd64&subject=Kilted)](https://build.ros2.org/job/Kdev__ffmpeg_image_transport__ubuntu_noble_amd64/)
2324
[![Build Status](https://build.ros2.org/buildStatus/icon?job=Rdev__ffmpeg_image_transport__ubuntu_noble_amd64&subject=Rolling)](https://build.ros2.org/job/Rdev__ffmpeg_image_transport__ubuntu_noble_amd64/)
2425

2526

@@ -59,83 +60,91 @@ should give output (among other transport plugins):
5960
This plugin decodes frames from ffmpeg compressed packets
6061
```
6162

62-
Remember to install the plugin on both hosts, the one that is encoding and
63-
the one that is decoding (viewing).
63+
Remember to install the plugin on both hosts, the one that is publishing and
64+
the one that is subscribing (viewing).
6465

6566
## Parameters
6667

68+
Below is a short description of the ROS parameters exposed by the Publisher and Subscriber plugins.
69+
The parameters refer to encoder and decoder variables described in more detail in the [``ffmpeg_encoder_decoder`` repository](https://github.com/ros-misc-utilities/ffmpeg_encoder_decoder).
70+
6771
### Publisher (camera driver)
6872

6973
Here is a list of the available encoding parameters:
7074

71-
- ``encoding``: the libav (ffmpeg) encoder being used. The default is ``libx264``, which is on-CPU unaccelerated encoding.
75+
- ``encoder``: the libav (ffmpeg) encoder being used. The default is ``libx264``, which is on-CPU unaccelerated encoding.
7276
Depending on your hardware, your encoding options may include the hardware accelerated ``h264_nvenc`` or ``h264_vaapi``.
7377
You can list all available encoders with ``ffmpeg --codecs``. In the h264 row, look for ``(encoders)``.
74-
- ``preset``: default is empty (""). Valid values can be for instance ``slow``, ``ll`` (low latency) etc.
75-
To find out what presets are available, run e.g.
76-
``ffmpeg -hide_banner -f lavfi -i nullsrc -c:v libx264 -preset help -f mp4 - 2>&1``
77-
- ``profile``: For instance ``baseline``, ``main``. See [the ffmpeg website](https://trac.ffmpeg.org/wiki/Encode/H.264).
78-
- ``tune``: See [the ffmpeg website](https://trac.ffmpeg.org/wiki/Encode/H.264). The default is empty("").
78+
- ``encoder_av_options``: default is empty (""). Comma-separeted list of valid
79+
libav options in the form of (key:value), e.g.:``'preset:ll,profile:main,crf:0'``.
80+
See the ffmpeg documentation for [more](https://trac.ffmpeg.org/wiki/Encode/H.264).
7981
- ``gop_size``: The number of frames between keyframes. Default: 10.
8082
The larger this number the more latency you will have, but also the more efficient the compression becomes.
8183
- ``bit_rate``: The max bit rate [in bits/s] that the encoding will target. Default is ``8242880``.
82-
- ``crf``: Constant Rate Factor, affects the image quality. Value range is ``[0, 51]``; ``0`` is lossless, ``23`` is default, ``51`` is worst quality.
83-
- ``delay``: Not sure what it does, but doesn't help with delay. Default is empty ("").
84-
- ``pixel_format``: Forces a different pixel format for internal conversions. Experimental, don't use.
85-
- ``qmax``: Max quantization rate. Defaults to 10. See [ffmpeg documentation](https://www.ffmpeg.org/ffmpeg-codecs.html).
86-
The larger this number, the worse the image looks, and the more efficient the encoding.
87-
- ``measure_performance``: For performance debugging (developers only). Defaults to false.
88-
- ``performance_interval``: How many frames to wait between logging performance data.
84+
- ``pixel_format``: Forces a different pixel for encoding.
85+
This pixel format corresponds to the ``av_source_pixel_format`` in the
86+
[ffmpeg\_encoder\_decoder documentation](https://github.com/ros-misc-utilities/ffmpeg_encoder_decoder).
87+
- ``qmax``: Max quantization rate. Defaults to 10.
88+
See [ffmpeg documentation](https://www.ffmpeg.org/ffmpeg-codecs.html).
89+
The larger this number, the worse the image looks, and the more efficient the encoding.
90+
- ``encoder_measure_performance``: For performance debugging (developers only). Defaults to false.
8991

9092
The parameters are under the ``ffmpeg`` variable block. If you launch
9193
your publisher node (camera driver), you can give it a parameter list on the way like so:
9294
```
93-
parameters=[{'ffmpeg_image_transport.encoding': 'hevc_nvenc',
94-
'ffmpeg_image_transport.profile': 'main',
95-
'ffmpeg_image_transport.preset': 'll',
96-
'ffmpeg_image_transport.gop_size': 15}]
95+
parameters=[{'image_raw.ffmpeg.encoder': 'hevc_nvenc',
96+
'image_raw.ffmpeg.encoder_av_options': 'preset:ll,profile:main,crf:0'}]
9797
```
98-
See the example launch file for a V4L USB camera
98+
See the example launch file for a V4L USB camera (``usb_camera.launch.py``).
99+
If the above parameter settings don't work, use the ``ros2 param dump <your_node_name>``
100+
command to find out what the proper parameter path is.
99101

100102
### Subscriber (viewer)
101103

102-
The subscriber has only one parameter (``map``), which is the map between the encoding that
103-
was used to encode the frames, and the libav decoder to be used for decoding. The mapping is done by creating entries in the ``ffmpeg.map`` parameter, which is prefixed by the image base name, e.g. ``camera``.
104-
105-
For example to tell the subscriber to use the ``hevc`` decoder instead of the default ``hevc_cuvid``
106-
decoder for decoding incoming ``hevc_nvenc`` packets set a parameter like so *after* you started the viewer:
107-
```
108-
ros2 param set <name_of_your_viewer_node> camera.image_raw.ffmpeg.map.hevc_nvenc hevc
109-
```
110-
This is assuming that your viewer node is subscribing to an image ``/camera/image_raw/ffmpeg``.
111-
112-
You also need to refresh the subscription (drop down menu in the viewer) for the parameter to take hold.
113-
If anyone ever figures out how to set the parameters *when* starting the viewer (rather than afterwards!), please update this document.
114-
104+
- ``decoder_av_options`` comma-separated list of libav options to pass
105+
to the decoder, like ``foo:bar,foobar:baz``. Default: empty string.
106+
- ``decoder_measure_performance`` enables performance
107+
measurements. Default: false.
108+
- ``decoders.<codec>.<av_source_pixel_format>.<cv_bridge_target_format>.<original_ros_encoding>`` specifies the decoders to use for a given FFMPEGPacket encoding.
109+
If no decoders are specified for the full encoding, a less specific parameter will be tested, i.e. ``decoders.<codec>.<av_source_pixel_format>.<cv_bridge_target_format>``, then ``decoders.<codec>.<av_source_pixel_format>``, and finally ``decoders.<codec>``.
110+
If all parameters are found to be empty, the Subscriber plugin will try to decode with a default set of libav decoders that support the appropriate codec.
111+
112+
All parameters are prefixed again by the image topic and the transport, just like for the publisher node.
113+
The easiest way to find the exact naming of the parameter is to run the node and to use ``ros2 param list`` to find the ``ffmpeg.decoders`` parameter.
114+
Please also refer to the republisher launch script example.
115+
116+
Typically ROS2 parameters are passed to a node by *initializing* the parameters before launching the node, and the node then reads the parameter when it *declares* the parameter.
117+
Unfortunately, this route is not available for the popular ``rqt`` based suite of image viewing tools such as ``rqt_image_view``, since ``rqt`` does not read command line arguments and therefore no parameters can be initialized. The only workaround there is to:
118+
1) start e.g. ``rqt_image_view``
119+
2) select the ffmpeg image transport in the drop down box. This will *declare* the ``decoders`` parameter so you can set it in the next step.
120+
3) find the node name with ``ros2 node list`` and set the parameter using something like
121+
``ros2 param set <name_of_your_viewer_node> camera.image_raw.ffmpeg.decoders.hevc hevc_cuvid``. This assumes your viewer node is subscribing to the topic ``/camera/image_raw/ffmpeg``.
122+
4) again using the drop down box, switch to another image transport and back to ffmpeg. This will cause the ffmpeg transport plugin to apply the updated ``decoders`` parameter.
115123

116124
### Republishing
117125

118126
The ``image_transport`` allows you to republish the decoded image locally,
119127
see for instance [here](https://gitlab.com/boldhearts/ros2_v4l2_camera/-/blob/foxy/README.md).
120-
Here the ROS parameters work as expected to modify the mapping between
121-
encoding and decoder.
128+
Here the ROS parameters work as expected to modify the mapping between encoding and decoder.
122129

123130
The following lines shows how to specify the decoder when republishing.
124-
For example to decode incoming ``hevc_nvenc`` packets with the ``hevc`` decoder:
131+
For example to first try to decode incoming ``hevc`` packets with the ``hevc_cuvid`` decoder, and if that fails, with the software ``hevc``decoder:
125132

126133
- ROS 2 Humble:
127134
```
128-
ros2 run image_transport republish ffmpeg in/ffmpeg:=image_raw/ffmpeg raw out:=image_raw/uncompressed --ros-args -p "ffmpeg_image_transport.map.hevc_nvenc:=hevc"
135+
ros2 run image_transport republish ffmpeg in/ffmpeg:=image_raw/ffmpeg raw out:=image_raw/uncompressed --ros-args -p "ffmpeg_image_transport.decoders.hevc:=hevc_cuvid,hevc"
129136
```
130137
- ROS 2 Jazzy:
131138
```
132-
ros2 run image_transport republish --ros-args -p in_transport:=ffmpeg -p out_transport:=raw --remap in/ffmpeg:=image_raw/ffmpeg --remap out:=image_raw/uncompressed -p "ffmpeg_image_transport.map.hevc_nvenc:=hevc"
139+
ros2 run image_transport republish --ros-args -p in_transport:=ffmpeg -p out_transport:=raw --remap in/ffmpeg:=image_raw/ffmpeg --remap out:=image_raw/uncompressed -p "ffmpeg_image_transport.decoders.hevc:=hevc_cuvid,hevc"
133140
```
134141

135142
Note: The commands below use the Humble syntax and need to be changed as shown here for Jazzy.
136143

137144
Republishing is generally not necessary so long as publisher and subscriber both properly use
138-
an image transport. Some nodes however, notably the rosbag player, do not support a proper transport, rendering republishing necessary.
145+
an image transport.
146+
Some nodes however, notably the rosbag player, do not support a proper transport, making republishing necessary.
147+
Please use the republishing launch file (``republish.launch.py``) in this repo as a starting point for how to set the decoders parameter.
139148

140149
#### Republishing raw images from rosbags in ffmpeg format
141150

@@ -153,15 +162,14 @@ You can record them in ``ffmpeg`` format by e.g ``ros2 bag record /out/ffmpeg``.
153162

154163
Let's say you have stored images as ffmpeg packets in a rosbag under the topic ``/camera/image_raw/ffmpeg``. To view them use this line:
155164
```
156-
ros2 run image_transport republish ffmpeg --ros-args -r in/ffmpeg:=/camera/image_raw/ffmpeg
157-
165+
ros2 run image_transport republish ffmpeg --ros-args -p in_transport:=ffmpeg -r in/ffmpeg:=/camera/image_raw/ffmpeg
158166
```
159167
This will republish the topic with full image transport support.
160168

161169
### Setting encoding parameters when launching camera driver
162170

163-
The ``launch`` directory contains an example launch file ``cam.launch.py`` that demonstrates
164-
how to set encoding profile and preset for e.g. a usb camera.
171+
The ``launch`` directory contains an example launch file ``usb_camera.launch.py`` that demonstrates
172+
how to set encoding profile and preset for a usb camera.
165173

166174

167175
### How to use a custom version of libav (aka ffmpeg)
@@ -170,6 +178,17 @@ See the [``ffmpeg_encoder_decoder`` repository](https://github.com/ros-misc-util
170178
There you will also find instructions for hardware accelerated
171179
streaming on the NVidia Jetson.
172180

181+
## Trouble shooting
182+
### Excessive lag
183+
Many encoders buffer frames to enable inter-frame prediction for improved compression.
184+
This can lead to very large lag. Use a small ``gop_size`` parameter to increase the frequency of keyframes.
185+
### Poor quality
186+
Set the ``bit_rate`` parameter or set the ``crf`` ``av_option`` parameter to something small like ``crf:1``. Experiment with the ffmpeg CLI tool until you get a satisfying quality.
187+
### Decoder cannot decode image
188+
Check that the ``av_source_pixel_format`` used by the encoder is actually supported by the decoder.
189+
Many decoders can only decode a small number of image formats.
190+
191+
173192
## License
174193

175194
This software is issued under the Apache License Version 2.0.

doc/conf.py

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -16,29 +16,29 @@
1616
import os
1717
import sys
1818

19-
sys.path.insert(0, os.path.abspath('.'))
19+
sys.path.insert(0, os.path.abspath("."))
2020

21-
project = 'ffmpeg_image_transport'
21+
project = "ffmpeg_image_transport"
2222
# copyright = '2024, Bernd Pfrommer'
23-
author = 'Bernd Pfrommer'
23+
author = "Bernd Pfrommer"
2424

2525

2626
# Add any Sphinx extension module names here, as strings.
2727
extensions = [
28-
'myst_parser',
29-
'sphinx.ext.autodoc',
30-
'sphinx.ext.doctest',
31-
'sphinx_rtd_theme',
32-
'sphinx.ext.coverage',
33-
'sphinx.ext.intersphinx',
34-
'sphinx.ext.autosummary',
35-
'sphinx.ext.napoleon',
28+
"myst_parser",
29+
"sphinx.ext.autodoc",
30+
"sphinx.ext.doctest",
31+
"sphinx_rtd_theme",
32+
"sphinx.ext.coverage",
33+
"sphinx.ext.intersphinx",
34+
"sphinx.ext.autosummary",
35+
"sphinx.ext.napoleon",
3636
]
3737

3838
# Add any paths that contain templates here, relative to this directory.
39-
templates_path = ['_templates']
39+
templates_path = ["_templates"]
4040

41-
source_suffix = '.rst'
41+
source_suffix = ".rst"
4242
# exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store']
4343
exclude_patterns = []
4444

@@ -51,19 +51,19 @@
5151
# a list of builtin themes.
5252
#
5353
# html_theme = 'alabaster'
54-
html_theme = 'sphinx_rtd_theme'
55-
htmlhelp_basename = 'ffmpeg_image_transport_doc'
54+
html_theme = "sphinx_rtd_theme"
55+
htmlhelp_basename = "ffmpeg_image_transport_doc"
5656

5757
# Add any paths that contain custom static files (such as style sheets) here,
5858
# relative to this directory. They are copied after the builtin static files,
5959
# so a file named "default.css" will overwrite the builtin "default.css".
60-
html_static_path = ['_static']
60+
html_static_path = ["_static"]
6161

6262
# -- Extension configuration -------------------------------------------------
6363

64-
autoclass_content = 'both'
64+
autoclass_content = "both"
6565

6666
autodoc_default_options = {
67-
'members': True, # document members
68-
'undoc-members': True, # also document members without documentation
67+
"members": True, # document members
68+
"undoc-members": True, # also document members without documentation
6969
}

include/ffmpeg_image_transport/ffmpeg_publisher.hpp

Lines changed: 13 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#define FFMPEG_IMAGE_TRANSPORT__FFMPEG_PUBLISHER_HPP_
1818

1919
#include <ffmpeg_encoder_decoder/encoder.hpp>
20+
#include <ffmpeg_image_transport/parameter_definition.hpp>
2021
#include <ffmpeg_image_transport_msgs/msg/ffmpeg_packet.hpp>
2122
#include <image_transport/simple_publisher_plugin.hpp>
2223
#include <memory>
@@ -31,50 +32,46 @@ using FFMPEGPacketConstPtr = FFMPEGPacket::ConstSharedPtr;
3132
class FFMPEGPublisher : public FFMPEGPublisherPlugin
3233
{
3334
public:
34-
using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
35-
using ParameterValue = rclcpp::ParameterValue;
36-
3735
#if defined(IMAGE_TRANSPORT_API_V1) || defined(IMAGE_TRANSPORT_API_V2)
3836
using PublisherTFn = PublishFn;
3937
#else
4038
using PublisherTFn = PublisherT;
4139
#endif
42-
43-
struct ParameterDefinition
44-
{
45-
ParameterValue defaultValue;
46-
ParameterDescriptor descriptor;
47-
};
48-
40+
#ifdef IMAGE_TRANSPORT_USE_QOS
41+
using QoSType = rclcpp::QoS;
42+
#else
43+
using QoSType = rmw_qos_profile_t;
44+
#endif
4945
FFMPEGPublisher();
5046
~FFMPEGPublisher() override;
5147
std::string getTransportName() const override { return "ffmpeg"; }
5248

5349
protected:
5450
#if defined(IMAGE_TRANSPORT_API_V1) || defined(IMAGE_TRANSPORT_API_V2)
5551
void advertiseImpl(
56-
rclcpp::Node * node, const std::string & base_topic, rmw_qos_profile_t custom_qos) override;
52+
rclcpp::Node * node, const std::string & base_topic, QoSType custom_qos) override;
5753
#else
5854
void advertiseImpl(
59-
rclcpp::Node * node, const std::string & base_topic, rmw_qos_profile_t custom_qos,
55+
rclcpp::Node * node, const std::string & base_topic, QoSType custom_qos,
6056
rclcpp::PublisherOptions opt) override;
6157
#endif
6258
void publish(const Image & message, const PublisherTFn & publisher) const override;
59+
void shutdown() override;
6360

6461
private:
6562
void packetReady(
6663
const std::string & frame_id, const rclcpp::Time & stamp, const std::string & codec,
6764
uint32_t width, uint32_t height, uint64_t pts, uint8_t flags, uint8_t * data, size_t sz);
6865

69-
rmw_qos_profile_t initialize(
70-
rclcpp::Node * node, const std::string & base_name, rmw_qos_profile_t custom_qos);
71-
void declareParameter(
72-
rclcpp::Node * node, const std::string & base_name, const ParameterDefinition & definition);
66+
QoSType initialize(rclcpp::Node * node, const std::string & base_name, QoSType custom_qos);
67+
void declareParameter(rclcpp::Node * node, const ParameterDefinition & definition);
68+
void handleAVOptions(const std::string & opt);
7369
// variables ---------
7470
rclcpp::Logger logger_;
7571
const PublisherTFn * publishFunction_{NULL};
7672
ffmpeg_encoder_decoder::Encoder encoder_;
7773
uint32_t frameCounter_{0};
74+
std::string paramNamespace_;
7875
// ---------- configurable parameters
7976
int performanceInterval_{175}; // num frames between perf printouts
8077
bool measurePerformance_{false};

0 commit comments

Comments
 (0)