WebアプリケーションによるROS2データの可視化4 Webアプリケーション側からのROS2情報送信

WebアプリケーションによるROS2データの可視化4 Webアプリケーション側からのROS2情報送信

※ ROSの表記について :
ROS1/ROS2について、文脈的にどちらでも当てはまる場合は単に「ROS」と表記しています。

はじめに


本記事は全4回のシリーズ記事の第4回 (最終回) です。

第1回 基本部分の作成
第2回 画像データの受信と表示
第3回 点群データの受信と表示
第4回 Webアプリケーション側からのROS2情報送信


前回は「点群データの受信と表示」として、ROS2を起動するサーバ側システム (以降は単に「サーバ」と表記) にて人工的に作成した点群データを送信し、Next.jsによるクライアント側Webアプリケーション (以降は単に「Webアプリケーション」と表記) 側で受け取って表示させてみました。
前々回と合わせ、画像、点群がそれぞれ受信して表示されるようになりました。

今回はこれまでと逆に、Webアプリケーション側からROS2トピックを送信し、サーバ側のノードに影響を与える仕組みを作ってみます。

ROS2 data visualization sample

文字列 ( std_msgs/String ) のコマンドを送信し、画像データ送信ノード側で受けたコマンドに応じて画像にフィルタをかける処理を作成します。

実装

Webアプリケーション側

今回はWebアプリケーション側が送信側となるため、こちらから実装を始めます。
まず、表示部となる Viewer側では、

  • コマンドを入力できるテキスト欄および送信処理を行うボタン
  • ボタン押下時の処理

を今までのViewerに追加します。

( Webアプリケーション側ディレクトリ )
$ cd visualize_sample_client

( Viewer 編集 )
$ vim pages/viewer.tsx
ソース詳細
const Viewer = () => {

    // コマンド文字列を保持する useState を追加
    const [commandStr, setCommandStr] = useState<string>('');

    // ROS側へコマンド送付を行う処理を追加
    const sendToServer = () => {
        if (commandStr !== '') {
            rosOpRef.current.sendTextCommand(commandStr);
        }
    };

    return (
        <> 
                {/* 追記部のみ */}

                {/* サーバ側へのコマンド送付 */}
                <Row>
                    <Row>
                        <Col xs lg="2">
                            <Form.Control
                                id="inputCommand"
                                placeholder="Command"
                                onChange={(e) => {setCommandStr(e.target.value);}}
                            />
                        </Col>
                        <Col xs lg="2">
                            <Button
                                variant={rosConnected ? "primary" : "secondary"}
                                disabled={!rosConnected}
                                onClick={rosConnected ? sendToServer : null}
                            >
                                サーバ側へ送信
                            </Button>
                        </Col>
                    </Row>
                    <Row>
                        <Col>
                            <span>
                            (Command ... BLUR, CONTOUR, DETAIL, EDGE, EMBOSS, SHARPEN, SMOOTH, DEFAULT)
                            </span>
                        </Col>
                    </Row>
                </Row>
        </>
    );
}

ROS側と送信するためのRosOperatorでは、Viewerで設定した sendTextCommand(commandStr) を実装して実際に送信ができるようにします。

( RosOperator 編集 )
$ vim libs/ros_operation.tsx
ソース詳細 (該当部のみ)
// コマンドトピック名
const TOPIC_NAME_COMMAND = '/command'

// String 型の定義 (画像受信時に定義済み)
export interface String {
    data: string;
}

