0. はじめに
OpenCVのimencodeで画像圧縮して通信量を減らせるか確認しました。
Pythonのlaunch対応は、ROS2から正式対応だそうなので、Pythonで書くときは、image_transportが使えないためです※。
なお、画質が落ちることは避けたいため、PNG圧縮をするようにしています。
※私が使い方がわからなかっただけかもしれません
1. PCの設定と使用画像
使用するのは、Ubuntu22.04 LTSが入ったデスクトップPC(Publish側)とノートPC(Subscribe側)の2台のPCです。
なお、Dockerを使用して、ROSのnoetic環境を構築しました。
1.1. テスト環境
項目 | デスクトップPC | ノートPC |
---|---|---|
CPU | 12th Gen Intel® Core™ i7-12700 × 20 | Intel® Core™ i5-8200Y CPU @ 1.30GHz × 4 |
Memory | 32GB | 8GB |
GPU | GeForce RTX 3080 | -- |
OS | Ubuntu 22.04 LTS | Ubuntu 22.04 LTS |
Docker version | 23.0.3 | 23.0.3 |
ROS Image | ros:noetic | ros:noetic |
1.2. テスト画像
以下の画像をデスクトップPCからノートPCへ転送します。
画像は、デスクトップPCのホスト側の~/docker
ディレクトリに格納します。
一応、画像サイズは、4022x2272ピクセルで画像名は、DSC_0040.JPGです。
2. 環境構築
デスクトップもノートPCも同じイメージを使用します。
2.1. Dockerfile
FROM ros:noetic
ENV DEBIAN_FRONTEND=noninteractive
RUN apt-get update &&\
apt-get install -y vim byobu net-tools ros-noetic-rviz ros-noetic-libuvc-camera \
ros-noetic-camera-calibration ros-noetic-image-proc ros-noetic-image-transport \
ros-noetic-image-transport-plugins ros-noetic-rqt* \
ros-noetic-usb-cam ros-noetic-image-view &&\
rm -rf /var/lib/apt/lists/* /var/cache/apt/archives/*
RUN mkdir -p /work/catkin_ws/src
WORKDIR /work/catkin_ws
2.2. イメージの起動
$ docker build . -t wakaba/ros_noetic:latest
$ xhost +
$ docker run -it --net host -e DISPLAY=$DISPLAY -v ~/docker:/data -v /tmp/.X11-unix:/tmp/.X11-unix --device /dev/video0:/dev/video0:rw wakaba/ros_noetic:latest
3. 作成テストコード
使用するコードは、デスクトップ側で画像を送信するpubs.py
とその画像を受け取るノートPC側のsubs.py
の2つです。node
の変数の箇所を変更することで、無圧縮と圧縮の選択ができます。
3.1. デスクトップPC(Publish側)
$ vi /work/catkin_ws/src/pubs.py
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import time
def process_image():
node = "bgr8" # 圧縮なし
#node = "mono8" # PNG圧縮あり
try:
bridge = CvBridge()
buf = cv2.imread('/data/DSC_0040.JPG')
st = time.time()
if node == "bgr8":
img = buf
elif node == "mono8":
ret, img = cv2.imencode('.png', buf, (cv2.IMWRITE_PNG_COMPRESSION, 0))
et = time.time()
print(f"publish time: {(et - st)*1000:.3f}[ms]")
imgMsg = bridge.cv2_to_imgmsg(img, node)
pub = rospy.Publisher('image_color', Image, queue_size=10)
pub.publish(imgMsg)
except Exception as err:
print(err)
def start_node():
rospy.init_node('img_pub')
rospy.loginfo('img_pub node started')
rate = rospy.Rate(10)
while not rospy.is_shutdown():
process_image()
rate.sleep()
if __name__ == '__main__':
try:
start_node()
except rospy.ROSInterruptException:
pass
3.2. ノートPC(subscribe側)
$ vi /work/catkin_ws/src/subs.py
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import time
def process_image(msg):
node="bgr8" # 圧縮なし
#node="mono8" # PNG圧縮あり
try:
bridge = CvBridge()
buf = bridge.imgmsg_to_cv2(msg, node)
st = time.time()
if node=="bgr8":
img = buf
elif node=="mono8":
img = cv2.imdecode(buf, flags=cv2.IMREAD_COLOR)
et = time.time()
print(f"Subscrite time:{(et-st)*1000:.3f}[ms]")
gimg = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
cv2.imshow('image', gimg)
cv2.waitKey(3)
except Exception as err:
print(err)
def start_node():
rospy.init_node('img_sub')
rospy.loginfo('img_sub node started')
rospy.Subscriber("image_color", Image, process_image)
rospy.spin()
if __name__ == '__main__':
try:
start_node()
except rospy.ROSInterruptException:
pass
4. 実行方法
4.1. デスクトップ側実行
$ cd /work/catkin_ws
$ byobu
$ export ROS_IP=192.168.10.107 #デスクチップ側のIP
$ roscore
# F2キーで新しいターミナルを開く
$ export ROS_IP=192.168.10.107 #デスクチップ側のIP
$ catkin_make
$ source ./devel/setup.bash
$ python3 src/pubs.py
4.2. ノートPC側実行
$ cd /work/catkin_ws
$ byobu
$ export ROS_MASTER_URI=http://192.168.10.107:11311
$ export ROS_IP=192.168.10.103 #デスクチップ側のIP
$ catkin_make
$ source ./devel/setup.bash
$ python3 src/subs.py
5. テスト結果
デスクトップ側でシステムモニターを起動してキャプチャしました。
※計測時にYouTubeLive観てましたすみません。
5.1. 無圧縮
データ量は、92MIB/秒ぐらいになりました。
圧縮時間は、img=buf
だけなのでほぼ時間がかかっていません。
送信時間
publish time: 0.001[ms]
publish time: 0.001[ms]
publish time: 0.001[ms]
publish time: 0.001[ms]
publish time: 0.001[ms]
受信時間
Subscrite time:0.001[ms]
Subscrite time:0.001[ms]
Subscrite time:0.001[ms]
Subscrite time:0.001[ms]
Subscrite time:0.001[ms]
5.2. OpenCVのPNG圧縮ありの転送テスト
pubs.py
の下記の箇所を変更して、PNGの圧縮率を0と1で試しています。
1のほうが圧縮率が高くなりますが、処理が重くなります。
-- ret, img = cv2.imencode('.png', buf, (cv2.IMWRITE_PNG_COMPRESSION, 0))
++ ret, img = cv2.imencode('.png', buf, (cv2.IMWRITE_PNG_COMPRESSION, 1))
5.2.1 PNG C0
データ量は、55MIB/秒ぐらいになりました。
圧縮時間は、330msなので30fpsの映像だと処理が全然間に合いません。
送信時間
publish time: 327.669[ms]
publish time: 338.364[ms]
publish time: 340.852[ms]
publish time: 333.813[ms]
publish time: 328.946[ms]
受信時間
Subscrite time:208.821[ms]
Subscrite time:221.936[ms]
Subscrite time:210.942[ms]
Subscrite time:229.639[ms]
Subscrite time:209.893[ms]
5.2.2. PNG C1
データ量は、最大で25MIB/秒ぐらいになりました。
圧縮に時間がかかるため、通信が安定しませんでした。
圧縮率0と比較して、倍以上の時間がかかっています。
送信時間
publish time: 618.466[ms]
publish time: 624.905[ms]
publish time: 621.771[ms]
publish time: 618.531[ms]
publish time: 621.896[ms]
受信時間
Subscrite time:435.985[ms]
Subscrite time:419.349[ms]
Subscrite time:423.506[ms]
Subscrite time:421.045[ms]
Subscrite time:407.444[ms]
5.2.3. JPEG Q100
pubs.py
の以下の箇所を変更してJPEGでも試してみました。
処理は早くなり、データ量も減りましたが、JPEGなので転送先での画質が下がってしまいます。
ちょっとした表示のための転送には良いかもしれません。
-- ret, img = cv2.imencode('.png', buf, (cv2.IMWRITE_PNG_COMPRESSION, 0))
++ ret, img = cv2.imencode(".jpg", buf, (cv2.IMWRITE_JPEG_QUALITY, 100))
publish time: 46.659[ms]
publish time: 44.789[ms]
publish time: 44.969[ms]
publish time: 45.265[ms]
publish time: 45.355[ms]
Subscrite time:160.990[ms]
Subscrite time:162.591[ms]
Subscrite time:178.614[ms]
Subscrite time:162.128[ms]
Subscrite time:158.244[ms]
6. 終わりに
結論、ちゃんとC++で書いて、image_transportを使ったほうが良い。
次回は、image_transportを使った実験記事を書きたいと思います。
付録:PNGとJPEGの圧縮速度
今回は、ROSパッケージをインストールする際にインストールされるOpenCV4.2.0を使用しましたが、ビルドしたOpenCVだと圧縮処理が速くなるのか確認しました。バージョン違いますが、Host側にインストールしたBuild済のOpenCV4.5.5と比較しました。
OpenCV | ROS | Host |
---|---|---|
verison | 4.2.0 | 4.5.5 |
Build | なし | あり |
PNG圧縮時間 | 334 ms | 180 ms |
JPEG圧縮時間 | 45 ms | 33 ms |
速くはなりますが、やはり30FPS(33.333ms)には及ばずでした。
参考