🎥

カメラからEVS(Event-based Vision Sensor)風画像を作ってみた1

2023/09/13に公開

最近、注目度の高いイベントカメラについて興味があり、RGBカメラからイベントカメラ風の画像を作成できないかと、考え作ってみようと思いました。

関連記事としては以下を参考にさせて頂きました。

今回作成したいもの

  • ros2を使用し、RGBカメラからリアルタイムでイベントカメラ風の画像を作成する
  • イベントデータを出力する
  • イベントデータから画像再生成する

環境

  • Ubuntu 22.04
  • ROS2 humble

開発

1. depthAIを使用して画像をリアルタイムにsubscribeする

使用したカメラはOAK-D Lite で、ドライバーはこちらです

まずは、ROS2でdepthAIを起動します

ターミナル
$ mkdir catkin_ws/src -p #our workspace
$ cd catkin_ws/src
$ git clone https://github.com/luxonis/depthai-ros.git
$ cd ..
$ colcon build
$ source install/setup.bash
$ ros2 launch depthai_examples mobile_publisher.launch.py camera_model:=OAK-D-LITE

2. カメラ画像をsubscribeして画像処理をする

やることは

  • カメラ画像をsubscribe
  • グレースケールに変換
  • 変換した画像の差分の画像を出力
  • イベント型のデータ(カスタムメッセージ)としても出力
コード
c++コード
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "event_style_msgs/msg/event.hpp"
#include "event_style_msgs/msg/event_array.hpp"
#include "cv_bridge/cv_bridge.h"
#include <opencv2/imgproc/imgproc.hpp>

using namespace std::chrono_literals;
using std::placeholders::_1;

class ConvertEventStyle : public rclcpp::Node
{
    public:
    ConvertEventStyle() : Node("convert_image_to_event_style")
    {
        publisher_event = this->create_publisher<event_style_msgs::msg::EventArray>("/event", 10);
        publisher_image = this->create_publisher<sensor_msgs::msg::Image>("/event_style_image", 10);
        subscription_ = this->create_subscription<sensor_msgs::msg::Image>("/color/image", 10, std::bind(&ConvertEventStyle::processImage, this, _1));
    }

    private:
    rclcpp::Publisher<event_style_msgs::msg::EventArray>::SharedPtr publisher_event;
    rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_image;
    rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr subscription_;
    
    cv::Mat prev_frame;
    cv::Mat current_frame;

    // 画像データを2つ取得して、輝度変換し、差分をとってイベントで出力する
    void processImage(const sensor_msgs::msg::Image::ConstPtr image_msg)
    {
        cv_bridge::CvImagePtr cv_image;
        cv_image = cv_bridge::toCvCopy(image_msg, image_msg->encoding);

        // 画像をグレースケールに変換
        cv::Mat gray_image;
        cv::cvtColor(cv_image->image, gray_image, cv::COLOR_BGR2GRAY);

        // フレームの差を格納する
        cv::Mat diff;
        // イベントにする輝度差の閾値
        int threshold = 10;

        // 画像のサイズを取得
        size_t height = cv_image->image.rows;
        size_t width = cv_image->image.cols;

        if (prev_frame.empty()) {
            prev_frame = gray_image;
        } else {
            // EventArray.msgを設定
            event_style_msgs::msg::EventArray event_array;
            event_array.header = image_msg->header;
            event_array.height = height;
            event_array.width = width;
            // 
            current_frame = gray_image;

            cv::subtract(current_frame, prev_frame, diff);

            for (int y = 0; y < height; ++y) {
                for (int x = 0; x < width; ++x) {
                    event_style_msgs::msg::Event event;
                    int value = diff.at<int>(y, x);
                    if (value > threshold) {
                        event.x = x;
                        event.y = y;
                        event.time = this->get_clock()->now();
                        event.polarity = 1;
                        event_array.events.push_back(event);
                    } else if (value < threshold) {
                        event.x = x;
                        event.y = y;
                        event.time = this->get_clock()->now();
                        event.polarity = 0;
                        event_array.events.push_back(event);
                    }
                }
            }
            publisher_event->publish(event_array);
            cv::absdiff(current_frame, prev_frame, diff);
            prev_frame = current_frame;
        }
        // BGR画像をsensor_msgs::msg::Imageに変換してパブリッシュ
        sensor_msgs::msg::Image::SharedPtr pub_image = cv_bridge::CvImage(std_msgs::msg::Header(), "mono8", diff).toImageMsg();
        publisher_image->publish(*pub_image);
    }
};

int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<ConvertEventStyle>());
    rclcpp::shutdown();
    return 0;
}
event.msg
# event msg
uint16 x
uint16 y
builtin_interfaces/Time time
bool polarity

起動時

表示されているイベントカメラ風の動画はdepthAIの画像の差分をそのまま出力している

改善点

PointGreyのカメラで実行したら、重くて全然動かなかった

  • 画像データをOpenCVで処理をしていることが原因
  • 差分をグレースケール画像にそのまま代入しているため、負の数の場合保存されず、極性が0のイベントを出力していない

上記の問題は一次元配列で受け取り、処理することで解決できそう

次回

  • 画像データを一次元配列に変換して処理をする
  • イベントデータをsubscribeしてフレームに戻すクラスを作成する
岐阜大学アレックス研究室

Discussion