【ROS】画像圧縮によってフレームレートを向上させるパッケージの紹介

はじめに

大西です。トピックを介して画像を送る時にカメラから取得した時は30fpsなのに受け取ったら10fps切っていたという経験はありませんか?

この記事ではそれを改善するためのパッケージimage_transportの導入、使用方法を紹介し、パッケージの使用前と使用後を比較していきます。

 

image_transportについて

今回紹介するimage_transportはトピックに流れている画像を受け取り、新しいトピックにパブリッシュするパッケージです。そのプラグインに圧縮を挟むものがあるので今回はそのプラグインの紹介になります。

次にこれを行うメリットとデメリットについて説明します。

メリット

遠隔通信時のフレームレート向上です。ルータを通して別PCに画像を送った場合フレームレートが著しく下がります。画像を圧縮することでフレームレートを圧縮前と比べて数倍にすることが可能です。

デメリット

jpg圧縮を行った場合元の画像と比べて画質が落ちることです。画質低下によって画像認識を行う場合精度が低下してしまう可能性があります。

 

導入

今回使うパッケージimage_transportとそのプラグインを導入します。apt-getで入れることができます。

$sudo apt-get install ros-indigo-image-transport ros-indigo-image-transport-plugins

このパッケージはrosをインストールした際に入っている場合があります。

下のコマンドを打ちこのようになれば導入は出来ています。

$rosrun image_transport list_transports

Declared transports:
image_transport/compressed
image_transport/compressedDepth
image_transport/raw
image_transport/theora

Details:
———-
“image_transport/compressed”
– Provided by package: compressed_image_transport
– Publisher: This plugin publishes a CompressedImage using either JPEG or PNG compression.
– Subscriber: This plugin decompresses a CompressedImage topic.
———-
“image_transport/compressedDepth”
– Provided by package: compressed_depth_image_transport
– Publisher: This plugin publishes a compressed depth images using PNG compression.
– Subscriber: This plugin decodes a compressed depth images.
———-
“image_transport/raw”
– Provided by package: image_transport
– Publisher: This is the default publisher. It publishes the Image as-is on the base topic.
– Subscriber: This is the default pass-through subscriber for topics of type sensor_msgs/Image.
———-
“image_transport/theora”
– Provided by package: theora_image_transport
– Publisher: This plugin publishes a video packet stream encoded using Theora.
– Subscriber: This plugin decodes a video packet stream encoded using Theora.

 

使用方法

私はxtionPROLIVEを使ってやっています。とりあえずわかりやすいように出力するトピック名はcompressed_imageでやります。

$rosrun image_transport republish raw in:=[圧縮したい画像のトピック名] compressed out:=[圧縮後パブリッシュするトピック名]

$rosrun image_transport republish raw in:=/camera/rgb/image_raw compressed out:=/compressed_image

rostopic listをすると/compressed_image/compressedが追加されています。

これだけで圧縮することが可能です。

 

検証

圧縮前と圧縮後で比較してみます。

まずはメッセージの型から、rostopic typeで確認します。

$ rostopic type /camera/rgb/image_raw
sensor_msgs/Image

$ rostopic type /compressed/compressed
sensor_msgs/CompressedImage

このパッケージを使うと画像の接メージがsensor_msgs/Imageからsensor_msgs/CompressedImageに変わります。メッセージの詳細はrosmsg showで確認できます。

次に2つの画像の比較です。左が/camera/rgb/image_raw、右が/compressed_image/compressedです。rawcompressed

違いがあまりわからないですが拡大すると若干圧縮の方が粗いです。

次はデータサイズです。rostopic bwで確認します。

$ rostopic bw /camera/rgb/image_raw
subscribed to [/camera/rgb/image_raw]
average: 28.04MB/s
mean: 0.92MB min: 0.92MB max: 0.92MB window: 30
average: 27.83MB/s
mean: 0.92MB min: 0.92MB max: 0.92MB window: 60
average: 27.74MB/s
mean: 0.92MB min: 0.92MB max: 0.92MB window: 90

$ rostopic bw /compressed/compressed
subscribed to [/compressed/compressed]
average: 1.25MB/s
mean: 0.04MB min: 0.04MB max: 0.04MB window: 30
average: 1.24MB/s
mean: 0.04MB min: 0.04MB max: 0.04MB window: 60
average: 1.24MB/s
mean: 0.04MB min: 0.04MB max: 0.04MB window: 90

1枚0.92MBが0.04MBになっています。

さて最後はフレームレートです。まずはカメラを繋げているPCから、rostopic hzで確認します。

$rostopic hz /camera/rgb/image_raw
subscribed to [/camera/rgb/image_raw]
average rate: 29.874
min: 0.033s max: 0.034s std dev: 0.00042s window: 30
average rate: 29.854
min: 0.032s max: 0.035s std dev: 0.00054s window: 60
average rate: 29.846
min: 0.032s max: 0.035s std dev: 0.00059s window: 89

