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

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

realsense lidarで取得したdepth(深度)画像をrosbagでpng画像として保存する方法

depth(深度)画像をbagファイルに保存してから、pngの画像に変換して保存する方法。


目次
デモ:lidarでcolor画像をbagファイルに保存してjpegで保存
1. realsense-viewでbagファイルの作成
2. realsense-rosで点群/depth画像の表示
3. depth画像をbagファイルに保存
4. rqt_bagでbagファイルの確認
5. depth画像のbagファイルをpng画像で保存
6. オプションコマンド一覧



デモ:realsense lidarでcolor画像をbagファイルに保存してjpegで保存

まず手始めにrgb画像をbagファイルに保存した後に連番のファイル名でjpegで保存するのを、簡単にデモとしてやってみる。

保存する画像のtopic名は/camera/color/image_raw

このチュートリアルを参考にした。


#sudo apt-get install mjpegtools 

# lidar起動
$ roslaunch realsense2_camera rs_camera.launch

# 別のターミナルでbagファイルに保存
# rosbag record -O 保存先パス 保存するtopic名
$ rosbag record -O /home/usr/place/image_raw.bag /camera/color/image_raw
#### [ INFO] [1643679891.621513921]: Subscribing to /camera/color/image_raw
#### [ INFO] [1643679891.623323101]: Recording to '/home/usr/place/image_raw.bag'.
# bagファイルを連番でjpeg画像に変換して保存
$ roscore
$ roslaunch bag2image.launch

#### [ INFO] [1643680110.387830885]: Saved image /home/usr/place/images/frame0042.jpg#### [rosbag_play-1] process has finished cleanly


保存用launchファイル(bag2image.launch)

<?xml version="1.0"?>
<launch>
  <!-- default arg parameter --> 
  <arg name="bag_path" default="/home/usr/place/image_raw.bag" />
  <arg name="transform_topic" default="/camera/color/image_raw" />
  <arg name="output_path" default="/home/usr/place/images/frame%04d.jpg" />
  <!-- rosbag node name --> 
  <node pkg="rosbag" type="play" name="rosbag_play" args="$(arg bag_path)"/>
     
  <!-- reproduce image node -->
  <node name="extract" pkg="image_view" type="extract_images" respawn="false" output="screen">
      <remap from="image" to="$(arg transform_topic)"/>
      <param name="filename_format" value="$(arg output_path)"/>
  </node>
</launch>

 
f:id:trafalbad:20220202011601j:plain

topic名/camera/color/image_rawのrgb画像は保存できた。


以下からはdepth画像をbagファイルから、pngの imageに変換する。
上と同じやり方でやると、

Couldn't save image, no data!
Unable to convert 16UC1 image to bgr8

とエラーが出て変換できないので、別のやり方で保存する。



1. realsense-viewでbagファイルの作成

realsense-viewコマンドでbagファイルを作る。
realsense-viewを起動。

右上のアイコンから保存先パスを指定。

f:id:trafalbad:20220202011632j:plain

「Record」ボタンを押す。
stopを押すとフォルダにbagファイルができてる。

realsense-viewだと全部のtopicが選択できる。

f:id:trafalbad:20220202011617j:plain



2. realsense-rosで点群/depth画像の表示

# lidar起動
# roslaunch realsense2_camera rs_camera.launch filters :=pointcloud
# rvizは勝手に起動するので、pointcloud2を選択する
roslaunch realsense2_camera demo_pointcloud.launch

pointcloud(点群)f:id:trafalbad:20220202011647j:plain

roslaunch realsense2_camera rs_camera.launch
# 画像表示
rosrun image_view image_view image:=/camera/depth/image_rect_raw

depth画像f:id:trafalbad:20220202194437j:plain


点群画像、depth画像のどっちもちゃんと表示できた。

点群画像のtopic名/camera/depth/color/points

depth画像のtopic名/camera/depth/image_rect_raw


3. depth画像をbagファイルに保存

depth画像からpcdを作るためには、rgb画像も一緒に保存しなきゃならないので、depth画像とrgb画像の両方のtopicを保存。

# realsense lidarを起動
$ roslaunch realsense2_camera rs_camera.launch