const RosOperator = forwardRef((props, ref) => {

    // 上位モジュールから呼び出される処理
    useImperativeHandle(ref, () => ({

        // ROSとの接続
        connect: () => {
            connectToROS();
        },

        // テキストのコマンドを送信 (追加)
        sendTextCommand: (command) => {
            sendCommand(command);
        },
    }));

    // Command string topic Sender
    const [commandStrSender, setCommandStrSender] = useState<ROSLIB.Topic | null>(null);

    // ROS オブジェクト更新時に Listener & Sender を更新
    useEffect(() => {
        // 今までの Listener 更新時の処理に commandStrSender の更新処理を追加

        setCommandStrSender(
            new ROSLIB.Topic({
                ros: ros,
                name: TOPIC_NAME_COMMAND,
                messageType: 'std_msgs/String',
            })
        );
    }

    // コマンド (文字列Topic) 送信
    const sendCommand = (command) => {
        const msg = new ROSLIB.Message({data: command})
        commandStrSender?.publish(msg);
    };
});

これで表示部からROSの通信部まで繋がり、送信ができるようになりました。

サーバ側

サーバ側は、前々回に作成した画像送信ノード ( image_sender_node ) を改造します。
文字列トピックを受信できるようにし、その文字列 (コマンド) に従って、送信前に画像フィルタをかけた上で送信します。

( サーバ側ディレクトリ )
$ cd visualize_sample_server

( エディタを開いて編集 )
$ vim scripts/image_sender_node.py
ソース詳細 (該当部のみ)
"""
読み込んだ画像を指定サイズで順次publishするノード
( コマンド追加版 )
"""
import glob
import numpy as np
# from PIL import Image
from PIL import Image, ImageFilter

import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from std_msgs.msg import Header
from std_msgs.msg import String  # for command
from sensor_msgs.msg import Image as SensorImage

### Node name
NODE_NAME = 'image_sender'

### Topic name
TOPIC_NAME = '/image'

### Subscription command topic name
SUB_TOPIC_NAME = '/command'

### Timer period
TIMER_PERIOD = 0.25  # 0.25秒おきに呼び出し

### Image size
# NOTE: 指定サイズにリサイズ
IMAGE_WIDTH  = 640
IMAGE_HEIGHT = 480
# IMAGE_WIDTH  = 256
# IMAGE_HEIGHT = 256

### 指定ディレクトリを読み込み → 中の画像を順次表示
IMAGE_DIR = './images/'

### Image sender node
class ImageSenderNode(Node) :

    def __init__(self) :
        super().__init__(NODE_NAME)

        # Initialize publisher
        self.publisher = self.create_publisher(SensorImage, TOPIC_NAME, 10)

        # Initialize command subscription
        self.subscription = self.create_subscription(
            String,
            SUB_TOPIC_NAME,
            self.command_callback,
            qos_profile_sensor_data,
        )

        # Command str
        self.command_str = ''  # 受信したら以降の画像に適用

        # Load images path
        self.images = glob.glob(f'{IMAGE_DIR}/*.jpg')
        self.images.extend(glob.glob(f'{IMAGE_DIR}/*.png'))
        self.images = sorted(self.images)
        self.idx = 0
        self.images_max = len(self.images)

        # Timer
        self.timer = self.create_timer(TIMER_PERIOD, self.on_timer)

    def command_callback(self, msg) :
        """
        受信したコマンド (string msg) を保持し、以降に送信する画像に適用する。
        """
        self.command_str = msg.data

    def on_timer(self) :

        # Open image
        img = Image.open(self.images[self.idx])
        img = img.resize((IMAGE_WIDTH, IMAGE_HEIGHT))

        # コマンド指定されていたら適用
        if self.command_str.upper() == 'BLUR' :
            img = img.filter(ImageFilter.BLUR)
        elif self.command_str.upper() == 'CONTOUR' :
            img = img.filter(ImageFilter.CONTOUR)
        elif self.command_str.upper() == 'DETAIL' :
            img = img.filter(ImageFilter.DETAIL)
        elif self.command_str.upper() == 'EDGE' :
            img = img.filter(ImageFilter.EDGE_ENHANCE)
        elif self.command_str.upper() == 'EMBOSS' :
            img = img.filter(ImageFilter.EMBOSS)
        elif self.command_str.upper() == 'SHARPEN' :
            img = img.filter(ImageFilter.SHARPEN)
        elif self.command_str.upper() == 'SMOOTH' :
            img = img.filter(ImageFilter.SMOOTH)

        # Publish
        header = Header(frame_id = 'map')
        header.stamp = self.get_clock().now().to_msg()
        msg = SensorImage()
        msg.header = header
        msg.height = img.height
        msg.width = img.width
        msg.encoding = 'rgb8'
        msg.is_bigendian = False
        msg.step = 3 * img.width
        msg.data = np.array(img).tobytes()
        self.publisher.publish(msg)

        # Increment
        self.idx += 1
        if self.idx >= self.images_max : self.idx = 0

def main(args = None):

    # Initialize rclpy
    print("Start image sender node.")
    rclpy.init(args = args)

    # Create node
    node = ImageSenderNode()

    # Spin
    try :
        rclpy.spin(node)
    except KeyboardInterrupt :  # Ctrl + C
        pass

    print("Shutdown image sender node.")
    rclpy.shutdown()

if __name__ == '__main__':
    main()

これで受信側も設定ができました。

実行

それぞれの機能が完成したので、実行してみます。

サーバ側

$ source ./install/setup.sh
$ ros2 launch visualize_sample_server execute.launch.py

Webアプリケーション側 (npmデバッグ実行)

$ PORT=8000 npm run dev

ブラウザでWebアプリケーションにアクセス( ここでは http://127.0.0.1:8000/viewer ) し、
「ROS接続開始」ボタンでサーバ側と繋ぐと、これまでと同様に画像と点群が表示されます。

更にコマンド (BLUR、CONTOUR、DETAIL、…) を入力し、画像表示に適用されることを確認します。

ここまでで、Webアプリケーション側で受信するだけではなく、送信の処理も作成することができました。

まとめ

これまでの全4回の記事にて、ROSデータをWebアプリケーションで送受信する方法を扱いました。

画像に関しては一旦文字列状に変換して送信を行う必要がある等、いくつかの制約事項はありますが、多くは特異な実装を行うことなく (ライブラリを組み込みつつ) 独自の Web アプリケーションを構築できることが分かりました。

ROSの仕組みは単にロボット向けのデータ制御だけではなく扱える仕組みなので、Webアプリケーションによる表示も含めたパッケージとして考えると様々な応用ができそうです。