音声出力

はじめに

Kachakaロボットは音声出力機能を備えており、様々な状況で音声によるコミュニケーションが可能です。このレッスンでは、ROS2を使用してKachakaロボットに音声で話させる方法について学びます。

Kachakaの音声出力機能

Kachakaロボットは、アクションサーバーを通じて音声出力を制御することができます。この機能を使用することで、以下のような用途が可能です:

  • ロボットの状態通知
  • ユーザーへの操作指示
  • エラーや警告の通知
  • 対話的なコミュニケーション

コードの解説

コード全文

以下がspeak.pyのコードです:

speak.py

#!/usr/bin/env python3
# -*- coding: utf-8 -*-

import rclpy
from kachaka_interfaces.action import ExecKachakaCommand
from kachaka_interfaces.msg import KachakaCommand
from rclpy.action import ActionClient
from rclpy.node import Node


class Speak(Node):
    """
    Node for making Kachaka robot speak
    """
    def __init__(self) -> None:
        """
        Node initialization
        - Set up action client
        - Wait for server
        """
        super().__init__("speak")
        self._action_client = ActionClient(
            self, ExecKachakaCommand, "/kachaka/kachaka_command/execute"
        )
        self._action_client.wait_for_server()

    def send_goal(self):
        """
        Send speech command
        Returns:
            Future: Future object representing the action execution result
        """
        # Create command message
        command = KachakaCommand()
        command.command_type = KachakaCommand.SPEAK_COMMAND
        command.speak_command_text = "こんにちは、カチャカです"

        # Create goal message
        goal_msg = ExecKachakaCommand.Goal()
        goal_msg.kachaka_command = command

        # Send goal asynchronously
        return self._action_client.send_goal_async(goal_msg)


def main(args=None):
    """
    Main function
    - Initialize ROS2
    - Create and run node
    - Release resources
    """
    # Initialize ROS2
    rclpy.init(args=args)

    # Create node
    speak = Speak()
    
    # Send speech command
    future = speak.send_goal()
    
    # Wait for command completion
    rclpy.spin_until_future_complete(speak, future)

    # Destroy node
    speak.destroy_node()
    
    # Shutdown ROS2
    rclpy.shutdown()


if __name__ == "__main__":
    main()

必要なインポート

import rclpy
from kachaka_interfaces.action import ExecKachakaCommand
from kachaka_interfaces.msg import KachakaCommand
from rclpy.action import ActionClient
from rclpy.node import Node

各インポートの説明:

  • rclpy: ROS2のPythonクライアントライブラリ。ROS2の基本機能を提供します。
  • ExecKachakaCommand: Kachakaのコマンド実行用アクションインターフェース。音声出力を含む様々なコマンドを実行できます。
  • KachakaCommand: Kachakaのコマンドメッセージ型。コマンドの種類やパラメータを定義します。
  • ActionClient: ROS2のアクションクライアント。アクションサーバーと通信するための機能を提供します。
  • Node: ROS2ノードの基本クラス。すべてのROS2ノードはこのクラスを継承します。

Speakクラスの実装

class Speak(Node):
    def __init__(self) -> None:
        super().__init__("speak")
        self._action_client = ActionClient(
            self, ExecKachakaCommand, "/kachaka/kachaka_command/execute"
        )
        self._action_client.wait_for_server()

クラスの初期化について:

  1. super().__init__("speak"): ノード名を"speak"として初期化します。
  2. ActionClientの初期化:
    • 第1引数: ノードインスタンス(self)
    • 第2引数: アクション型(ExecKachakaCommand)
    • 第3引数: アクションサーバーの名前("/kachaka/kachaka_command/execute")
  3. wait_for_server(): アクションサーバーが利用可能になるまで待機します。

音声コマンドの送信

def send_goal(self):
    command = KachakaCommand()
    command.command_type = KachakaCommand.SPEAK_COMMAND
    command.speak_command_text = "こんにちは、カチャカです"
    goal_msg = ExecKachakaCommand.Goal()
    goal_msg.kachaka_command = command
    return self._action_client.send_goal_async(goal_msg)

コマンド送信の手順:

  1. KachakaCommandメッセージの作成
  2. コマンドタイプをSPEAK_COMMANDに設定
  3. 発話するテキストを設定
  4. ゴールメッセージの作成
  5. 非同期でゴールを送信

メイン関数

def main(args=None):
    rclpy.init(args=args)
    speak = Speak()
    future = speak.send_goal()
    rclpy.spin_until_future_complete(speak, future)
    speak.destroy_node()
    rclpy.shutdown()

メイン関数の処理の流れ:

  1. rclpy.init(args=args): ROS2を初期化
  2. speak = Speak(): Speakノードのインスタンスを作成
  3. future = speak.send_goal(): 音声コマンドを送信
  4. rclpy.spin_until_future_complete(speak, future): コマンドの完了を待機
  5. speak.destroy_node(): ノードを破棄
  6. rclpy.shutdown(): ROS2を終了

使用方法

前提条件

  • Kachakaロボットが起動していること
  • ROS2の環境が正しく設定されていること
  • kachaka_speakパッケージがビルドされていること

実行手順

  1. ノードを実行します:
ros2 run kachaka_speak speak

演習

  1. 異なるメッセージを話させる

    • speak_command_textの内容を変更して、異なるメッセージを話させてみましょう。
  2. 複数のメッセージを連続して話させる

    • メッセージを配列で管理し、順番に話させる機能を追加してみましょう。
  3. コマンドの結果を確認する

    • send_goal_asyncの戻り値を処理して、コマンドの実行結果を確認してみましょう。

注意点

  • Kachakaロボットが起動していない場合、アクションサーバーに接続できません
  • アクションサーバーが利用可能になるまで待機するため、起動に時間がかかる場合があります
  • デフォルトでは「こんにちは、カチャカです」というメッセージを発話します