# もう一個のターミナルでbagファイルに保存
# rosbag record -O 保存先bagファイルパス 保存するtopic名1 保存するtopic名2
$ rosbag record -O /home/parallels/place/depth.bag /camera/color/image_raw /camera/depth/image_rect_raw
### [ INFO] [1647418306.286532131]: Subscribing to /camera/color/image_raw
### [ INFO] [1647418306.289360248]: Subscribing to /camera/depth/image_rect_raw
### [ INFO] [1647418306.291541263]: Recording to '/home/parallels/place/depth.bag'


4. rqt_bagでbagファイルの確認

ROSのツールで本格的にbagファイルをGUIで確認できる

# rosrun rqt_bag rqt_bag bagfileのパス
roscore
rosrun rqt_bag rqt_bag depth.bag


5. depth画像のbagファイルをpng画像で保存

pythonで保存してみる。

topic名
RGB画像:/camera/color/image_raw
depth画像:/camera/depth/image_rect_raw

depth画像とそのRGB画像の両方とdepth画像を色付けした(jetcolor)画像を保存した。

変換スクリプト(bag2image.py)

#!/usr/bin/env python3

import os
import argparse
import cv2
import numpy as np
import rosbag
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
H = 480
W = 640
def main():
    parser = argparse.ArgumentParser()
    parser.add_argument('--bag_file', type=str, default="/home/parallels/place/depth.bag")
    parser.add_argument('--depth_topic', type=str, default="/camera/depth/image_rect_raw")
    parser.add_argument('--image_topic', type=str, default="/camera/color/image_raw")
    parser.add_argument('--output_path', type=str, default="/home/parallels/place")
    args = parser.parse_args()

    out_rgb_dir = os.path.join(args.output_path, "rgb")
    out_dep_dir = os.path.join(args.output_path, "depth")
    out_jet_dir = os.path.join(args.output_path, "jet")
    if not os.path.isdir(out_rgb_dir):
        os.makedirs(out_rgb_dir)
    if not os.path.isdir(out_dep_dir):
        os.makedirs(out_dep_dir)
    if not os.path.isdir(out_jet_dir):
        os.makedirs(out_jet_dir)
    rgb_topic = args.image_topic
    depth_topic = args.depth_topic

    bag = rosbag.Bag(args.bag_file, "r")
    topics = bag.get_type_and_topic_info()[1].keys()
    bridge = CvBridge()
    count = 0
    for topic, msg, t in bag.read_messages(topics=[rgb_topic, depth_topic]):
        if topic==rgb_topic:
            cvimg = bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
            cvimg = cv2.resize(cvimg, (W, H), interpolation=cv2.INTER_NEAREST)
            cv2.imwrite(os.path.join(out_rgb_dir, "frame%06i.jpg" % count), cvimg)
            print('rgb', cvimg.shape, cvimg.max(), cvimg.min())
        elif topic==depth_topic:
            cvimg = bridge.imgmsg_to_cv2(msg, desired_encoding='passthrough')
            cvimg = cv2.resize(cvimg, (W, H), interpolation=cv2.INTER_NEAREST)
            cv2.imwrite(os.path.join(out_dep_dir, "frame%06i.png" % count), cvimg)
            
            jet_img = cv2.applyColorMap(cv2.convertScaleAbs(cvimg, alpha=0.08), cv2.COLORMAP_JET)
            cv2.imwrite(os.path.join(out_jet_dir, "frame%06i.png" % count), jet_img)
            print('depth', cvimg.shape, cvimg.max(), cvimg.min())
        print("Wrote image %i" % count)
        count += 1

    bag.close()

    return

if __name__ == '__main__':
    main()

カラーマップ/depth画像/JetColor画像

f:id:trafalbad:20220316183715p:plain

0〜255で正規化されるので、どうやらこれがdepth画像とそのカラーマップで間違いない。



6. オプションコマンド一覧

# 全topicを bagファイルに保存。メモリが足らなくなるのでおすすめしない
$ rosbag record -a 

# コマンドライン上でbagファイルを再生
$ rosbag play ファイル名.bag

# bagファイルの情報(topicとか時刻)を確認
$  rosbag info ファイル名.bag

# 2倍速で再生
$ rosbag play ファイル名.bag -r 2.0 --clock

# -lでループ再生
$ rosbag play ファイル名.bag -l

参考サイト

D435からの画像をrvizで表示させる
How to export image and video data from a bag file
ROS】Ubuntu16.04+ROS kinetic環境におけるRealsense D415を使った点群表示
bag_to_png.py