$rostopic hz /compressed/compressed
subscribed to [/compressed/compressed]
average rate: 29.852
min: 0.029s max: 0.036s std dev: 0.00140s window: 29
average rate: 29.825
min: 0.029s max: 0.036s std dev: 0.00107s window: 59
average rate: 29.840
min: 0.029s max: 0.036s std dev: 0.00117s window: 89

まぁ直接つなげているので変わりませんね。大体30fps出ています。

次は別PCからルータを通して繋げて確認してみます。

$ rostopic hz /camera/rgb/image_raw
subscribed to [/camera/rgb/image_raw]
average rate: 0.817
min: 1.224s max: 1.224s std dev: 0.00000s window: 2
no new messages
average rate: 0.704
min: 1.224s max: 1.616s std dev: 0.19570s window: 3
average rate: 0.703

$ rostopic hz /compressed_image/compressed
subscribed to [/compressed_image/compressed]
average rate: 12.395
min: 0.041s max: 0.116s std dev: 0.02012s window: 10
average rate: 10.265
min: 0.041s max: 0.134s std dev: 0.02487s window: 19
average rate: 10.061
min: 0.041s max: 0.134s std dev: 0.02200s window: 29

0.7fpsから10fpsくらいに上がってますね。しかしこれではまだ遅いと思いますので次はパラメータを変更して圧縮レベルを変える方法を紹介します。

 

パラメータの変更方法

まずは現在の圧縮形式と圧縮レベルの確認します。rosparam getを使います。

$ rosparam get /compressed_image/compressed/format
jpeg

$ rosparam get /compressed_image/compressed/jpeg_quality
80

jpeg圧縮で圧縮レベル80ですね。このパッケージはopencvを使って圧縮しているようなので圧縮レベルはjpegは1~100、pngは1~9です。

試しに圧縮レベルを50に変更します。

$ rosparam set /compressed_image/compressed/jpeg_quality 50

$ rosparam dump

 

確認します。

$ rosparam get /compressed_image/compressed/jpeg_quality
50

$ rostopic bw /compressed_image/compressed
subscribed to [/compressed_image/compressed]
average: 623.64KB/s
mean: 20.39KB min: 20.35KB max: 20.44KB window: 30
average: 617.39KB/s
mean: 20.39KB min: 20.35KB max: 20.44KB window: 60

$ rostopic hz /compressed_image/compressed
subscribed to [/compressed_image/compressed]
average rate: 26.342
min: 0.019s max: 0.056s std dev: 0.00978s window: 23
average rate: 26.492
min: 0.018s max: 0.063s std dev: 0.01002s window: 50

先ほど40KBほどだったサイズが20KBになっています.フレームレートも26fpsなのでかなり改善されました。

ここまで圧縮するとデメリットにも書いた画質低下が目に見えてわかります.左が圧縮前,右が圧縮レベル50です。

raw2compressed50

拡大すると粗さが目立ちます。

 

最後にpng圧縮にしたい場合はrosparamでformatをpngにするとpng圧縮になります。

 

動作環境

OS: Ubuntu 14.04 LTS

ROS: Indigo

 

参考:http://wiki.ros.org/compressed_image_transport

【ROS】画像圧縮によってフレームレートを向上させるパッケージの紹介」への5件のフィードバック

  1. はじめまして
    ROSで圧縮した画像を使おうと思って検索していたら、この記事に出会いました。

    容量を小さくするとCompressedの型になりますが、それを容量と
    が小さいままImageの型でpublishすることはできるのでしょうか。

    CompressedImageとImageの型におけるdataの関係性などお分かりでしたら、教えていただきたいです。

    1. コメントありがとうございます
      まずこの記事で紹介したパッケージではImage型のままpublishする機能はありません

      次に関係性ですがImage型には画像サイズがありますがCompressedImageにはそれがありません
      CompressedImage型はサイズの情報がないことからcv_bridgeで扱えなかったと思います

  2. はじめまして。
    カメラ画像をリモートで監視しながらturtlebotをジョイスティックで操作したいと思い、画像を圧縮する方法を探していたところ、この記事を見つけました。
    内容がとてもわかりやすく、簡単に画像圧縮をすることができたのですが、image_viewで画像を表示することができませんでした。どのようにカラー画像を表示させているのか、教えていただきたいです。

    1. コメントありがとうございます.
      私はrqt_image_viewを使用しております.
      これはguiでsensor_msgsのメッセージが流れているトピックを選択し,可視化するものです.
      以下のコマンドで実行できます.
      $rosrun rqt_image_view rqt_image_view

  3. 返信ありがとうございます。
    rqt_image_viewはとても使いやすくていいですね。
    コマンドまで教えていただいてありがとうございました。

コメントを残す

メールアドレスが公開されることはありません。 * が付いている欄は必須項目です

CAPTCHA