アプリとサービスのすすめ

アプリやIT系のサービスを中心に書いていきます。たまに副業やビジネス関係の情報なども気ままにつづります

ROSで画像を圧縮してJetsonからホストPCへ遠隔で送信

画像を圧縮してJetson側からホストPCに送信して保存してみた。
そのとき圧縮効果でどれだけ速度が上がったのかを、webカメラとlidarの両方で調べてみたのでその備忘録。

結果からいうと、web(USB)カメラとLidar両方で、速度向上の効果があった。


ちなみに圧縮画像のtopic名は〜/image_raw/compressedとcompressedがついてるやつで、
opencvとrvizのlaunchファイルで直接取得する方法もある。


環境
Ubuntu 20.04
ROS : noetic
Jetson nano(JetPack 4.3)


目次
1. Jetsonでusbカメラのセットアップ
2. launchファイル(xml)の文法
3. USBカメラ画像を圧縮してJetsonからPCへ送信
4. Lidarへの画像圧縮の効果
5. 参考サイト


1. Jetsonでusbカメラのセットアップ

# usbカメラに必要なドライバのインストール
$ sudo apt install ros-melodic-usb-cam
$ sudo apt install ros-melodic-image-view

# usb_camのlaunchファイルをwork spaceのlaunchフォルダにコピー
$ sudo cp /opt/ros/melodic/share/usb_cam/launch/usb_cam-test.launch launch/usb_cam.launch
# jetsonがUSBカメラを認識してるか確認
$ ls /dev/video*
#### /dev/video0
# 試しに起動
$ rosrun usb_cam usb_cam_node

# または$ roslaunch ros_start usb_cam.launch でもいい
# カメラのポートを指定する場合はlaunchファイルを書き換える


f:id:trafalbad:20220129201134j:plain

JetsonでUSBカメラ画像を表示できた。


2. launchファイル(xml)の文法

launchファイルでよく使われるタグについて

groupタグ



xmlを細かくまとめる役割(特に意味ない)

nodeタグ



ノード内でのやり取りを記述する


remapタグ



ROSトピックの名前を変更する。

<node>
<remap from='chatter', to='content'/>
</node>


ROSのトピック名が'chatter'から'content'に変わる。
いまいち分かりにくいので、使いながら直感的に覚えた方がいいかも。

argタグ



launchファイルを起動するときの引数。指定できるのは
・論理型(bool値)
・数値型(double)
・文字列(String)



ifとunlessを使った条件分岐


もしname='mode'の条件があるとき

・if ならmode=='mode'と同じ
・unless ならmode!='mode'と同じ

** 'default'を書いてないとエラーになる。

<launch>
<!-- 'default'がないとエラーになる -->
<arg name='mode', default='true'>
<!-- 'mode'のとき-->
<group if='$(arg mode)'>
〜ノード処理
</group>
<!-- 'mode'でないとき-->
<group unless="$(arg mode)">
〜ノード処理
</group>
</launch>
# ROSノードが起動する
$ roalaunch 〜 〜.launch 
# ROSノードが起動しない
$ roalaunch 〜 〜.launch mode:=false

evalを使った条件分岐



Pythonでいうif, elifの関係

<launch>
<arg name='mode' default='mode0'>
<group if="(eval mode=='mode0' or mode=='mode1')">
〜nodeの処理
</group>
</launch>
# ROSノードが起動する
$ roalaunch 〜 〜.launch mode:=mode0
$ roalaunch 〜 〜.launch mode:=mode1
# ROSノードが起動しない
$ roalaunch 〜 〜.launch mode:=mode2

paramタグ


paramはlaunchファイル起動時にROSノードに値を渡すことができる機能で、launchファイルに渡す値を記述する。


basic_param_talker.cpp

#include <ros/ros.h>
#include <std_msgs/String.h>
#include <string>

int main(int argc, char** argv)
{
ros::init(argc, argv, "basic_param_talker");
ros::NodeHandle nh;
ros::NodeHandle pnh("~");
ros::Publisher chatter_pub = nh.advertise<std_msgs::String>("chatter", 10);
std::string msg_chatter = "hello world!";
pnh.getParam("content", msg_chatter);

ros::Rate loop_rate(10);
while (ros::ok())
{
 std_msgs::String msg;
 msg.data = msg_chatter;
 ROS_INFO("%s", msg.data.c_str());
 chatter_pub.publish(msg);

 ros::spinOnce();
 loop_rate.sleep();
}
return 0;
}


・8行目で、roslaunchからパラメータの値をros::NodeHandle pnh("~"); で受け取る。

・10行目に値を受け取る変数を定義。

・11行目のpn.getParam("content",msg_chatter);はcontentという名前を受けて、その値をmsg_chatterに代入するという関数

launchファイル(launch_param.launch)

<launch>
<node name="basic_param_talker"   pkg="basic_lecture" type="basic_param_talker" >
 <param name="content" value="alternative hello"/>
</node>
<node name="basic_simple_listener" pkg="basic_lecture" type="basic_simple_listener" output="screen"/>
</launch>
$ roslaunch basic_lecture launch_param.launch 
#### [ INFO] [1554469390.298268118]: I heard: [alternative hello]
#### [ INFO] [1554469390.399493784]: I heard:[alternative hello]


3. USBカメラ画像を圧縮してJetsonからPCへ送信

