ROS2側:ROS2からUnityにカメラデータ送信

ROS2 Unityとの通信“で通信ができていることを前提にスクリプトを記載している。

ROS2からUnityにカメラデータを送信する際のメッセージファイルとpythonコードを記載する。

メッセージファイル(CameraMsg.msg)

uint8[] img_data

pythonコード

# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
#     http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.


# Copyright 2022 robot-creation-diary.com
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
#     http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# 整数とテキストを送信するチュートリアルの内容から、カメラデータを取得し
# 変換・送信するように変更してある。

import rclpy
from rclpy.node import Node

from cpp_pubsub.msg import CameraMsg
import cv2


class MinimalPublisher(Node):

    def __init__(self):
        super().__init__('minimal_publisher')
        self.publisher_ = self.create_publisher(CameraMsg, 'topic', 10)
        timer_period = 0.033  # seconds
        self.timer = self.create_timer(timer_period, self.timer_callback)

        # カメラ関連
        # 0はカメラを指定する番号。状況に応じて変更のこと
        self.video_capture = cv2.VideoCapture(0)

    def __del__(self):
        pass

    def timer_callback(self):

        # カメラ関連
        ret, frame_data = self.video_capture.read()
        ret, encoded_data = cv2.imencode(".jpg", frame_data,
                                         (cv2.IMWRITE_JPEG_QUALITY, 50))

        # データ送信関連
        msg = CameraMsg()
        # 送信用データの代入単純に=で代入しようとすると型が違うと怒られる
        msg.img_data.frombytes(encoded_data)

        self.publisher_.publish(msg)
        # コンソールに何も表示されないと不安なのでデータの内容を表示
        self.get_logger().info('Publishing:  %d %d'
                               % (msg.img_data[0], msg.img_data[1]))


def main(args=None):
    rclpy.init(args=args)

    minimal_publisher = MinimalPublisher()

    rclpy.spin(minimal_publisher)

    # Destroy the node explicitly
    # (optional - otherwise it will be done automatically
    # when the garbage collector destroys the node object)
    minimal_publisher.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()