Skip to content
Projects
Groups
Snippets
Help
Loading...
Sign in / Register
Toggle navigation
F
ffmpeg_image_transport
Project
Project
Details
Activity
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Board
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Packages
Packages
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
jfx_tools
ffmpeg_image_transport
Commits
306aab5d
Commit
306aab5d
authored
May 11, 2023
by
alexander
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
add files
parents
Pipeline
#1516
failed with stages
Changes
23
Pipelines
1
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
23 changed files
with
1460 additions
and
0 deletions
+1460
-0
CMakeLists.txt
src/ffmpeg_image_transport/CMakeLists.txt
+80
-0
README.md
src/ffmpeg_image_transport/README.md
+159
-0
EncoderDyn.cfg
src/ffmpeg_image_transport/cfg/EncoderDyn.cfg
+44
-0
EncoderDyn_jetson.cfg
src/ffmpeg_image_transport/cfg_jetson/EncoderDyn_jetson.cfg
+44
-0
FindFFMPEG.cmake
src/ffmpeg_image_transport/cmake/FindFFMPEG.cmake
+103
-0
compile_ffmpeg.md
src/ffmpeg_image_transport/docs/compile_ffmpeg.md
+106
-0
ffmpeg_plugins.xml
src/ffmpeg_image_transport/ffmpeg_plugins.xml
+14
-0
ffmpeg_decoder.h
...transport/include/ffmpeg_image_transport/ffmpeg_decoder.h
+81
-0
ffmpeg_encoder.h
...transport/include/ffmpeg_image_transport/ffmpeg_encoder.h
+135
-0
ffmpeg_publisher.h
...ansport/include/ffmpeg_image_transport/ffmpeg_publisher.h
+59
-0
ffmpeg_subscriber.h
...nsport/include/ffmpeg_image_transport/ffmpeg_subscriber.h
+43
-0
tdiff.h
...eg_image_transport/include/ffmpeg_image_transport/tdiff.h
+28
-0
h264.launch
src/ffmpeg_image_transport/launch/h264.launch
+38
-0
package.xml
src/ffmpeg_image_transport/package.xml
+22
-0
ffmpeg_decoder.cpp
src/ffmpeg_image_transport/src/ffmpeg_decoder.cpp
+0
-0
ffmpeg_encoder.cpp
src/ffmpeg_image_transport/src/ffmpeg_encoder.cpp
+291
-0
ffmpeg_publisher.cpp
src/ffmpeg_image_transport/src/ffmpeg_publisher.cpp
+114
-0
ffmpeg_subscriber.cpp
src/ffmpeg_image_transport/src/ffmpeg_subscriber.cpp
+47
-0
manifest.cpp
src/ffmpeg_image_transport/src/manifest.cpp
+6
-0
tdiff.cpp
src/ffmpeg_image_transport/src/tdiff.cpp
+15
-0
CMakeLists.txt
src/ffmpeg_image_transport_msgs/CMakeLists.txt
+9
-0
FFMPEGPacket.msg
src/ffmpeg_image_transport_msgs/msg/FFMPEGPacket.msg
+8
-0
package.xml
src/ffmpeg_image_transport_msgs/package.xml
+14
-0
No files found.
src/ffmpeg_image_transport/CMakeLists.txt
0 → 100644
View file @
306aab5d
cmake_minimum_required
(
VERSION 2.8
)
project
(
ffmpeg_image_transport
)
set
(
CMAKE_CXX_FLAGS
"
${
CMAKE_CXX_FLAGS
}
-std=c++11 -g -Wall"
)
# set(ON-JETSON-PLATFORM "TRUE")
find_package
(
catkin REQUIRED COMPONENTS
roscpp
cv_bridge
image_transport
ffmpeg_image_transport_msgs
sensor_msgs
dynamic_reconfigure
)
set
(
CMAKE_MODULE_PATH
${
PROJECT_SOURCE_DIR
}
/cmake
)
find_package
(
FFMPEG REQUIRED
)
if
(
ON-JETSON-PLATFORM
)
generate_dynamic_reconfigure_options
(
cfg_jetson/EncoderDyn.cfg
)
else
()
generate_dynamic_reconfigure_options
(
cfg/EncoderDyn.cfg
)
endif
()
catkin_package
(
INCLUDE_DIRS include
LIBRARIES
${
PROJECT_NAME
}
CATKIN_DEPENDS
roscpp
cv_bridge
image_transport
ffmpeg_image_transport_msgs
sensor_msgs
dynamic_reconfigure
DEPENDS
FFMPEG
)
find_package
(
OpenCV
)
include_directories
(
include
${
FFMPEG_INCLUDE_DIR
}
${
catkin_INCLUDE_DIRS
}
${
OpenCV_INCLUDE_DIRS
}
)
# add the plugin
add_library
(
${
PROJECT_NAME
}
src/manifest.cpp
src/ffmpeg_publisher.cpp
src/ffmpeg_subscriber.cpp
src/ffmpeg_encoder.cpp
src/ffmpeg_decoder.cpp
src/tdiff.cpp
${
FFMPEG_LIBRARIES
}
)
add_dependencies
(
${
PROJECT_NAME
}
${${
PROJECT_NAME
}
_EXPORTED_TARGETS
}
${
catkin_EXPORTED_TARGETS
}
)
target_link_libraries
(
${
PROJECT_NAME
}
${
catkin_LIBRARIES
}
${
OpenCV_LIBRARIES
}
${
FFMPEG_LIBRARIES
}
)
install
(
DIRECTORY
include/
${
PROJECT_NAME
}
/
DESTINATION
${
CATKIN_PACKAGE_INCLUDE_DESTINATION
}
FILES_MATCHING PATTERN
"*.h"
)
install
(
DIRECTORY
launch
DESTINATION
${
CATKIN_PACKAGE_SHARE_DESTINATION
}
)
install
(
TARGETS
${
PROJECT_NAME
}
ARCHIVE DESTINATION
${
CATKIN_PACKAGE_LIB_DESTINATION
}
LIBRARY DESTINATION
${
CATKIN_PACKAGE_LIB_DESTINATION
}
RUNTIME DESTINATION
${
CATKIN_PACKAGE_BIN_DESTINATION
}
)
install
(
FILES
ffmpeg_plugins.xml
DESTINATION
${
CATKIN_PACKAGE_SHARE_DESTINATION
}
)
src/ffmpeg_image_transport/README.md
0 → 100644
View file @
306aab5d
# ROS image transport for FFmpeg encoding
This ROS image transport supports encoding/decoding with the FFMpeg
library. With this transport, you can encode h264 and h265, using
nvidia hardware acceleration when available.
Also have a look at
[
this repo tools to help with decoding
](
https://github.com/daniilidis-group/ffmpeg_image_transport_tools
)
.
## Downloading
Create a catkin workspace (if not already there) and download the
ffmpeg image transport and other required packages:
mkdir -p catkin_ws/src
cd catkin_ws/src
git clone https://github.com/daniilidis-group/ffmpeg_image_transport_msgs.git
git clone https://github.com/daniilidis-group/ffmpeg_image_transport.git
Optionally get the additional set of ffmpeg tools:
git clone git@github.com:daniilidis-group/ffmpeg_image_transport_tools.git
## Requirements: FFmpeg v4.0 or later, and a "reasonable" resolution
At some point this software worked on the following systems:
-
Ubuntu 16.04 + ROS kinetic (not tested in a long while, maybe broken
by now)
-
Ubuntu 18.04 + ROS melodic
-
Ubuntu 20.04 + ROS noetic (recently tested, should work with stock ffmpeg)
If you have ffmpeg 4.0 or later you may be able to compile against default header files:
sudo apt install ffmpeg
If you don't have ffmpeg 4.0 or later, or you hit compile errors
(supposedly even happens now on Ubuntu 18.04),
[
follow these instructions to compile ffmpeg from scratch
](
docs/compile_ffmpeg.md
)
, and point the
transport to the right place:
ffmpeg_dir=<here the ffmpeg_dir>
catkin config -DCMAKE_BUILD_TYPE=Release -DFFMPEG_LIB=${ffmpeg_dir}/build/lib -DFFMPEG_INC=${ffmpeg_dir}/build/include
Note that not all resolutions are supported in hardware accelerated
mode for h264 encoding/decoding, so you may get strange results if you
have cameras with resolutions other than those supported by
e.g. nvenc. Plain 1920x1200 works, probably also VGA, but other
resolutions need to be verified. Experiments indicate that the line
width must be a multiple of 32!
## Compiling
This should be easy as running the following inside your catkin workspace
catkin config -DCMAKE_BUILD_TYPE=Release
or, if you have your own version of ffmpeg installaed under
``${ffmpeg_dir``
(see above)
catkin config -DCMAKE_BUILD_TYPE=Release -DFFMPEG_LIB=${ffmpeg_dir}/build/lib -DFFMPEG_INC=${ffmpeg_dir}/build/include
then compile should be as easy as this:
catkin build ffmpeg_image_transport
## How to use
Usage should be transparent, but the ffmpeg image transport plugin
needs to be available on both the publishing and the subscribing
node. You also
*
need to add the location to your custom built ffmpeg
library
*
to
``LD_LIBRARY_PATH``
, like so (change path to match yours):
```
export LD_LIBRARY_PATH=$HOME/catkin_ws/ffmpeg/build/lib:$LD_LIBRARY_PATH
```
Once done, you should get the following output when you run
``list_transports``
:
```
rosrun image_transport list_transports
Declared transports:
... some stuff ...
image_transport/ffmpeg
... some stuff ...
Details:
----------
... some stuff ...
"image_transport/ffmpeg"
- Provided by package: ffmpeg_image_transport
- Publisher:
This plugin encodes frame into ffmpeg compressed packets
- Subscriber:
This plugin decodes frame from ffmpeg compressed packets
```
If it says something about "plugins not built", that means the
``LD_LIBRARY_PATH``
is not set correctly.
### republishing
Most ROS nodes that publish images use an image transport for that. If
not you can use a republish node to convert images into an ffmpeg
stream. The following line will start a republish node in ffmpeg format:
```
rosrun image_transport republish raw in:=/webcam/image_raw ffmpeg out:=/webcam/image_raw/ffmpeg _/webcam/image_raw/ffmpeg/encoding:=x264
```
### encoder parameters
The image transport has various parameters that you can configure
dynamically via
``rqt_reconfigure``
, or specify at startup by
prepending the topic name. For instance to use the unaccelerated
``libx264``
encoding, start a republish node like this:
```
rosrun image_transport republish raw in:=/webcam/image_raw ffmpeg __name:=repub out:=~/image_raw _/image_raw/ffmpeg/encoder:=libx264
```
Note: I had to
``__name``
the node to get the ros parameter show up under the topic name.
Parameters (see ffmpeg h264 documentation for explanation):
-
``encoder``
: ffmpeg encoding to use. Allowed values:
``h265_nvenc``
,
``hevc_nvenc``
,
``libx264``
(no GPU). Default:
``hevc_nvenc``
.
-
``profile``
: ffmpeg profile. Allowed values:
``main``
,
``main10``
,
``rext``
,
``high``
. Default:
``main``
.
-
``qmax``
: maximum allowed quantization, controls quality. Range 0-63, default: 10.
-
``bit_rate``
: bit rate in bits/sec. Range 10-2000000000, default: 8242880.
-
``gop_size``
: gop size (number of frames): Range 1-128, default: 15
-
``measure_performance``
: switch on performance debugging output. Default: false.
-
``performance_interval``
: number of frames between performance printouts. Default: 175.
### encoder parameters
Usually the decoder infers from the received encoding type what decoding scheme to use.
You can overwrite it with a node-level parameter though:
-
``decoder_type``
:
-
``h264``
: used if encoding is
``libx264``
or
``h264_nvenc``
.
-
``hevc_cuvid``
: first tried if encoding is
``hevc_nvenc``
.
-
``hevc``
: second tried if encoding is
``hevc_nvenc``
.
For example to force
``hevc``
decoding, run a node like this:
```
rosrun image_transport republish ffmpeg in:=/repub/image_raw raw out:=~/image_raw _/ffmpeg/decoder_type:=hevc
```
## Trouble shooting:
On e.g. Ubuntu 16.04, you need a newer version of ffmpeg. If you get an error like this one,
you need a newer version of ffmpeg:
In member function ‘bool ffmpeg_image_transport::FFMPEGDecoder::decodePacket(const ConstPtr&)’:
/home/pfrommer/Documents/birds/src/ffmpeg_image_transport/src/ffmpeg_decoder.cpp:104:47:
error: ‘avcodec_send_packet’ was not declared in this scope
int ret = avcodec_send_packet(ctx, &packet);
If the build still fails, make sure you start from scratch:
catkin clean ffmpeg_image_transport
src/ffmpeg_image_transport/cfg/EncoderDyn.cfg
0 → 100755
View file @
306aab5d
#!/usr/bin/env python2
PACKAGE
=
"ffmpeg_image_transport"
from
dynamic_reconfigure.parameter_generator_catkin
import
*
gen
=
ParameterGenerator
()
#
# encoder options
#
encode_enum
=
gen
.
enum
([
gen
.
const
(
"h264_nvenc"
,
str_t
,
"h264_nvenc"
,
"h264_nvenc"
),
gen
.
const
(
"hevc_nvenc"
,
str_t
,
"hevc_nvenc"
,
"hevc_nvenc"
),
gen
.
const
(
"libx264"
,
str_t
,
"libx264"
,
"libx264"
)],
"An enum to set the encoder"
)
gen
.
add
(
"encoder"
,
str_t
,
0
,
"encoding method"
,
"h264_nvenc"
,
edit_method
=
encode_enum
)
profile_enum
=
gen
.
enum
([
gen
.
const
(
"main"
,
str_t
,
"main"
,
"main"
),
gen
.
const
(
"main10"
,
str_t
,
"main10"
,
"main10"
),
gen
.
const
(
"rext"
,
str_t
,
"rext"
,
"rext"
),
gen
.
const
(
"high"
,
str_t
,
"high"
,
"high"
)],
"An enum to set the profile"
)
gen
.
add
(
"profile"
,
str_t
,
0
,
"profile"
,
"main"
,
edit_method
=
profile_enum
)
preset_enum
=
gen
.
enum
([
gen
.
const
(
"slow"
,
str_t
,
"slow"
,
"slow"
),
gen
.
const
(
"medium"
,
str_t
,
"medium"
,
"medium"
),
gen
.
const
(
"fast"
,
str_t
,
"fast"
,
"fast"
),
gen
.
const
(
"hp"
,
str_t
,
"hp"
,
"hp"
),
gen
.
const
(
"hq"
,
str_t
,
"hq"
,
"hq"
),
gen
.
const
(
"bd"
,
str_t
,
"bd"
,
"bd"
),
gen
.
const
(
"ll"
,
str_t
,
"ll"
,
"low latency"
),
gen
.
const
(
"llhq"
,
str_t
,
"llhq"
,
"low latency hq"
),
gen
.
const
(
"llhp"
,
str_t
,
"llhp"
,
"low latency hp"
),
gen
.
const
(
"lossless"
,
str_t
,
"lossless"
,
"lossless"
),
gen
.
const
(
"losslesshp"
,
str_t
,
"losslesshp"
,
"lossless hp"
)],
"An enum to set the preset"
)
gen
.
add
(
"preset"
,
str_t
,
0
,
"preset"
,
"slow"
,
edit_method
=
preset_enum
)
gen
.
add
(
"qmax"
,
int_t
,
0
,
"maximum allowed quantization"
,
10
,
0
,
63
)
gen
.
add
(
"bit_rate"
,
int_t
,
0
,
"bit_rate [in bits_sec]"
,
2097152
,
10
,
2000000000
)
gen
.
add
(
"frame_rate"
,
int_t
,
0
,
"frame_rate [frames in seconds]"
,
10
,
1
,
60
)
gen
.
add
(
"gop_size"
,
int_t
,
0
,
"gop_size [frames]"
,
50
,
1
,
128
)
gen
.
add
(
"measure_performance"
,
bool_t
,
0
,
"measure performance"
,
False
)
gen
.
add
(
"performance_interval"
,
int_t
,
0
,
"interval between perf printout [frames]"
,
175
,
1
,
100000
)
exit
(
gen
.
generate
(
PACKAGE
,
"ffmpeg_image_transport"
,
"EncoderDyn"
))
src/ffmpeg_image_transport/cfg_jetson/EncoderDyn_jetson.cfg
0 → 100755
View file @
306aab5d
#!/usr/bin/env python2
PACKAGE
=
"ffmpeg_image_transport"
from
dynamic_reconfigure.parameter_generator_catkin
import
*
gen
=
ParameterGenerator
()
#
# encoder options
#
encode_enum
=
gen
.
enum
([
gen
.
const
(
"h264_nvenc"
,
str_t
,
"h264_nvenc"
,
"h264_nvenc"
),
gen
.
const
(
"hevc_nvenc"
,
str_t
,
"hevc_nvenc"
,
"hevc_nvenc"
),
gen
.
const
(
"libx264"
,
str_t
,
"libx264"
,
"libx264"
),
gen
.
const
(
"h264_nvmpi"
,
str_t
,
"h264_nvmpi"
,
"h264_nvmpi"
)],
"An enum to set the encoder"
)
gen
.
add
(
"encoder"
,
str_t
,
3
,
"encoding method"
,
"h264_nvmpi"
,
edit_method
=
encode_enum
)
profile_enum
=
gen
.
enum
([
gen
.
const
(
"main"
,
str_t
,
"main"
,
"main"
),
gen
.
const
(
"main10"
,
str_t
,
"main10"
,
"main10"
),
gen
.
const
(
"rext"
,
str_t
,
"rext"
,
"rext"
),
gen
.
const
(
"high"
,
str_t
,
"high"
,
"high"
)],
"An enum to set the profile"
)
gen
.
add
(
"profile"
,
str_t
,
0
,
"profile"
,
"main"
,
edit_method
=
profile_enum
)
preset_enum
=
gen
.
enum
([
gen
.
const
(
"slow"
,
str_t
,
"slow"
,
"slow"
),
gen
.
const
(
"medium"
,
str_t
,
"medium"
,
"medium"
),
gen
.
const
(
"fast"
,
str_t
,
"fast"
,
"fast"
),
gen
.
const
(
"hp"
,
str_t
,
"hp"
,
"hp"
),
gen
.
const
(
"hq"
,
str_t
,
"hq"
,
"hq"
),
gen
.
const
(
"bd"
,
str_t
,
"bd"
,
"bd"
),
gen
.
const
(
"ll"
,
str_t
,
"ll"
,
"low latency"
),
gen
.
const
(
"llhq"
,
str_t
,
"llhq"
,
"low latency hq"
),
gen
.
const
(
"llhp"
,
str_t
,
"llhp"
,
"low latency hp"
),
gen
.
const
(
"lossless"
,
str_t
,
"lossless"
,
"lossless"
),
gen
.
const
(
"losslesshp"
,
str_t
,
"losslesshp"
,
"lossless hp"
)],
"An enum to set the preset"
)
gen
.
add
(
"preset"
,
str_t
,
0
,
"preset"
,
"slow"
,
edit_method
=
preset_enum
)
gen
.
add
(
"qmax"
,
int_t
,
0
,
"maximum allowed quantization"
,
10
,
0
,
63
)
gen
.
add
(
"bit_rate"
,
int_t
,
0
,
"bit_rate [in bits_sec]"
,
2097152
,
10
,
2000000000
)
gen
.
add
(
"gop_size"
,
int_t
,
0
,
"gop_size [frames]"
,
50
,
1
,
128
)
gen
.
add
(
"measure_performance"
,
bool_t
,
0
,
"measure performance"
,
False
)
gen
.
add
(
"performance_interval"
,
int_t
,
0
,
"interval between perf printout [frames]"
,
175
,
1
,
100000
)
exit
(
gen
.
generate
(
PACKAGE
,
"ffmpeg_image_transport"
,
"EncoderDyn"
))
src/ffmpeg_image_transport/cmake/FindFFMPEG.cmake
0 → 100644
View file @
306aab5d
# - Try to find ffmpeg libraries (libavcodec, libavformat and libavutil)
# Once done this will define
#
# FFMPEG_FOUND - system has ffmpeg or libav
# FFMPEG_INCLUDE_DIR - the ffmpeg include directory
# FFMPEG_LIBRARIES - Link these to use ffmpeg
# FFMPEG_LIBAVCODEC
# FFMPEG_LIBAVFORMAT
# FFMPEG_LIBAVUTIL
# FFMPEG_LIBSWSCALE
# FFMPEG_LIBSWRESAMPLE
#
# Copyright (c) 2008 Andreas Schneider <mail@cynapses.org>
# Modified for other libraries by Lasse Kärkkäinen <tronic>
# Modified for Hedgewars by Stepik777
#
# Redistribution and use is allowed according to the terms of the New
# BSD license.
#
if
(
FFMPEG_LIBRARIES AND FFMPEG_INCLUDE_DIR
)
# in cache already
set
(
FFMPEG_FOUND TRUE
)
else
(
FFMPEG_LIBRARIES AND FFMPEG_INCLUDE_DIR
)
# use pkg-config to get the directories and then use these values
# in the FIND_PATH() and FIND_LIBRARY() calls
find_package
(
PkgConfig
)
set
(
FFMPEG_EXTRA_LIB_DIRS /usr/lib/x86_64-linux-gnu /usr/lib /usr/local/lib /opt/local/lib /sw/lib
)
set
(
FFMPEG_EXTRA_LIB_DIRS
${
FFMPEG_LIB
}
/usr/lib /usr/local/lib /opt/local/lib /sw/lib
)
if
(
PKG_CONFIG_FOUND
)
pkg_check_modules
(
_FFMPEG_AVCODEC libavcodec
)
pkg_check_modules
(
_FFMPEG_AVFORMAT libavformat
)
pkg_check_modules
(
_FFMPEG_AVUTIL libavutil
)
pkg_check_modules
(
_FFMPEG_SWSCALE libswscale
)
pkg_check_modules
(
_FFMPEG_SWRESAMPLE libswresample
)
endif
(
PKG_CONFIG_FOUND
)
find_path
(
FFMPEG_AVCODEC_INCLUDE_DIR
NAMES libavcodec/avcodec.h
HINTS
${
FFMPEG_INC
}
PATH_SUFFIXES ffmpeg libav
)
# NO_DEFAULT_PATH
find_library
(
FFMPEG_LIBAVCODEC
NAMES avcodec
HINTS
${
FFMPEG_LIB
}
# NO_DEFAULT_PATH
)
find_library
(
FFMPEG_LIBAVFORMAT
NAMES avformat
HINTS
${
FFMPEG_LIB
}
# NO_DEFAULT_PATH
)
find_library
(
FFMPEG_LIBAVUTIL
NAMES avutil
HINTS
${
FFMPEG_LIB
}
# NO_DEFAULT_PATH
)
find_library
(
FFMPEG_LIBSWSCALE
NAMES swscale
HINTS
${
FFMPEG_LIB
}
# NO_DEFAULT_PATH
)
find_library
(
FFMPEG_LIBSWRESAMPLE
NAMES swresample
HINTS
${
FFMPEG_LIB
}
# NO_DEFAULT_PATH
)
if
(
FFMPEG_LIBAVCODEC AND FFMPEG_LIBAVFORMAT
)
set
(
FFMPEG_FOUND TRUE
)
endif
()
if
(
FFMPEG_FOUND
)
set
(
FFMPEG_INCLUDE_DIR
${
FFMPEG_AVCODEC_INCLUDE_DIR
}
)
set
(
FFMPEG_LIBRARIES
${
FFMPEG_LIBSWSCALE
}
${
FFMPEG_LIBSWRESAMPLE
}
${
FFMPEG_LIBAVCODEC
}
${
FFMPEG_LIBAVFORMAT
}
${
FFMPEG_LIBAVUTIL
}
)
endif
(
FFMPEG_FOUND
)
if
(
FFMPEG_FOUND
)
if
(
NOT FFMPEG_FIND_QUIETLY
)
message
(
STATUS
"Found FFMPEG or Libav:
${
FFMPEG_LIBRARIES
}
,
${
FFMPEG_INCLUDE_DIR
}
"
)
endif
(
NOT FFMPEG_FIND_QUIETLY
)
else
(
FFMPEG_FOUND
)
if
(
FFMPEG_FIND_REQUIRED
)
message
(
FATAL_ERROR
"Could not find libavcodec or libavformat or libavutil"
)
endif
(
FFMPEG_FIND_REQUIRED
)
endif
(
FFMPEG_FOUND
)
endif
(
FFMPEG_LIBRARIES AND FFMPEG_INCLUDE_DIR
)
src/ffmpeg_image_transport/docs/compile_ffmpeg.md
0 → 100644
View file @
306aab5d
# How to compile FFmpeg from scratch for your project
## Prepare for FFmpeg installation
Install ffmpeg build dependencies according to
[
this website
](
https://trac.ffmpeg.org/wiki/CompilationGuide/Ubuntu
)
:
sudo apt-get update -qq && sudo apt-get -y install \
autoconf \
automake \
build-essential \
cmake \
git-core \
libass-dev \
libfreetype6-dev \
libsdl2-dev \
libtool \
libva-dev \
libvdpau-dev \
libvorbis-dev \
libxcb1-dev \
libxcb-shm0-dev \
libxcb-xfixes0-dev \
pkg-config \
texinfo \
wget \
zlib1g-dev \
libx264-dev \
libx265-dev
Make your own ffmpeg directory:
ffmpeg_dir=<absolute_path_to_empty_directory_for_ffmpeg_stuff>
mkdir -p $ffmpeg_dir/build $ffmpeg_dir/bin
Build yasm:
cd $ffmpeg_dir
wget -O yasm-1.3.0.tar.gz https://www.tortall.net/projects/yasm/releases/yasm-1.3.0.tar.gz && \
tar xzvf yasm-1.3.0.tar.gz && \
cd yasm-1.3.0 && \
./configure --prefix="$ffmpeg_dir/build" --bindir="$ffmpeg_dir/bin" && \
make && \
make install
Build nasm:
cd $ffmpeg_dir
wget https://www.nasm.us/pub/nasm/releasebuilds/2.13.03/nasm-2.13.03.tar.bz2 && \
tar xjvf nasm-2.13.03.tar.bz2 && \
cd nasm-2.13.03 && \
./autogen.sh && \
PATH="${ffmpeg_dir}/bin:$PATH" ./configure --prefix="${ffmpeg_dir}/build" --bindir="${ffmpeg_dir}/bin" && \
make && \
make install
Get nvcodec headers:
cd $ffmpeg_dir
git clone https://git.videolan.org/git/ffmpeg/nv-codec-headers.git
cd nv-codec-headers
At this point you will have to pick the right version of the headers. You need the one that matches
your driver. For instance:
git checkout n8.2.15.8
will get you a version that works with with Linux 410.48 or newer (see README file). If you mess
up here, you will later get an error that looks like this:
[hevc_nvenc @ 0x7fc67c03a580] Cannot load libnvidia-encode.so.1
[hevc_nvenc @ 0x7fc67c03a580] The minimum required Nvidia driver for nvenc is 418.30 or newer
Now create a modified Makefile that points to the right location:
tmp_var="${ffmpeg_dir//"/"/"\/"}"
sed "s/\/usr\/local/${tmp_var}\/build/g" Makefile > Makefile.tmp
make -f Makefile.tmp install
# Compile FFMpeg
Clone and configure ffmpeg to your needs. The following configuration gives you
cuda and the hardware accelerated nvidia (nvenc) encoding for x264/x265.
This builds an ffmpeg that has more components than you need.
cd $ffmpeg_dir
git clone https://github.com/FFmpeg/FFmpeg.git
cd $ffmpeg_dir/FFmpeg
To build full NVidia encode/decode support, do this:
PATH="$ffmpeg_dir/bin:$PATH" PKG_CONFIG_PATH="$ffmpeg_dir/build/lib/pkgconfig" ./configure --prefix=${ffmpeg_dir}/build --extra-cflags=-I${ffmpeg_dir}/build/include --extra-ldflags=-L${ffmpeg_dir}/build/lib --bindir=${ffmpeg_dir}/bin --enable-cuda-nvcc --enable-cuvid --enable-libnpp --extra-cflags=-I/usr/local/cuda/include/ --extra-ldflags=-L/usr/local/cuda/lib64/ --enable-gpl --enable-nvenc --enable-libx264 --enable-libx265 --enable-nonfree --enable-shared
If you don't have an NVidia card, do this:
PATH="$ffmpeg_dir/bin:$PATH" PKG_CONFIG_PATH="$ffmpeg_dir/build/lib/pkgconfig" ./configure --prefix=${ffmpeg_dir}/build --extra-cflags=-I${ffmpeg_dir}/build/include --extra-ldflags=-L${ffmpeg_dir}/build/lib --bindir=${ffmpeg_dir}/bin --enable-gpl --enable-libx264 --enable-libx265 --enable-nonfree --enable-shared
Now build and install (runs for a few minutes!):
PATH="$ffmpeg_dir/bin:${PATH}:/usr/local/cuda/bin" make && make install && hash -r
src/ffmpeg_image_transport/ffmpeg_plugins.xml
0 → 100644
View file @
306aab5d
<library
path=
"lib/libffmpeg_image_transport"
>
<class
name=
"image_transport/ffmpeg_pub"
type=
"ffmpeg_image_transport::FFMPEGPublisher"
base_class_type=
"image_transport::PublisherPlugin"
>
<description>
This plugin encodes frame into ffmpeg compressed packets
</description>
</class>
<class
name=
"image_transport/ffmpeg_sub"
type=
"ffmpeg_image_transport::FFMPEGSubscriber"
base_class_type=
"image_transport::SubscriberPlugin"
>
<description>
This plugin decodes frame from ffmpeg compressed packets
</description>
</class>
</library>
src/ffmpeg_image_transport/include/ffmpeg_image_transport/ffmpeg_decoder.h
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#pragma once
#include "ffmpeg_image_transport_msgs/FFMPEGPacket.h"
#include "ffmpeg_image_transport/tdiff.h"
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <memory>
#include <unordered_map>
extern
"C"
{
#include <libavcodec/avcodec.h>
#include <libavformat/avio.h>
#include <libavformat/avformat.h>
#include <libswscale/swscale.h>
#include <libavutil/opt.h>
#include <libavutil/imgutils.h>
#include <libavutil/samplefmt.h>
#include <libavutil/hwcontext.h>
}
namespace
ffmpeg_image_transport
{
using
Image
=
sensor_msgs
::
Image
;
using
ImagePtr
=
sensor_msgs
::
ImagePtr
;
using
ImageConstPtr
=
sensor_msgs
::
ImageConstPtr
;
using
FFMPEGPacket
=
ffmpeg_image_transport_msgs
::
FFMPEGPacket
;
typedef
std
::
unordered_map
<
int64_t
,
ros
::
Time
>
PTSMap
;
class
FFMPEGDecoder
{
public
:
typedef
boost
::
function
<
void
(
const
ImageConstPtr
&
img
,
bool
isKeyFrame
)
>
Callback
;
FFMPEGDecoder
();
~
FFMPEGDecoder
();
bool
isInitialized
()
const
{
return
(
codecContext_
!=
NULL
);
}
// Initialize decoder upon first packet received,
// providing callback to be called when frame is complete.
// You must still call decodePacket(msg) afterward!
bool
initialize
(
const
FFMPEGPacket
::
ConstPtr
&
msg
,
Callback
callback
,
const
std
::
string
&
codec
=
std
::
string
());
// clears all state, but leaves config intact
void
reset
();
// decode packet (may result in frame callback!)
bool
decodePacket
(
const
FFMPEGPacket
::
ConstPtr
&
msg
);
void
setMeasurePerformance
(
bool
p
)
{
measurePerformance_
=
p
;
}
void
printTimers
(
const
std
::
string
&
prefix
)
const
;
void
resetTimers
();
private
:
bool
initDecoder
(
int
width
,
int
height
,
const
std
::
string
&
codecName
,
const
std
::
vector
<
std
::
string
>
&
codec
);
// --------- variables
Callback
callback_
;
// mapping of header
PTSMap
ptsToStamp_
;
// performance analysis
bool
measurePerformance_
{
false
};
TDiff
tdiffTotal_
;
// libav stuff
std
::
string
encoding_
;
AVCodecContext
*
codecContext_
{
NULL
};
AVFrame
*
decodedFrame_
{
NULL
};
AVFrame
*
cpuFrame_
{
NULL
};
AVFrame
*
colorFrame_
{
NULL
};
SwsContext
*
swsContext_
{
NULL
};
std
::
unordered_map
<
std
::
string
,
std
::
vector
<
std
::
string
>>
codecMap_
;
enum
AVPixelFormat
hwPixFormat_
;
AVPacket
packet_
;
AVBufferRef
*
hwDeviceContext_
{
NULL
};
};
}
src/ffmpeg_image_transport/include/ffmpeg_image_transport/ffmpeg_encoder.h
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#pragma once
#include "ffmpeg_image_transport_msgs/FFMPEGPacket.h"
#include "ffmpeg_image_transport/tdiff.h"
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <opencv2/core/core.hpp>
#include <memory>
#include <list>
#include <iostream>
#include <unordered_map>
#include <mutex>
extern
"C"
{
#include <libavcodec/avcodec.h>
#include <libavformat/avio.h>
#include <libavformat/avformat.h>
#include <libswscale/swscale.h>
#include <libavutil/opt.h>
#include <libavutil/imgutils.h>
#include <libavutil/samplefmt.h>
}
namespace
ffmpeg_image_transport
{
using
Image
=
sensor_msgs
::
Image
;
using
ImagePtr
=
sensor_msgs
::
ImagePtr
;
using
ImageConstPtr
=
sensor_msgs
::
ImageConstPtr
;
typedef
std
::
unordered_map
<
int64_t
,
ros
::
Time
>
PTSMap
;
class
FFMPEGEncoder
{
using
FFMPEGPacket
=
ffmpeg_image_transport_msgs
::
FFMPEGPacket
;
using
FFMPEGPacketConstPtr
=
ffmpeg_image_transport_msgs
::
FFMPEGPacketConstPtr
;
typedef
std
::
unique_lock
<
std
::
recursive_mutex
>
Lock
;
typedef
boost
::
function
<
void
(
const
FFMPEGPacketConstPtr
&
pkt
)
>
Callback
;
public
:
FFMPEGEncoder
();
~
FFMPEGEncoder
();
// ------- various encoding settings
void
setCodec
(
const
std
::
string
&
n
)
{
Lock
lock
(
mutex_
);
codecName_
=
n
;
}
void
setProfile
(
const
std
::
string
&
p
)
{
Lock
lock
(
mutex_
);
profile_
=
p
;
}
void
setPreset
(
const
std
::
string
&
p
)
{
Lock
lock
(
mutex_
);
preset_
=
p
;
}
void
setQMax
(
int
q
)
{
Lock
lock
(
mutex_
);
qmax_
=
q
;
}
void
setBitRate
(
int
r
)
{
Lock
lock
(
mutex_
);
bitRate_
=
r
;
}
void
setGOPSize
(
int
g
)
{
Lock
lock
(
mutex_
);
GOPSize_
=
g
;
}
void
setFrameRate
(
int
frames
,
int
second
)
{
Lock
lock
(
mutex_
);
frameRate_
.
num
=
frames
;
frameRate_
.
den
=
second
;
timeBase_
.
num
=
second
;
timeBase_
.
den
=
frames
;
}
void
setMeasurePerformance
(
bool
p
)
{
Lock
lock
(
mutex_
);
measurePerformance_
=
p
;
}
// ------- teardown and startup
bool
isInitialized
()
const
{
Lock
lock
(
mutex_
);
return
(
codecContext_
!=
NULL
);
}
bool
initialize
(
int
width
,
int
height
,
Callback
callback
);
void
reset
();
// encode image
void
encodeImage
(
const
cv
::
Mat
&
img
,
const
std_msgs
::
Header
&
header
,
const
ros
::
WallTime
&
t0
);
void
encodeImage
(
const
sensor_msgs
::
Image
&
msg
);
// ------- performance statistics
void
printTimers
(
const
std
::
string
&
prefix
)
const
;
void
resetTimers
();
private
:
bool
openCodec
(
int
width
,
int
height
);
void
closeCodec
();
int
drainPacket
(
const
std_msgs
::
Header
&
hdr
,
int
width
,
int
height
);
// --------- variables
mutable
std
::
recursive_mutex
mutex_
;
boost
::
function
<
void
(
const
FFMPEGPacketConstPtr
&
pkt
)
>
callback_
;
// config
std
::
string
codecName_
;
std
::
string
preset_
;
std
::
string
profile_
;
AVPixelFormat
pixFormat_
{
AV_PIX_FMT_YUV420P
};
AVRational
timeBase_
{
1
,
10
};
AVRational
frameRate_
{
10
,
1
};
int
GOPSize_
{
15
};
int64_t
bitRate_
{
1000000
};
int
qmax_
{
0
};
// libav state
AVCodecContext
*
codecContext_
{
NULL
};
AVFrame
*
frame_
{
NULL
};
AVPacket
packet_
;
int64_t
pts_
{
0
};
PTSMap
ptsToStamp_
;
// performance analysis
bool
measurePerformance_
{
true
};
int64_t
totalInBytes_
{
0
};
int64_t
totalOutBytes_
{
0
};
unsigned
int
frameCnt_
{
0
};
TDiff
tdiffUncompress_
;
TDiff
tdiffEncode_
;
TDiff
tdiffDebayer_
;
TDiff
tdiffFrameCopy_
;
TDiff
tdiffSendFrame_
;
TDiff
tdiffReceivePacket_
;
TDiff
tdiffCopyOut_
;
TDiff
tdiffPublish_
;
TDiff
tdiffTotal_
;
};
}
src/ffmpeg_image_transport/include/ffmpeg_image_transport/ffmpeg_publisher.h
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#pragma once
#include "ffmpeg_image_transport_msgs/FFMPEGPacket.h"
#include "ffmpeg_image_transport/ffmpeg_encoder.h"
#include "ffmpeg_image_transport/EncoderDynConfig.h"
#include <image_transport/simple_publisher_plugin.h>
#include <dynamic_reconfigure/server.h>
#include <mutex>
#include <memory>
namespace
ffmpeg_image_transport
{
typedef
image_transport
::
SimplePublisherPlugin
<
ffmpeg_image_transport_msgs
::
FFMPEGPacket
>
FFMPEGPublisherPlugin
;
class
FFMPEGPublisher
:
public
FFMPEGPublisherPlugin
{
typedef
std
::
unique_lock
<
std
::
recursive_mutex
>
Lock
;
using
FFMPEGPacketConstPtr
=
ffmpeg_image_transport_msgs
::
FFMPEGPacketConstPtr
;
public
:
virtual
std
::
string
getTransportName
()
const
override
{
return
"ffmpeg"
;
}
void
configure
(
EncoderDynConfig
&
config
,
int
level
);
protected
:
// override to set up reconfigure server
virtual
void
advertiseImpl
(
ros
::
NodeHandle
&
nh
,
const
std
::
string
&
base_topic
,
uint32_t
queue_size
,
const
image_transport
::
SubscriberStatusCallback
&
user_connect_cb
,
const
image_transport
::
SubscriberStatusCallback
&
user_disconnect_cb
,
const
ros
::
VoidPtr
&
tracked_object
,
bool
latch
)
override
;
void
publish
(
const
sensor_msgs
::
Image
&
message
,
const
PublishFn
&
publish_fn
)
const
override
;
void
connectCallback
(
const
ros
::
SingleSubscriberPublisher
&
pub
)
override
;
void
disconnectCallback
(
const
ros
::
SingleSubscriberPublisher
&
pub
)
override
;
private
:
void
packetReady
(
const
FFMPEGPacketConstPtr
&
pkt
);
void
setCodecFromConfig
(
const
EncoderDynConfig
&
cfg
);
void
initConfigServer
();
// variables ---------
typedef
dynamic_reconfigure
::
Server
<
EncoderDynConfig
>
ConfigServer
;
std
::
shared_ptr
<
ros
::
NodeHandle
>
nh_
;
std
::
shared_ptr
<
ConfigServer
>
configServer_
;
const
PublishFn
*
publishFunction_
{
NULL
};
FFMPEGEncoder
encoder_
;
unsigned
int
frameCounter_
{
0
};
EncoderDynConfig
config_
;
std
::
recursive_mutex
configMutex_
;
};
}
src/ffmpeg_image_transport/include/ffmpeg_image_transport/ffmpeg_subscriber.h
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#pragma once
#include "ffmpeg_image_transport_msgs/FFMPEGPacket.h"
#include "ffmpeg_image_transport/ffmpeg_decoder.h"
#include <image_transport/simple_subscriber_plugin.h>
#include <sensor_msgs/Image.h>
#include <string>
namespace
ffmpeg_image_transport
{
using
Image
=
sensor_msgs
::
Image
;
using
ImagePtr
=
sensor_msgs
::
ImagePtr
;
using
ImageConstPtr
=
sensor_msgs
::
ImageConstPtr
;
typedef
image_transport
::
SimpleSubscriberPlugin
<
ffmpeg_image_transport_msgs
::
FFMPEGPacket
>
FFMPEGSubscriberPlugin
;
class
FFMPEGSubscriber
:
public
FFMPEGSubscriberPlugin
{
public
:
virtual
~
FFMPEGSubscriber
()
{}
virtual
std
::
string
getTransportName
()
const
{
return
"ffmpeg"
;
}
protected
:
virtual
void
internalCallback
(
const
typename
FFMPEGPacket
::
ConstPtr
&
message
,
const
Callback
&
user_cb
)
override
;
virtual
void
subscribeImpl
(
ros
::
NodeHandle
&
nh
,
const
std
::
string
&
base_topic
,
uint32_t
queue_size
,
const
Callback
&
callback
,
const
ros
::
VoidPtr
&
tracked_object
,
const
image_transport
::
TransportHints
&
transport_hints
)
override
;
private
:
void
frameReady
(
const
ImageConstPtr
&
img
,
bool
isKeyFrame
)
const
;
FFMPEGDecoder
decoder_
;
std
::
string
decoderType_
;
const
Callback
*
userCallback_
;
};
}
src/ffmpeg_image_transport/include/ffmpeg_image_transport/tdiff.h
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#pragma once
#include <iostream>
namespace
ffmpeg_image_transport
{
class
TDiff
{
public
:
friend
std
::
ostream
&
operator
<<
(
std
::
ostream
&
os
,
const
TDiff
&
td
);
inline
void
update
(
double
dt
)
{
duration_
+=
dt
;
cnt_
++
;
}
inline
void
reset
()
{
duration_
=
0
;
cnt_
=
0
;
}
private
:
int64_t
cnt_
{
0
};
double
duration_
{
0
};
};
std
::
ostream
&
operator
<<
(
std
::
ostream
&
os
,
const
TDiff
&
td
);
}
src/ffmpeg_image_transport/launch/h264.launch
0 → 100644
View file @
306aab5d
<launch>
<arg name="cam_idx0" default="0" />
<arg name="cam_idx1" default="1" />
<arg name="cam_idx2" default="2" />
<arg name="cam_idx3" default="3" />
<node pkg="image_transport"
type="republish"
name="h264_republish_$(arg cam_idx0)"
output="screen"
args="ffmpeg in:=/camera_array/cam$(arg cam_idx0)/image_raw
raw out:=/camera_array/cam$(arg cam_idx0)/h264_image _/ffmpeg/decoder_type:=h264">
</node>
<node pkg="image_transport"
type="republish"
name="h264_republish_$(arg cam_idx1)"
output="screen"
args="ffmpeg in:=/camera_array/cam$(arg cam_idx1)/image_raw
raw out:=/camera_array/cam$(arg cam_idx1)/h264_image _/ffmpeg/decoder_type:=h264">
</node>
<node pkg="image_transport"
type="republish"
name="h264_republish_$(arg cam_idx2)"
output="screen"
args="ffmpeg in:=/camera_array/cam$(arg cam_idx2)/image_raw
raw out:=/camera_array/cam$(arg cam_idx2)/h264_image _/ffmpeg/decoder_type:=h264">
</node>
<node pkg="image_transport"
type="republish"
name="h264_republish_$(arg cam_idx3)"
output="screen"
args="ffmpeg in:=/camera_array/cam$(arg cam_idx3)/image_raw
raw out:=/camera_array/cam$(arg cam_idx3)/h264_image _/ffmpeg/decoder_type:=h264">
</node>
</launch>
src/ffmpeg_image_transport/package.xml
0 → 100644
View file @
306aab5d
<?xml version="1.0"?>
<package
format=
"2"
>
<name>
ffmpeg_image_transport
</name>
<version>
1.0.0
</version>
<description>
ffmpeg compressed image transport for ros
</description>
<maintainer
email=
"bernd.pfrommer@gmail.com"
>
Bernd Pfrommer
</maintainer>
<license>
Apache
</license>
<buildtool_depend>
catkin
</buildtool_depend>
<depend>
roscpp
</depend>
<depend>
image_transport
</depend>
<depend>
sensor_msgs
</depend>
<depend>
ffmpeg_image_transport_msgs
</depend>
<depend>
opencv
</depend>
<depend>
cv_bridge
</depend>
<depend>
dynamic_reconfigure
</depend>
<export>
<image_transport
plugin=
"${prefix}/ffmpeg_plugins.xml"
/>
</export>
</package>
src/ffmpeg_image_transport/src/ffmpeg_decoder.cpp
0 → 100644
View file @
306aab5d
This diff is collapsed.
Click to expand it.
src/ffmpeg_image_transport/src/ffmpeg_encoder.cpp
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#include "ffmpeg_image_transport/ffmpeg_encoder.h"
#include "ffmpeg_image_transport_msgs/FFMPEGPacket.h"
#include <sensor_msgs/Image.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/imgcodecs.hpp>
#include <fstream>
#include <iomanip>
namespace
ffmpeg_image_transport
{
FFMPEGEncoder
::
FFMPEGEncoder
()
{
// must init the packet and set the pointers to zero
// in case a closeCodec() happens right away,
// and av_packet_unref() is called.
av_init_packet
(
&
packet_
);
packet_
.
data
=
NULL
;
// packet data will be allocated by the encoder
packet_
.
size
=
0
;
}
FFMPEGEncoder
::~
FFMPEGEncoder
()
{
Lock
lock
(
mutex_
);
closeCodec
();
}
void
FFMPEGEncoder
::
reset
()
{
Lock
lock
(
mutex_
);
closeCodec
();
}
void
FFMPEGEncoder
::
closeCodec
()
{
if
(
codecContext_
)
{
avcodec_close
(
codecContext_
);
codecContext_
=
NULL
;
}
if
(
frame_
)
{
av_free
(
frame_
);
frame_
=
0
;
}
if
(
packet_
.
data
!=
NULL
)
{
av_packet_unref
(
&
packet_
);
// free packet allocated by encoder
packet_
.
data
=
NULL
;
packet_
.
size
=
0
;
}
}
bool
FFMPEGEncoder
::
initialize
(
int
width
,
int
height
,
Callback
callback
)
{
Lock
lock
(
mutex_
);
callback_
=
callback
;
return
(
openCodec
(
width
,
height
));
}
bool
FFMPEGEncoder
::
openCodec
(
int
width
,
int
height
)
{
codecContext_
=
NULL
;
try
{
if
(
codecName_
.
empty
())
{
throw
(
std
::
runtime_error
(
"no codec set!"
));
}
if
((
width
%
32
)
!=
0
)
{
throw
(
std
::
runtime_error
(
"image line width must be "
"multiple of 32 but is: "
+
std
::
to_string
(
width
)));
}
// find codec
AVCodec
*
codec
=
avcodec_find_encoder_by_name
(
codecName_
.
c_str
());
if
(
!
codec
)
{
throw
(
std
::
runtime_error
(
"cannot find codec: "
+
codecName_
));
}
// allocate codec context
codecContext_
=
avcodec_alloc_context3
(
codec
);
if
(
!
codecContext_
)
{
throw
(
std
::
runtime_error
(
"cannot allocate codec context!"
));
}
codecContext_
->
bit_rate
=
bitRate_
;
codecContext_
->
qmax
=
qmax_
;
// 0: highest, 63: worst quality bound
codecContext_
->
width
=
width
;
codecContext_
->
height
=
height
;
codecContext_
->
time_base
=
timeBase_
;
codecContext_
->
framerate
=
frameRate_
;
// gop size is number of frames between keyframes
// small gop -> higher bandwidth, lower cpu consumption
codecContext_
->
gop_size
=
GOPSize_
;
// number of bidirectional frames (per group?).
// NVenc can only handle zero!
codecContext_
->
max_b_frames
=
0
;
// encoded pixel format. Must be supported by encoder
// check with e.g.: ffmpeg -h encoder=h264_nvenc -pix_fmts
codecContext_
->
pix_fmt
=
pixFormat_
;
if
(
av_opt_set
(
codecContext_
->
priv_data
,
"profile"
,
profile_
.
c_str
(),
AV_OPT_SEARCH_CHILDREN
)
!=
0
)
{
ROS_ERROR_STREAM
(
"cannot set profile: "
<<
profile_
);
}
if
(
av_opt_set
(
codecContext_
->
priv_data
,
"preset"
,
preset_
.
c_str
(),
AV_OPT_SEARCH_CHILDREN
)
!=
0
)
{
ROS_ERROR_STREAM
(
"cannot set preset: "
<<
preset_
);
}
ROS_DEBUG
(
"codec: %10s, profile: %10s, preset: %10s,"
" bit_rate: %10ld qmax: %2d"
,
codecName_
.
c_str
(),
profile_
.
c_str
(),
preset_
.
c_str
(),
bitRate_
,
qmax_
);
/* other optimization options for nvenc
if (av_opt_set_int(codecContext_->priv_data, "surfaces",
0, AV_OPT_SEARCH_CHILDREN) != 0) {
ROS_ERROR_STREAM("cannot set surfaces!");
}
*/
if
(
avcodec_open2
(
codecContext_
,
codec
,
NULL
)
<
0
)
{
throw
(
std
::
runtime_error
(
"cannot open codec!"
));
}
ROS_DEBUG_STREAM
(
"opened codec: "
<<
codecName_
);
frame_
=
av_frame_alloc
();
if
(
!
frame_
)
{
throw
(
std
::
runtime_error
(
"cannot alloc frame!"
));
}
frame_
->
width
=
width
;
frame_
->
height
=
height
;
frame_
->
format
=
codecContext_
->
pix_fmt
;
// allocate image for frame
if
(
av_image_alloc
(
frame_
->
data
,
frame_
->
linesize
,
width
,
height
,
(
AVPixelFormat
)
frame_
->
format
,
32
)
<
0
)
{
throw
(
std
::
runtime_error
(
"cannot alloc image!"
));
}
//Initialize packet
av_init_packet
(
&
packet_
);
packet_
.
data
=
NULL
;
// packet data will be allocated by the encoder
packet_
.
size
=
0
;
}
catch
(
const
std
::
runtime_error
&
e
)
{
ROS_ERROR_STREAM
(
e
.
what
());
if
(
codecContext_
)
{
avcodec_close
(
codecContext_
);
codecContext_
=
NULL
;
}
if
(
frame_
)
{
av_free
(
frame_
);
frame_
=
0
;
}
return
(
false
);
}
ROS_DEBUG_STREAM
(
"intialized codec "
<<
codecName_
<<
" for image: "
<<
width
<<
"x"
<<
height
);
return
(
true
);
}
void
FFMPEGEncoder
::
encodeImage
(
const
sensor_msgs
::
Image
&
msg
)
{
ros
::
WallTime
t0
;
if
(
measurePerformance_
)
{
t0
=
ros
::
WallTime
::
now
();
}
cv
::
Mat
img
=
cv_bridge
::
toCvCopy
(
msg
,
sensor_msgs
::
image_encodings
::
BGR8
)
->
image
;
encodeImage
(
img
,
msg
.
header
,
t0
);
if
(
measurePerformance_
)
{
const
auto
t1
=
ros
::
WallTime
::
now
();
tdiffDebayer_
.
update
((
t1
-
t0
).
toSec
());
}
}
void
FFMPEGEncoder
::
encodeImage
(
const
cv
::
Mat
&
img
,
const
std_msgs
::
Header
&
header
,
const
ros
::
WallTime
&
t0
)
{
Lock
lock
(
mutex_
);
ros
::
WallTime
t1
,
t2
,
t3
;
if
(
measurePerformance_
)
{
frameCnt_
++
;
t1
=
ros
::
WallTime
::
now
();
totalInBytes_
+=
img
.
cols
*
img
.
rows
;
// raw size!
}
const
uint8_t
*
p
=
img
.
data
;
const
int
width
=
img
.
cols
;
const
int
height
=
img
.
rows
;
const
AVPixelFormat
targetFmt
=
codecContext_
->
pix_fmt
;
if
(
targetFmt
==
AV_PIX_FMT_BGR0
)
{
memcpy
(
frame_
->
data
[
0
],
p
,
width
*
height
*
3
);
}
else
if
(
targetFmt
==
AV_PIX_FMT_YUV420P
)
{
cv
::
Mat
yuv
;
cv
::
cvtColor
(
img
,
yuv
,
cv
::
COLOR_BGR2YUV_I420
);
const
uint8_t
*
p
=
yuv
.
data
;
memcpy
(
frame_
->
data
[
0
],
p
,
width
*
height
);
memcpy
(
frame_
->
data
[
1
],
p
+
width
*
height
,
width
*
height
/
4
);
memcpy
(
frame_
->
data
[
2
],
p
+
width
*
(
height
+
height
/
4
),
(
width
*
height
)
/
4
);
}
else
{
ROS_ERROR_STREAM
(
"cannot convert format bgr8 -> "
<<
(
int
)
codecContext_
->
pix_fmt
);
return
;
}
if
(
measurePerformance_
)
{
t2
=
ros
::
WallTime
::
now
();
tdiffFrameCopy_
.
update
((
t2
-
t1
).
toSec
());
}
frame_
->
pts
=
pts_
++
;
//
ptsToStamp_
.
insert
(
PTSMap
::
value_type
(
frame_
->
pts
,
header
.
stamp
));
int
ret
=
avcodec_send_frame
(
codecContext_
,
frame_
);
if
(
measurePerformance_
)
{
t3
=
ros
::
WallTime
::
now
();
tdiffSendFrame_
.
update
((
t3
-
t2
).
toSec
());
}
// now drain all packets
while
(
ret
==
0
)
{
ret
=
drainPacket
(
header
,
width
,
height
);
}
if
(
measurePerformance_
)
{
const
ros
::
WallTime
t4
=
ros
::
WallTime
::
now
();
tdiffTotal_
.
update
((
t4
-
t0
).
toSec
());
}
}
int
FFMPEGEncoder
::
drainPacket
(
const
std_msgs
::
Header
&
header
,
int
width
,
int
height
)
{
ros
::
WallTime
t0
,
t1
,
t2
;
if
(
measurePerformance_
)
{
t0
=
ros
::
WallTime
::
now
();
}
int
ret
=
avcodec_receive_packet
(
codecContext_
,
&
packet_
);
if
(
measurePerformance_
)
{
t1
=
ros
::
WallTime
::
now
();
tdiffReceivePacket_
.
update
((
t1
-
t0
).
toSec
());
}
const
AVPacket
&
pk
=
packet_
;
if
(
ret
==
0
&&
packet_
.
size
>
0
)
{
FFMPEGPacket
*
packet
=
new
FFMPEGPacket
;
FFMPEGPacketConstPtr
pptr
(
packet
);
packet
->
data
.
resize
(
packet_
.
size
);
packet
->
img_width
=
width
;
packet
->
img_height
=
height
;
packet
->
pts
=
pk
.
pts
;
packet
->
flags
=
pk
.
flags
;
memcpy
(
&
(
packet
->
data
[
0
]),
packet_
.
data
,
packet_
.
size
);
if
(
measurePerformance_
)
{
t2
=
ros
::
WallTime
::
now
();
totalOutBytes_
+=
packet_
.
size
;
tdiffCopyOut_
.
update
((
t2
-
t1
).
toSec
());
}
packet
->
header
=
header
;
auto
it
=
ptsToStamp_
.
find
(
pk
.
pts
);
if
(
it
!=
ptsToStamp_
.
end
())
{
packet
->
header
.
stamp
=
it
->
second
;
packet
->
encoding
=
codecName_
;
callback_
(
pptr
);
// deliver packet callback
if
(
measurePerformance_
)
{
const
ros
::
WallTime
t3
=
ros
::
WallTime
::
now
();
tdiffPublish_
.
update
((
t3
-
t2
).
toSec
());
}
ptsToStamp_
.
erase
(
it
);
}
else
{
ROS_ERROR_STREAM
(
"pts "
<<
pk
.
pts
<<
" has no time stamp!"
);
}
av_packet_unref
(
&
packet_
);
// free packet allocated by encoder
av_init_packet
(
&
packet_
);
// prepare next one
}
return
(
ret
);
}
void
FFMPEGEncoder
::
printTimers
(
const
std
::
string
&
prefix
)
const
{
Lock
lock
(
mutex_
);
ROS_INFO_STREAM
(
prefix
<<
" pktsz: "
<<
totalOutBytes_
/
frameCnt_
<<
" compr: "
<<
totalInBytes_
/
(
double
)
totalOutBytes_
<<
" debay: "
<<
tdiffDebayer_
<<
" fmcp: "
<<
tdiffFrameCopy_
<<
" send: "
<<
tdiffSendFrame_
<<
" recv: "
<<
tdiffReceivePacket_
<<
" cout: "
<<
tdiffCopyOut_
<<
" publ: "
<<
tdiffPublish_
<<
" tot: "
<<
tdiffTotal_
);
}
void
FFMPEGEncoder
::
resetTimers
()
{
Lock
lock
(
mutex_
);
tdiffDebayer_
.
reset
();
tdiffFrameCopy_
.
reset
();
tdiffSendFrame_
.
reset
();
tdiffReceivePacket_
.
reset
();
tdiffCopyOut_
.
reset
();
tdiffPublish_
.
reset
();
tdiffTotal_
.
reset
();
frameCnt_
=
0
;
totalOutBytes_
=
0
;
totalInBytes_
=
0
;
}
}
// namespace
src/ffmpeg_image_transport/src/ffmpeg_publisher.cpp
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#include "ffmpeg_image_transport/ffmpeg_publisher.h"
#include <boost/algorithm/string/classification.hpp>
#include <boost/algorithm/string/split.hpp>
namespace
ffmpeg_image_transport
{
void
FFMPEGPublisher
::
packetReady
(
const
FFMPEGPacketConstPtr
&
pkt
)
{
(
*
publishFunction_
)(
*
pkt
);
}
static
bool
is_equal
(
const
EncoderDynConfig
&
a
,
const
EncoderDynConfig
&
b
)
{
return
(
a
.
encoder
==
b
.
encoder
&&
a
.
profile
==
b
.
profile
&&
a
.
qmax
==
b
.
qmax
&&
a
.
bit_rate
==
b
.
bit_rate
&&
a
.
gop_size
==
b
.
gop_size
&&
a
.
measure_performance
==
b
.
measure_performance
);
}
void
FFMPEGPublisher
::
configure
(
EncoderDynConfig
&
config
,
int
level
)
{
if
(
!
is_equal
(
config_
,
config
))
{
config_
=
config
;
setCodecFromConfig
(
config
);
encoder_
.
reset
();
// will be opened on next image
}
}
void
FFMPEGPublisher
::
advertiseImpl
(
ros
::
NodeHandle
&
nh
,
const
std
::
string
&
base_topic
,
uint32_t
queue_size
,
const
image_transport
::
SubscriberStatusCallback
&
conn_cb
,
const
image_transport
::
SubscriberStatusCallback
&
disconn_cb
,
const
ros
::
VoidPtr
&
tracked_object
,
bool
latch
)
{
const
std
::
string
transportTopic
=
getTopicToAdvertise
(
base_topic
);
nh_
.
reset
(
new
ros
::
NodeHandle
(
transportTopic
));
initConfigServer
();
// make the queue twice the size between keyframes.
queue_size
=
std
::
max
((
int
)
queue_size
,
2
*
config_
.
gop_size
);
FFMPEGPublisherPlugin
::
advertiseImpl
(
nh
,
base_topic
,
queue_size
,
conn_cb
,
disconn_cb
,
tracked_object
,
latch
);
}
void
FFMPEGPublisher
::
setCodecFromConfig
(
const
EncoderDynConfig
&
config
)
{
encoder_
.
setCodec
(
config
.
encoder
);
encoder_
.
setProfile
(
config
.
profile
);
encoder_
.
setPreset
(
config
.
preset
);
encoder_
.
setQMax
(
config
.
qmax
);
encoder_
.
setBitRate
(
config
.
bit_rate
);
encoder_
.
setFrameRate
(
config
.
frame_rate
,
1
);
encoder_
.
setGOPSize
(
config
.
gop_size
);
encoder_
.
setMeasurePerformance
(
config
.
measure_performance
);
ROS_DEBUG_STREAM
(
"FFMPEGPublisher codec: "
<<
config
.
encoder
<<
", profile: "
<<
config
.
profile
<<
", preset: "
<<
config
.
preset
<<
", bit rate: "
<<
config
.
bit_rate
<<
", qmax: "
<<
config
.
qmax
<<
", frame_rate: "
<<
config
.
frame_rate
);
}
void
FFMPEGPublisher
::
publish
(
const
sensor_msgs
::
Image
&
message
,
const
PublishFn
&
publish_fn
)
const
{
FFMPEGPublisher
*
me
=
const_cast
<
FFMPEGPublisher
*>
(
this
);
if
(
!
me
->
encoder_
.
isInitialized
())
{
me
->
initConfigServer
();
me
->
publishFunction_
=
&
publish_fn
;
if
(
!
me
->
encoder_
.
initialize
(
message
.
width
,
message
.
height
,
boost
::
bind
(
&
FFMPEGPublisher
::
packetReady
,
me
,
boost
::
placeholders
::
_1
)))
{
ROS_ERROR_STREAM
(
"cannot initialize encoder!"
);
return
;
}
}
me
->
encoder_
.
encodeImage
(
message
);
// may trigger packetReady() callback(s) from encoder!
Lock
lock
(
me
->
configMutex_
);
if
(
me
->
config_
.
measure_performance
)
{
if
(
++
me
->
frameCounter_
>
(
unsigned
int
)
me
->
config_
.
performance_interval
)
{
me
->
encoder_
.
printTimers
(
nh_
->
getNamespace
());
me
->
encoder_
.
resetTimers
();
me
->
frameCounter_
=
0
;
}
}
}
void
FFMPEGPublisher
::
initConfigServer
()
{
Lock
lock
(
configMutex_
);
if
(
!
configServer_
)
{
configServer_
.
reset
(
new
ConfigServer
(
*
nh_
));
// this will trigger an immediate callback!
configServer_
->
setCallback
(
boost
::
bind
(
&
FFMPEGPublisher
::
configure
,
this
,
boost
::
placeholders
::
_1
,
boost
::
placeholders
::
_2
));
}
}
void
FFMPEGPublisher
::
connectCallback
(
const
ros
::
SingleSubscriberPublisher
&
pub
)
{
ROS_DEBUG_STREAM
(
"FFMPEGPublisher: connect() now has subscribers: "
<<
getNumSubscribers
());
initConfigServer
();
}
void
FFMPEGPublisher
::
disconnectCallback
(
const
ros
::
SingleSubscriberPublisher
&
pub
)
{
ROS_DEBUG_STREAM
(
"FFMPEGPublisher: disconnect() subscribers left: "
<<
getNumSubscribers
());
}
}
src/ffmpeg_image_transport/src/ffmpeg_subscriber.cpp
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#include "ffmpeg_image_transport/ffmpeg_subscriber.h"
#include <cv_bridge/cv_bridge.h>
#include <opencv2/imgproc/imgproc.hpp>
namespace
ffmpeg_image_transport
{
void
FFMPEGSubscriber
::
frameReady
(
const
ImageConstPtr
&
img
,
bool
isKeyFrame
)
const
{
(
*
userCallback_
)(
img
);
}
void
FFMPEGSubscriber
::
subscribeImpl
(
ros
::
NodeHandle
&
nh
,
const
std
::
string
&
base_topic
,
uint32_t
queue_size
,
const
Callback
&
callback
,
const
ros
::
VoidPtr
&
tracked_object
,
const
image_transport
::
TransportHints
&
transport_hints
)
{
const
std
::
string
pname
=
ros
::
this_node
::
getName
()
+
"/ffmpeg/decoder_type"
;
nh
.
param
<
std
::
string
>
(
pname
,
decoderType_
,
""
);
// bump queue size a bit to avoid lost packets
queue_size
=
std
::
max
((
int
)
queue_size
,
20
);
FFMPEGSubscriberPlugin
::
subscribeImpl
(
nh
,
base_topic
,
queue_size
,
callback
,
tracked_object
,
transport_hints
);
}
void
FFMPEGSubscriber
::
internalCallback
(
const
FFMPEGPacket
::
ConstPtr
&
msg
,
const
Callback
&
user_cb
)
{
if
(
!
decoder_
.
isInitialized
())
{
if
(
msg
->
flags
==
0
)
{
return
;
// wait for key frame!
}
userCallback_
=
&
user_cb
;
if
(
!
decoder_
.
initialize
(
msg
,
boost
::
bind
(
&
FFMPEGSubscriber
::
frameReady
,
this
,
boost
::
placeholders
::
_1
,
boost
::
placeholders
::
_2
),
decoderType_
))
{
ROS_ERROR_STREAM
(
"cannot initialize decoder!"
);
return
;
}
}
decoder_
.
decodePacket
(
msg
);
}
}
src/ffmpeg_image_transport/src/manifest.cpp
0 → 100644
View file @
306aab5d
#include <pluginlib/class_list_macros.h>
#include "ffmpeg_image_transport/ffmpeg_publisher.h"
#include "ffmpeg_image_transport/ffmpeg_subscriber.h"
PLUGINLIB_EXPORT_CLASS
(
ffmpeg_image_transport
::
FFMPEGPublisher
,
image_transport
::
PublisherPlugin
)
PLUGINLIB_EXPORT_CLASS
(
ffmpeg_image_transport
::
FFMPEGSubscriber
,
image_transport
::
SubscriberPlugin
)
src/ffmpeg_image_transport/src/tdiff.cpp
0 → 100644
View file @
306aab5d
/* -*-c++-*--------------------------------------------------------------------
* 2018 Bernd Pfrommer bernd.pfrommer@gmail.com
*/
#include "ffmpeg_image_transport/tdiff.h"
#include <iomanip>
namespace
ffmpeg_image_transport
{
std
::
ostream
&
operator
<<
(
std
::
ostream
&
os
,
const
TDiff
&
td
)
{
os
<<
std
::
fixed
<<
std
::
setprecision
(
4
)
<<
td
.
duration_
*
(
td
.
cnt_
>
0
?
1.0
/
(
double
)
td
.
cnt_
:
0
);
return
os
;
}
}
// namespace
src/ffmpeg_image_transport_msgs/CMakeLists.txt
0 → 100644
View file @
306aab5d
cmake_minimum_required
(
VERSION 2.8
)
project
(
ffmpeg_image_transport_msgs
)
find_package
(
catkin REQUIRED COMPONENTS std_msgs message_generation
)
add_message_files
(
DIRECTORY msg FILES FFMPEGPacket.msg
)
generate_messages
(
DEPENDENCIES std_msgs
)
catkin_package
(
CATKIN_DEPENDS message_runtime std_msgs
)
src/ffmpeg_image_transport_msgs/msg/FFMPEGPacket.msg
0 → 100644
View file @
306aab5d
Header header # Original sensor_msgs/Image header
uint8[] data # ffmpeg compressed payload
int32 img_width # original image width
int32 img_height # original image height
string encoding # Specifies the encoding used
uint64 pts # packet pts
uint8 flags # packet flags
src/ffmpeg_image_transport_msgs/package.xml
0 → 100644
View file @
306aab5d
<?xml version="1.0"?>
<package
format=
"2"
>
<name>
ffmpeg_image_transport_msgs
</name>
<version>
1.0.0
</version>
<description>
messages for ffmpeg image transport plugin
</description>
<maintainer
email=
"bernd.pfrommer@gmail.com"
>
Bernd Pfrommer
</maintainer>
<license>
Apache
</license>
<buildtool_depend>
catkin
</buildtool_depend>
<build_depend>
message_generation
</build_depend>
<exec_depend>
message_runtime
</exec_depend>
<depend>
std_msgs
</depend>
</package>
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment