Skip to content
Merged
Show file tree
Hide file tree
Changes from 15 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 17 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,13 +37,18 @@ find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)


if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.3.0")
add_definitions(-DIMAGE_TRANSPORT_USE_QOS)
endif()

set(LIBRARY_NAME ${PROJECT_NAME}_component)

add_library(
${LIBRARY_NAME}
SHARED
src/ffmpeg_publisher.cpp
src/ffmpeg_subscriber.cpp
src/parameter_definition.cpp
src/manifest.cpp)

target_include_directories(${LIBRARY_NAME} PUBLIC
Expand Down Expand Up @@ -94,10 +99,10 @@ pluginlib_export_plugin_description_file(image_transport ffmpeg_plugins.xml)

if(BUILD_TESTING)
find_package(ament_cmake REQUIRED)
find_package(ament_cmake_black REQUIRED)
find_package(ament_cmake_copyright REQUIRED)
find_package(ament_cmake_cppcheck REQUIRED)
find_package(ament_cmake_cpplint REQUIRED)
find_package(ament_cmake_flake8 REQUIRED)
find_package(ament_cmake_lint_cmake REQUIRED)
find_package(ament_cmake_clang_format REQUIRED)
find_package(ament_cmake_xmllint REQUIRED)
Expand All @@ -109,13 +114,20 @@ if(BUILD_TESTING)
ament_copyright()
ament_cppcheck(LANGUAGE c++)
ament_cpplint(FILTERS "-build/include,-runtime/indentation_namespace")
ament_flake8()
ament_lint_cmake()
if(NOT $ENV{ROS_DISTRO} STREQUAL "galactic")
ament_pep257()
endif()
ament_clang_format(CONFIG_FILE .clang-format)
ament_black()
ament_xmllint()

find_package(ament_cmake_gtest REQUIRED)
ament_add_gtest(${PROJECT_NAME}_test test/test_1.cpp
WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/test)
target_include_directories(${PROJECT_NAME}_test PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
target_link_libraries(${PROJECT_NAME}_test
${sensor_msgs_TARGETS} rclcpp::rclcpp image_transport::image_transport)

endif()

ament_package()
Expand Down
98 changes: 56 additions & 42 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# ROS2 image transport for ffmpeg/libav

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

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

[![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/)
[![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/)
[![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/)
[![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/)


Expand Down Expand Up @@ -59,83 +60,86 @@ should give output (among other transport plugins):
This plugin decodes frames from ffmpeg compressed packets
```

Remember to install the plugin on both hosts, the one that is encoding and
the one that is decoding (viewing).
Remember to install the plugin on both hosts, the one that is publishing and
the one that is subscribing (viewing).

## Parameters

Below is a short description of the ROS parameters exposed by the Publisher and Subscriber plugins.
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).

### Publisher (camera driver)

Here is a list of the available encoding parameters:

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

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

### Subscriber (viewer)

The subscriber has only one parameter (``map``), which is the map between the encoding that
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``.

For example to tell the subscriber to use the ``hevc`` decoder instead of the default ``hevc_cuvid``
decoder for decoding incoming ``hevc_nvenc`` packets set a parameter like so *after* you started the viewer:
```
ros2 param set <name_of_your_viewer_node> camera.image_raw.ffmpeg.map.hevc_nvenc hevc
```
This is assuming that your viewer node is subscribing to an image ``/camera/image_raw/ffmpeg``.

You also need to refresh the subscription (drop down menu in the viewer) for the parameter to take hold.
If anyone ever figures out how to set the parameters *when* starting the viewer (rather than afterwards!), please update this document.
The subscriber has only one parameter (``map.<some_encoding>``), which is the map between a codec and a comma-separated list of libav decoders that can be used for decoding.
If you don't set the map parameter, the Subscriber plugin will try to decode with a default set of libav decoders that support the appropriate codec.
The map is exposed as the ROS``ffmpeg.map`` parameter, which is prefixed by the image base name, e.g. ``camera.image_raw``.
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.map`` parameter.
Please also refer to the republisher launch script example.

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.
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:
1) start e.g. ``rqt_image_view``
2) select the ffmpeg image transport in the drop down box. This will *declare* the ``map`` parameter so you can set it in the next step.
3) find the node name with ``ros2 node list`` and set the parameter using something like
``ros2 param set <name_of_your_viewer_node> camera.image_raw.ffmpeg.map.hevc hevc_cuvid``. This assumes your viewer node is subscribing to the topic ``/camera/image_raw/ffmpeg``.
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 ``map`` parameter.

### Republishing

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

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

- ROS 2 Humble:
```
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"
ros2 run image_transport republish ffmpeg in/ffmpeg:=image_raw/ffmpeg raw out:=image_raw/uncompressed --ros-args -p "ffmpeg_image_transport.map.hevc:=hevc_cuvid,hevc"
```
- ROS 2 Jazzy:
```
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"
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:=hevc_cuvid,hevc"
```

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

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

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

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

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:
```
ros2 run image_transport republish ffmpeg --ros-args -r in/ffmpeg:=/camera/image_raw/ffmpeg

ros2 run image_transport republish ffmpeg --ros-args -p in_transport:=ffmpeg -r in/ffmpeg:=/camera/image_raw/ffmpeg
```
This will republish the topic with full image transport support.

### Setting encoding parameters when launching camera driver

The ``launch`` directory contains an example launch file ``cam.launch.py`` that demonstrates
how to set encoding profile and preset for e.g. a usb camera.
The ``launch`` directory contains an example launch file ``usb_cambera.launch.py`` that demonstrates
how to set encoding profile and preset for a usb camera.


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

## Trouble shooting
### Excessive lag
Many encoders buffer frames to enable inter-frame prediction for improved compression.
This can lead to very large lag. Use a small ``gop_size`` parameter to increase the frequency of keyframes.
### Poor quality
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.
### Decoder cannot decode image
Check that the ``av_source_pixel_format`` used by the encoder is actually supported by the decoder.
Many decoders can only decode a small number of image formats.


## License

This software is issued under the Apache License Version 2.0.
38 changes: 19 additions & 19 deletions doc/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,29 +16,29 @@
import os
import sys

sys.path.insert(0, os.path.abspath('.'))
sys.path.insert(0, os.path.abspath("."))

project = 'ffmpeg_image_transport'
project = "ffmpeg_image_transport"
# copyright = '2024, Bernd Pfrommer'
author = 'Bernd Pfrommer'
author = "Bernd Pfrommer"


# Add any Sphinx extension module names here, as strings.
extensions = [
'myst_parser',
'sphinx.ext.autodoc',
'sphinx.ext.doctest',
'sphinx_rtd_theme',
'sphinx.ext.coverage',
'sphinx.ext.intersphinx',
'sphinx.ext.autosummary',
'sphinx.ext.napoleon',
"myst_parser",
"sphinx.ext.autodoc",
"sphinx.ext.doctest",
"sphinx_rtd_theme",
"sphinx.ext.coverage",
"sphinx.ext.intersphinx",
"sphinx.ext.autosummary",
"sphinx.ext.napoleon",
]

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

source_suffix = '.rst'
source_suffix = ".rst"
# exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store']
exclude_patterns = []

Expand All @@ -51,19 +51,19 @@
# a list of builtin themes.
#
# html_theme = 'alabaster'
html_theme = 'sphinx_rtd_theme'
htmlhelp_basename = 'ffmpeg_image_transport_doc'
html_theme = "sphinx_rtd_theme"
htmlhelp_basename = "ffmpeg_image_transport_doc"

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

# -- Extension configuration -------------------------------------------------

autoclass_content = 'both'
autoclass_content = "both"

autodoc_default_options = {
'members': True, # document members
'undoc-members': True, # also document members without documentation
"members": True, # document members
"undoc-members": True, # also document members without documentation
}
13 changes: 3 additions & 10 deletions include/ffmpeg_image_transport/ffmpeg_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#define FFMPEG_IMAGE_TRANSPORT__FFMPEG_PUBLISHER_HPP_

#include <ffmpeg_encoder_decoder/encoder.hpp>
#include <ffmpeg_image_transport/parameter_definition.hpp>
#include <ffmpeg_image_transport_msgs/msg/ffmpeg_packet.hpp>
#include <image_transport/simple_publisher_plugin.hpp>
#include <memory>
Expand All @@ -31,21 +32,12 @@ using FFMPEGPacketConstPtr = FFMPEGPacket::ConstSharedPtr;
class FFMPEGPublisher : public FFMPEGPublisherPlugin
{
public:
using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
using ParameterValue = rclcpp::ParameterValue;

#if defined(IMAGE_TRANSPORT_API_V1) || defined(IMAGE_TRANSPORT_API_V2)
using PublisherTFn = PublishFn;
#else
using PublisherTFn = PublisherT;
#endif

struct ParameterDefinition
{
ParameterValue defaultValue;
ParameterDescriptor descriptor;
};

FFMPEGPublisher();
~FFMPEGPublisher() override;
std::string getTransportName() const override { return "ffmpeg"; }
Expand All @@ -60,16 +52,17 @@ class FFMPEGPublisher : public FFMPEGPublisherPlugin
rclcpp::PublisherOptions opt) override;
#endif
void publish(const Image & message, const PublisherTFn & publisher) const override;
void shutdown() override;

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

rmw_qos_profile_t initialize(
rclcpp::Node * node, const std::string & base_name, rmw_qos_profile_t custom_qos);
void declareParameter(
rclcpp::Node * node, const std::string & base_name, const ParameterDefinition & definition);
void handleAVOptions(const std::string & opt);
// variables ---------
rclcpp::Logger logger_;
const PublisherTFn * publishFunction_{NULL};
Expand Down
19 changes: 15 additions & 4 deletions include/ffmpeg_image_transport/ffmpeg_subscriber.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#define FFMPEG_IMAGE_TRANSPORT__FFMPEG_SUBSCRIBER_HPP_

#include <ffmpeg_encoder_decoder/decoder.hpp>
#include <ffmpeg_image_transport/parameter_definition.hpp>
#include <ffmpeg_image_transport_msgs/msg/ffmpeg_packet.hpp>
#include <image_transport/simple_subscriber_plugin.hpp>
#include <string>
Expand Down Expand Up @@ -47,18 +48,28 @@ class FFMPEGSubscriber : public FFMPEGSubscriberPlugin
#else
void subscribeImpl(
rclcpp::Node * node, const std::string & base_topic, const Callback & callback,
rmw_qos_profile_t custom_qos, rclcpp::SubscriptionOptions) override;
#ifdef IMAGE_TRANSPORT_USE_QOS
rclcpp::QoS custom_qos,
#else
rmw_qos_profile_t custom_qos,
#endif
rclcpp::SubscriptionOptions) override;
#endif
void shutdown() override;

private:
void frameReady(const ImageConstPtr & img, bool /*isKeyFrame*/) const;
void initialize(rclcpp::Node * node, const std::string & base_topics);
void initialize(rclcpp::Node * node, const std::string & base_topic);
std::string getDecodersFromMap(const std::string & encoding);
void declareParameter(
rclcpp::Node * node, const std::string & base_name, const ParameterDefinition & definition);
void handleAVOptions(const std::string & opt);
// -------------- variables
rclcpp::Logger logger_;
rclcpp::Node * node_;
rclcpp::Node * node_{nullptr};
ffmpeg_encoder_decoder::Decoder decoder_;
std::string decoderType_;
const Callback * userCallback_;
const Callback * userCallback_{nullptr};
std::string param_namespace_;
};
} // namespace ffmpeg_image_transport
Expand Down
Loading
Loading