# PC側でも同じようなセットアップをする。画像圧縮用ライブラリをinstall
$ sudo apt-get install -y ros-noetic-image-transport
$ sudo apt-get install -y ros-noetic-image-transport-plugins
# usb_camのlaunchファイルをwork spaceのlaunchフォルダにコピー
$ sudo cp /opt/ros/melodic/share/usb_cam/launch/usb_cam-test.launch launch/usb_cam.launch

USB画像圧縮用launchファイル(image_republish.launch)

<?xml version="1.0"?>
<launch>
  <!-- default arg parameter --> 
  <arg name="use_compressed" default="false" />

  <!-- compressed transport image --> 
  <group if="$(arg use_compressed)">
    <node name="image_republish" pkg="image_transport" type="republish" args="compressed raw">
      <!-- input topic name -->
	    <remap from="in" to="/usb_cam/image_raw"/>
      <!-- output topic name -->
      <remap from="out" to="/image_exp" />
    </node>
    <node name="image_view" pkg="image_view" type="image_view" >
      <!-- output topic name -->
      <remap from="image" to="/image_exp"/>
    </node>
  </group>
  <!-- normal transport image --> 
  <group unless="$(arg use_compressed)">
    <node name="image_view" pkg="image_view" type="image_view" >
      <!-- input topic name -->
	    <remap from="image" to="/usb_cam/image_raw"/>
    </node>
  </group>
</launch>


USB画像取得用pythonスクリプト(color_vel.py)

#!/usr/bin/env python3
import rospy
import cv2
import time
import numpy as np
from sensor_msgs.msg import Image
from geometry_msgs.msg import Twist
from cv_bridge import CvBridge, CvBridgeError
#from memory_profiler import profile

path = '/home/usr/place/images/img{}.png'
LIDAR_NODE_NAME = '/usb_cam/image_raw'
_bridge = CvBridge()
c = _time = 0

def start_node():
    rospy.init_node('color_extract')
    _image_sub = rospy.Subscriber(LIDAR_NODE_NAME, Image, callback)

def get_colored_area(cv_image, lower, upper):
    hsv_image = cv2.cvtColor(cv_image, cv2.COLOR_BGR2HSV)
    mask_image = cv2.inRange(hsv_image, lower, upper)
    area = cv2.countNonZero(mask_image)
    return area

#@profile 
def callback(data):
    global c, _time
    now = time.time()
    try:
        cv_image = _bridge.imgmsg_to_cv2(data, 'bgr8')

    except CvBridgeError as e:
        print(e)
    print('cost time is ', (time.time()-now)*1000, '[ms]')
    _time += (time.time()-now)*1000
    c += 1
    blue_area = get_colored_area(
            cv_image, np.array([50,100,100]), np.array([150,255,255]))
    
    #rospy.loginfo('blue=%d, red=%d' % (blue_area, red_area))
    cv2.imwrite(path.format(str(blue_area)), cv_image.astype(np.uint8))
    if c==30:
        print('total time is', _time)
        c=0
        _time = 0

if __name__ == '__main__':
    start_node()
    try:
        rospy.spin()
    except KeyboardInterrupt:
        pass

圧縮してホストPCに送信してみる

# Jetson側での操作
$ export ROS_MASTER_URI=http://192.168.10.111:11311
$ export ROS_IP=192.168.10.102
# webカメラを起動
$ rosrun usb_cam usb_cam_node # ($ roslaunch ros_start usb_cam.launch)
# ホストPC側で操作
$ export ROS_MASTER_URI=http://192.168.10.111:11311
$ export ROS_IP=192.168.10.111

# 圧縮して送信
$ roscore
$ roslaunch ros_start image_republish.launch use_compressed:=true
$ rosrun ros_start color_vel.py
# 圧縮しないで送信
$ roslaunch ros_start image_republish.launch

結果

  
30枚の合計処理時間(USBカメラ画像への圧縮効果)Latency
圧縮した場合 15.2616 [ms]
圧縮しない場合 20.4401 [ms]



4. Lidarへの画像圧縮の効果

# lidarが認識されてるか調べる
$ ls /dev/video*
#### /dev/video0  /dev/video1  /dev/video2  /dev/video3


4つもLidar用のデバイスがある。
通常画像、距離画像、センサーデータをとる多機能カメラだからかも。


Lidar用の画像圧縮用launchファイル(image_republish.launch)
Remapタグの/usb_cam/image_raw/camera/color/image_rawに変えただけ。

 <remap from="image" to="/camera/color/image_raw"/>


color_vel.py
こちらもSubscriberのノード名を/usb_cam/image_raw/camera/color/image_rawに変えただけ。

path = '/home/usr/place/images/img{}.png'
LIDAR_NODE_NAME = '/camera/color/image_raw'
_bridge = CvBridge()

圧縮して通信

# Jetson側の操作
# lidar起動
$ roslaunch realsense2_camera rs_camera.launch

# PC側の操作
$ roscore
$ rosrun ros_start color_vel.py
$ roslaunch ros_start image_republish.launch use_compressed:=true

  
30枚の合計処理時間(Lidar画像への圧縮効果)Latency
圧縮した場合 29.2716 [ms]
圧縮しない場合 32.3560 [ms]

少しは速くなる程度の結果に。
ノーマル画像だけ圧縮してもLidarにはあまり速度向上の効果はない結果になった。

5. 参考サイト

ROS講座57 カメラ画像を圧縮して送信
wifi経由でトピック通信する時、画像データは圧縮して扱った方が良さそう
ROS講座19 roslaunch2
ROSの勉強 第40弾:USBカメラ