Skip to content

Commit

Permalink
added documentation and improved cmake exporting
Browse files Browse the repository at this point in the history
  • Loading branch information
berndpfrommer committed Mar 11, 2024
1 parent c8de103 commit 0a84c99
Show file tree
Hide file tree
Showing 8 changed files with 163 additions and 31 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
doc/generated
11 changes: 8 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -70,16 +70,20 @@ target_include_directories(${LIBRARY_NAME} PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")


ament_target_dependencies(${LIBRARY_NAME}
PUBLIC
cv_bridge
image_transport
pluginlib
rclcpp
sensor_msgs
ffmpeg_image_transport_msgs)

target_link_libraries(${LIBRARY_NAME} opencv_imgproc PkgConfig::LIBAV)
target_link_libraries(${LIBRARY_NAME}
PUBLIC
opencv_imgproc
PkgConfig::LIBAV)


add_executable(test_encoder
test/test_encoder.cpp)
Expand Down Expand Up @@ -154,4 +158,5 @@ if(BUILD_TESTING)
ament_xmllint()
endif()

ament_package()
ament_package(CONFIG_EXTRAS cmake/${PROJECT_NAME}-extras.cmake.in)

50 changes: 22 additions & 28 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,28 +1,30 @@
# ROS2 image transport for FFmpeg encoding

This ROS2 image transport supports encoding/decoding with the FFMpeg
library. With this transport you can encode h264 and h265, using
Nvidia hardware acceleration when available.
The ROS2 image transport supports encoding/decoding with the FFMpeg
library, for example encoding h264 and h265 or HEVC, using
Nvidia or other hardware acceleration when available.
This package is a complete rewrite of an
[older ROS1 ffmpeg_image_transport](https://github.com/daniilidis-group/ffmpeg_image_transport)
package.

The publisher plugin of the transport produces
[ffmpeg image transport messages](https://github.com/ros-misc-utitilies/ffmpeg_image_transport_msgs).
These are raw, encoded packets that are then transmitted and decoded by the
subscriber plugin of the transport. This image transport library
contains both the publisher(encoder) and subscriber(decoder)
subscriber plugin of the transport. The transport library
contains both the publisher(encoder) and subscriber(decoder) plugin
and therefore must be installed on both sides to be useful.

To extract e.g. frames or an mp4 file from a recorded bag, have a look at the
[ffmpeg\_image\_transport\_tools](https://github.com/ros-misc-utilities/ffmpeg_image_transport_tools) repository.

## Supported systems

Tested on:
Continuous integration is tested under Ubuntu with the following ROS2 distros:

- Ubuntu 20.04 and ROS2 Galactic
- Ubuntu 22.04 and ROS2 Humble
[![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=Idev__ffmpeg_image_transport__ubuntu_jammy_amd64&subject=Iron)](https://build.ros2.org/job/Idev__ffmpeg_image_transport__ubuntu_jammy_amd64/)
[![Build Status](https://build.ros2.org/buildStatus/icon?job=Rdev__ffmpeg_image_transport__ubuntu_jammy_amd64&subject=Rolling)](https://build.ros2.org/job/Rdev__ffmpeg_image_transport__ubuntu_jammy_amd64/)

Should build on later ROS2 distros as well.

## Installation

Expand All @@ -33,41 +35,33 @@ sudo apt-get install ros-${ROS_DISTRO}-ffmpeg-image-transport
```

### From source
Create a ROS2 workspace as usual, clone this repo into it and pull in
the required repo with the messages:
```
mkdir -p ws/src
cd ws/src
git clone https://github.com/ros-misc-utilities/ffmpeg_image_transport.git
cd ..
vcs import < src/ffmpeg_image_transport/ffmpeg_image_transport.repos
```

Install the dependencies (libav) via rosdep (must be run from top of workspace!):
```
rosdep install --from-paths src --ignore-src -r
```

You should now be able to build:
```
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
Set the following shell variables:
```bash
repo=ffmpeg_image_transport
url=https://github.com/ros-misc-utilities/${repo}.git
```
and follow the [instructions here](https://github.com/ros-misc-utilities/.github/blob/master/docs/build_ros_repository.md)

Make sure to source your workspace's ``install/setup.bash`` afterwards.
If all goes well you should see the transport show up:

```
ros2 run image_transport list_transports
```

should give output (among other transport plugins):
```
image_transport/ffmpeg"

```text
"image_transport/ffmpeg"
- Provided by package: ffmpeg_image_transport
- Publisher:
This plugin encodes frames into ffmpeg compressed packets
- Subscriber:
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).

Expand Down
10 changes: 10 additions & 0 deletions cmake/ffmpeg_image_transport-extras.cmake.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
set(FFMPEG_PKGCONFIG "" CACHE STRING "extra path to pkgconfig")
set(ENV{PKG_CONFIG_PATH} ${FFMPEG_PKGCONFIG})

find_package(PkgConfig REQUIRED)

pkg_check_modules(LIBAV REQUIRED IMPORTED_TARGET
libavcodec
libswresample
libswscale
libavutil)
69 changes: 69 additions & 0 deletions doc/conf.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
# Copyright 2024 Bernd Pfrommer
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#

import os
import sys

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

project = 'ffmpeg_image_transport'
# copyright = '2024, 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',
]

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

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

# The name of the Pygments (syntax highlighting) style to use.
pygments_style = None

# -- Options for HTML output -------------------------------------------------

# The theme to use for HTML and HTML Help pages. See the documentation for
# a list of builtin themes.
#
# html_theme = 'alabaster'
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']

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

autoclass_content = 'both'

autodoc_default_options = {
'members': True, # document members
'undoc-members': True, # also document members without documentation
}
8 changes: 8 additions & 0 deletions doc/index.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
ffmpeg_image_transport
======================

.. toctree::
:maxdepth: 2

.. include:: readme_include.md
:parser: myst_parser.sphinx_
3 changes: 3 additions & 0 deletions doc/readme_include.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
```{include} ../README.md
:relative-images:
```
42 changes: 42 additions & 0 deletions rosdoc2.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
## This 'attic section' self-documents this file's type and version.
type: 'rosdoc2 config'
version: 1

---

settings:
## If this is true, a standard index page is generated in the output directory.
## It uses the package information from the 'package.xml' to show details
## about the package, creates a table of contents for the various builders
## that were run, and may contain links to things like build farm jobs for
## this package or links to other versions of this package.
## If this is not specified explicitly, it defaults to 'true'.
generate_package_index: true

## Point to python sources relative to package.xml file
python_source: 'ffmpeg_image_transport'

## Don't run doxygen
always_run_doxygen: false

## Build python API docs
## This is most useful if the user would like to generate Python API
## documentation for a package that is not of the `ament_python` build type.
always_run_sphinx_apidoc: false

# disable breathe and exhale
enable_breathe: false
enable_exhale: false

# This setting, if provided, will override the build_type of this package
# for documentation purposes only. If not provided, documentation will be
# generated assuming the build_type in package.xml.
override_build_type: 'ament_python'

builders:
- sphinx: {
name: 'ffmpeg_image_transport',
## This path is relative to output staging.
sphinx_sourcedir: 'doc/',
output_dir: ''
}

0 comments on commit 0a84c99

Please sign in to comment.