この記事はCyberAgent AI Lab Advent Calendar 2024の23日目の記事です。
はじめに
ROS 2にてマシン間もしくはコンテナ間で大きなデータを送受信するような構成の場合、送受信データサイズが大きいと遅延が生じたり、通信帯域を圧迫する恐れがあります。
そこで、ffmpeg_image_transportパッケージで画像データをエンコードすることで送受信のデータサイズを減らすことができます。このとき、エンコード処理は各種アクセラレーターの恩恵を受けられるため、エンコード処理のCPU使用率も抑制することができます。
本記事ではこのffmpeg_image_transportパッケージを紹介し、エンコード処理速度の効果検証を行います。また、従来から使われていたimage_transport(参考記事:ラズパイ上のROS2で圧縮した画像をPublishする #ubuntu20.04 - Qiita)とも結果を比較します。
ffmpeg_image_transportパッケージとは
ffmpeg_image_transportパッケージは、FFmpegを用いて動画像のエンコード・デコードを行うROS 2パッケージです。本パッケージはFFmpegを用いてエンコード処理を行っていることから手軽に各種ハードウェアアクセラレーターの恩恵を受けられます。
ソースコードはhttps://github.com/ros-misc-utilities/ffmpeg_image_transportで管理されており、以下のプラグインが実装されています。
- パブリッシャー (エンコーダー)
- サブスクライバー (デコーダー)
そのため、パブリッシャーとサブスクライバーが別マシン(もしくは別コンテナ)で動作する場合、別マシン(もしくは別コンテナ)それぞれffmpeg_image_transportパッケージのインストールが必要となる点に注意が必要です。※下図参照
メッセージ定義
ffmpeg_image_transportパッケージは、エンコード後の画像データをffmpeg_image_transport_msgs
のトピックとして配信します。ffmpeg_image_transport_msgs
のメッセージ定義は以下の通りです。
std_msgs/Header header
int32 width # original image width
int32 height # original image height
string encoding # encoding used
uint64 pts # packet pts
uint8 flags # packet flags
bool is_bigendian # true if machine stores in big endian format
uint8[] data # ffmpeg compressed payload
ffmpeg_image_transport_msgsに格納されるデータについて下表にまとめます。
名前 | 型 | 意味 |
---|---|---|
width | int32 | オリジナル画像の幅(ピクセル) |
height | int32 | オリジナル画像の高さ(ピクセル) |
encoding | string | コーデック名 |
pts | uint64 | Presentation timestamp in AVStream->time_base units https://ffmpeg.org/doxygen/3.2/structAVPacket.html参照 |
flags | uint8 | AV_PKT_FLAGのフラグ値 https://ffmpeg.org/doxygen/3.2/structAVPacket.html参照 |
is_bigendian | bool | データがビッグエンディアンか否か |
data | uint8[] | エンコード結果のペイロード |
ffmpeg_image_transport_msgsのメッセージ定義について詳細を知りたい方は下記URLを参照ください。
- https://docs.ros.org/en/jazzy/p/ffmpeg_image_transport_msgs/
- https://github.com/ros-misc-utilities/ffmpeg_image_transport_msgs
AVPacketのパケット仕様はhttps://ffmpeg.org/doxygen/3.2/structAVPacket.htmlを参照ください。
パラメータ
本章でffmpeg_image_transportパッケージのパラメータについて解説します。
FFMPEGEncoderパラメータ
FFMPEGEncoderのパラメータを下表に示します。
パラメータ | 意味 | 型 | デフォルト値 |
---|---|---|---|
encoding | コーデック名。指定できる値は後述。 | std::string | libx264 |
profile | プロファイル https://trac.ffmpeg.org/wiki/Encode/H.264#Profile参照 |
std::string | - |
preset | プリセット https://trac.ffmpeg.org/wiki/Encode/H.264#Preset参照 |
std::string | - |
tune | 動画の傾向 https://trac.ffmpeg.org/wiki/Encode/H.264#Tune参照 |
std::string | - |
delay | ディレイ | std::string | - |
crf | CRF(Constant Rate Factor)。エンコード品質を表す。https://trac.ffmpeg.org/wiki/Encode/H.264#a1.ChooseaCRFvalue参照 | std::string | - |
qmax | q値の最大値 | int | 10 |
bit_rate | The max bit rate [in bits/s] that the encoding will target. | int64_t | 8242880 |
gop_size | The number of frames inbetween keyframes. | int64_t | 15 |
pixel_format | ピクセルフォーマット https://ffmpeg.org/doxygen/5.0/pixfmt_8h.html#a9a8e335cf3be472042bc9f0cf80cd4c5参照 |
std::string | - |
encodingに指定できる値を下表にまとめました。
encoding値 | コーデック |
---|---|
libx264 | H.264(libx264) |
h264 | H.264(FFmpegのデフォルト設定) |
h264_nvenc | H.264(NVENC) https://trac.ffmpeg.org/wiki/HWAccelIntro#NVENC参照 |
h264_nvmpi | H.264(NVENC) Jetsonデバイス上で指定可能。詳細は後述。 |
h264_vaapi | H.264(VAAPI) https://trac.ffmpeg.org/wiki/Hardware/VAAPI#Encoding参照 |
hevc_nvenc | H.265(NVENC) https://trac.ffmpeg.org/wiki/HWAccelIntro#NVENC参照 |
FFMPEGSubscriberパラメータ
FFMPEGSubscriberのパラメータを下表に示します。
パラメータ | 意味 | 型 | デフォルト値 |
---|---|---|---|
measure_performance | デコード処理のパフォーマンス計測を行うか | bool | false |
FFMPEGPublisherパラメータ
FFMPEGPublisherのパラメータを下表に示します。
パラメータ | 意味 | 型 | デフォルト値 |
---|---|---|---|
measure_performance | エンコード処理のパフォーマンス計測を行うか | bool | false |
performance_interval | 何フレームごとにパフォーマンス計測を行うか | int | 175 |
インストール方法
本章でffmpeg_image_transportパッケージのインストール方法について説明します。大きく分けると以下の2通りあります。
- aptでインストール
- ソースビルド
aptでインストール
aptでインストールする場合は以下のコマンドを実行します。
sudo apt install ros-${ROS_DISTRO}-ffmpeg-image-transport
ソースビルド
ソースビルドする場合は以下のコマンドを実行します。特定バージョンのソースコードを使う場合、clone後にcheckoutを行ってください。
mkdir -p ~/dev_ws/src
cd ~/dev_ws/src
git clone https://github.com/ros-misc-utilities/ffmpeg_image_transport.git
cd ..
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
source ~/dev_ws/install/setup.bash
使い方
本章でffmpeg_image_transportパッケージの使い方について説明します。今回、以下の2パターンについて紹介します。
- USBカメラ
- Gazebo
USBカメラ
usb_camパッケージでビデオキャプチャするときにffmpeg_image_transportパッケージを使うサンプルはhttps://github.com/ros-misc-utilities/ffmpeg_image_transport/blob/master/launch/cam.launch.pyにあります。
Node(
package='usb_cam',
executable='usb_cam_node_exe',
output='screen',
name=node_name,
parameters=[
params_path,
{
'ffmpeg_image_transport.encoding': 'libx264',
'ffmpeg_image_transport.profile': 'main',
'ffmpeg_image_transport.preset': 'll',
'ffmpeg_image_transport.gop': 15,
},
],
)
ポイントとしてはusb_cam_node_exeノードを起動する際にffmpeg_image_transportパッケージのパラメータを指定している点です。
parameters=[
params_path,
{
'ffmpeg_image_transport.encoding': 'libx264',
'ffmpeg_image_transport.profile': 'main',
'ffmpeg_image_transport.preset': 'll',
'ffmpeg_image_transport.gop': 15,
},
],
Gazebo
補足的な位置付けですが、Gazebo(Gazebo Classic)上のカメラでffmpeg_image_transportパッケージを使う方法についても紹介します。パラメータ記述例を以下に示します。
camera_controller:
ros__parameters:
ffmpeg_image_transport:
encoding: h264_nvenc
エンコード処理速度の効果検証
本章でffmpeg_image_transportによるエンコード処理速度の効果を検証していきます。今回、オリジナル画像サイズのRGB画像を配信することとし、以下の3つについてメッセージサイズを確認します、
- Image(Raw Image)
- CompressedImage
- ffmpeg_image_transport_msgs
また、できるだけ条件を合わせるべく、Gazebo(Gazebo Classic)上で実験を行いました。
検証環境
名前 | バージョン、モデル名など |
---|---|
OS | Ubuntu 22.04 |
ROS 2ディストリビューション | Humble Hawksbill |
DDS | eProsima Fast DDS |
GPU | NVIDIA GeForce RTX 4070 |
NVIDIAドライババージョン | 560.94 |
今回、扱う画像データサイズが大きいためhttps://autowarefoundation.github.io/autoware-documentation/main/installation/additional-settings-for-developers/network-configuration/dds-settings/を参考にしてDDSチューニングを行っておきます。
計測方法
本記事では4K(3840x2160)サイズのRGB画像を扱うこととし、以下の3つのパターンについてメッセージサイズを計測します。
- image_transport(Raw Image)
- image_transport(CompressedImage)
- ffmpeg_image_transport(H.264)
メッセージサイズはros2 topic echo <topic_name> --no-arr
で確認し、dataのlengthを見ることとします。今回用いるffmpeg_image_transportパッケージのパラメータファイルは以下の通りです。
camera_controller:
ros__parameters:
ffmpeg_image_transport:
encoding: h264_nvenc
計測結果
メッセージサイズを下表にまとめます。ffmpeg_image_transportパッケージを使うことで画像データサイズを大きく減らすことができていることがわかります。
データ | メッセージサイズ |
---|---|
image_transport(Raw Image) | 24.88 MB |
image_transport(CompressedImage) | 0.20 MB |
ffmpeg_image_transport(H.264) | 2.714 KB |
詳細な計測結果は以下を参照ください。
image_transport(Raw Image)
$ ros2 topic echo /front_camera_sensor/image_raw --no-arr
《中略》
header:
stamp:
sec: 219
nanosec: 279000000
frame_id: camera_depth_link
height: 2160
width: 3840
encoding: rgb8
is_bigendian: 0
step: 11520
data: '<sequence type: uint8, length: 24883200>'
$ ros2 topic bw /front_camera_sensor/image_raw
《中略》
52.89 MB/s from 51 messages
Message size mean: 24.88 MB min: 24.88 MB max: 24.88 MB
image_transport(CompressedImage)
$ ros2 topic echo /front_camera_sensor/image_raw/compressed --no-arr
《中略》
header:
stamp:
sec: 283
nanosec: 945000000
frame_id: camera_depth_link
format: rgb8; jpeg compressed bgr8
data: '<sequence type: uint8, length: 196961>'
$ ros2 topic bw /front_camera_sensor/image_raw/compressed
《中略》
730.02 KB/s from 50 messages
Message size mean: 174.59 KB min: 157.67 KB max: 200.13 KB
ffmpeg_image_transport(H.264)
$ ros2 topic echo /front_camera_sensor/image_raw/ffmpeg --no-arr
《中略》
header:
stamp:
sec: 205
nanosec: 55000000
frame_id: camera_depth_link
width: 3840
height: 2160
encoding: h264_nvenc
pts: 53
flags: 0
is_bigendian: false
data: '<sequence type: uint8, length: 2714>'
$ ros2 topic bw /front_camera_sensor/image_raw/ffmpeg
《中略》
14.47 KB/s from 50 messages
Message size mean: 2.89 KB min: 0.89 KB max: 4.88 KB
その他
fffmpeg_image_transport_tools
前述の通り、ffmpeg_image_transportパッケージは、エンコード後の画像データをffmpeg_image_transport_msgs
のトピックとして配信します。そのため、rosbag2として記録すると、このメッセージ型で記録されることとなります。そのため、これまでよく使われていたsensor_msgs/msg/Image、sensor_msgs/msg/CompressedImageをサポートしていた従来のツールがそのまま使えないことになります。
このような不便さを解消するため、ffmpeg_image_transportに対応したユーティリティツールも開発されており、https://github.com/ros-misc-utilities/ffmpeg_image_transport_toolsで管理されています。
今回はaptでインストールすることにします。ソースビルドについては前述のリポジトリにあるREADMEを参照ください。
sudo apt install ros-${ROS_DISTRO}-ffmpeg-image-transport-tools
このパッケージは以下の機能を持っています。
- rosbag2(ffmpeg_image_transport_msgs)からmp4ファイルを生成
- rosbag2(ffmpeg_image_transport_msgs)から静止画ファイルを生成
以降、これらの機能について簡単に紹介します。
rosbag2(ffmpeg_image_transport_msgs)からmp4ファイルを生成
bag_to_fileツールでffmpeg_image_transport_msgs
のトピックが記録されたrosbag2ファイルからmp4ファイルを抽出することができます。実行コマンドを以下に示します。
bag_to_file -b input_bag -t topic -r rate [-o out_file] [-T timestamp_file] [-s start_time] [-e end_time]
このツールのオプションを下表にまとめます。
オプション | 意味 | 必須/オプション |
---|---|---|
b | 入力rosbag2ファイル | 必須 |
t | トピック名 | 必須 |
r | レート | 必須 |
o | 出力ファイル | オプション |
T | タイムスタンプファイル | オプション |
s | 開始タイムスタンプ | オプション |
e | 終了タイムスタンプ | オプション |
rosbag2(ffmpeg_image_transport_msgs)から静止画ファイルを生成
bag_to_framesツールでffmpeg_image_transport_msgs
のトピックが記録されたrosbag2ファイルからフレーム画像を抽出することができます。実行コマンドを以下に示します。
bag_to_frames -b input_bag -t topic [-o out_dir] [-d decoder][-T timestamp_file] [-s start_time] [-e end_time]
このツールのオプションを下表にまとめます。
オプション | 意味 | 必須/オプション |
---|---|---|
b | 入力rosbag2ファイル | 必須 |
t | トピック名 | 必須 |
o | 出力ファイル | オプション |
d | デコーダー | オプション |
T | タイムスタンプファイル | オプション |
s | 開始タイムスタンプ | オプション |
e | 終了タイムスタンプ | オプション |
タイムスタンプファイルの記述例は以下の通りです。
# packet no, pts, header_stamp recording_stamp
0 0 1710085154473057750 1710085156001866724
1 1 1710085155950467594 1710085156024209913
Jetsonデバイス上でffmpeg_image_transportを使う
本記事では扱いませんが、NVMPIをサポートするカスタムビルドをしたFFmpegを使うことにより、Jetsonデバイス上で効率的にエンコードを行うことができます。詳細はhttps://github.com/ros-misc-utilities/ffmpeg_image_transport/blob/master/README.md#how-to-use-ffmpeg-hardware-accelerated-encoding-on-the-nvidia-jetsonを参照ください。
おわりに
本記事ではffmpeg_image_transportパッケージを紹介し、エンコード処理速度の効果検証を行いました。効果的な画像データの配信、購読の選択肢の一つとして参考にして頂ければ幸いです。
参考URL
- https://docs.clearpathrobotics.com/docs/ros/config/camera_compression
- https://docs.clearpathrobotics.com/docs/ros/config/yaml/sensors/cameras/#ffmpeg-compression-settings
- https://autowarefoundation.github.io/autoware-documentation/main/installation/additional-settings-for-developers/network-configuration/dds-settings