Изменение действий в стандартных командах

Внесение изменений в стандартные действия

Стандартные действия — это готовые сценарии, которые позволяют Робоголове реагировать на голосовые команды, показывать мультимедиа и выполнять простые движения. Но всегда возникает желание добавить чего-то своего: новую картинку, другую мелодию, изменить угол наклона головы или даже добавить дополнительный эффект.

Рассмотрим настройку стандартных действий на примере стандартного действия std_ears, которое вызывается по команде "Слушай, Робот! Покажи уши".


Любые изменения в стандартных действиях применяются "на лету", после сохранения изменений файлов. Если началось непредсказуемое поведение - запустите пакет robohead_controller в ручном режиме (см. далее).

1. Расположение файлов стандартных действий

Стандартные действия находятся в папке robohead_controller_actions пакета robohead_controller. Для std_ears перейдите в папку:

~/robohead_ws/src/robohead/robohead_controller/scripts/robohead_controller_actions/std_ears

В ней вы увидите три основных файла:

  • ears.png — картинка с ушами, которая выводится на экран;

  • ears.mp3 — аудиофайл, который воспроизводится через динамики;

  • action.py — скрипт, описывающий всю логику действия: какие сообщения отправлять, какие сервисы вызывать и в какой последовательности.

Пример структуры:

std_ears/
├── ears.png
├── ears.mp3
└── action.py

2. Разбор скрипта action.py

Откройте файл action.py. Основной блок кода выглядит примерно так:

from robohead_controller_actions.main import *

def run(robohead_controller:RoboheadController, cmds:str):
    '''
    Эта функция вызывается, когда вы произносите «Слушай, Робот! Покажи уши».
    Все инструкции ниже выполняются последовательно.
    '''

    # 1. Получаем путь до текущей папки, чтобы легко ссылаться на медиа-файлы
    script_path = os.path.dirname(os.path.abspath(__file__)) + '/'
    
    # 2. Отправляем картинку ушей на экран
    msg = PlayMediaRequest() # Создаем сообщение для вызова сервиса PlayMedia пакета display_driver
    msg.is_blocking = 0 # Не ждём завершения воспроизведения
    msg.is_cycled = 0 # Воспроизведение не зациклено
    msg.path_to_file = script_path + 'ears.png' # Формируем абсолютный путь до файла, который хотим вывести на экран
    robohead_controller.display_driver_srv_PlayMedia(msg) # Вызываем сервис PlayMedia с сформированным сообщением

    # 3. Воспроизводим звук (mp3-файл) через динамики
    msg = PlayAudioRequest() # Создаем сообщение для вызова сервиса PlayAudio пакета speakers_driver
    msg.path_to_file = script_path + 'ears.mp3' # Формируем абсолютный путь до файла, который хотим воспроизвести через динамики
    msg.is_blocking = 0 # Не ждём завершения воспроизведения
    msg.is_cycled = 0 # Воспроизведение не зациклено
    robohead_controller.speakers_driver_srv_PlayAudio(msg) # Вызываем сервис с сформированным сообщением

    # 4. Меняем положение шеи: задаём горизонтальный и вертикальный углы
    msg = NeckSetAngleRequest() # Создаем сообщение для вызова сервиса NeckSetAngle пакета neck_driver
    msg.horizontal_angle = 0 # Положение шеи по горизонтали 0
    msg.vertical_angle = 30 # Положение шеи по вертикали 30
    msg.duration = 1 # Длительность, за которую необходимо достичь заданного положения 1 секунда
    msg.is_blocking = 0 # Не ждём, пока шея полностью встанет в позицию
    robohead_controller.neck_driver_srv_NeckSetAngle(msg) # Вызываем сервис с сформированным сообщением

    # 5. Меняем угол ушей: левое −30°, правое +30°
    msg = EarsSetAngleRequest() # Создаем сообщение для вызова сервиса EarsSetAngle пакета ears_driver
    msg.left_ear_angle = -30 # Левое ухо в положение -30
    msg.right_ear_angle = 30 # Правое ухо в положенеи 30
    robohead_controller.ears_driver_srv_EarsSetAngle(msg) # Вызываем сервис с сформированным сообщением

    # 6. Добавляем «игривое» подёргивание ушами 5 раз
    k=-1 # Переменная, меняющая направление положения ушей
    for _ in range(5): # Цикл, повторяющий подергивания ушей 5 раз
        rospy.sleep(0.5) # Ждём полсекунды
        msg.left_ear_angle = -30*k # Левое ухо в положение -30*k
        msg.right_ear_angle = 30*k # Правое ухо в положение 30*k
        k*=-1 # Меняем направление ушей
        robohead_controller.ears_driver_srv_EarsSetAngle(msg) # Вызываем сервис с сформированным сообщением

3. Примеры пользовательских изменений

Ниже приведены несколько примеров, как разнообразить действие std_ears без глубокого изменения логики.

3.1 Замена медиа-ресурсов

  • Вывод видео вместо статичного изображения

    1. Поместите свой видеофайл (например, video.mp4) в ту же папку.

    2. В файле action.py измените строчку, где формируется путь до медиафайла:

    - msg.path_to_file = script_path + 'ears.png'
    + msg.path_to_file = script_path + 'video.mp4'

    После этого скажите голосом: "Слушай, Робот! Покажи уши", и робот покажет видео на экране.

Важно Обратите внимание, что размер видео должен быть строго 1080х1080 пикселей!

  • Изменение звукового сопровождения

Бывает хочется, чтобы Робоголова не просто проигрывала короткий звук «Ухи мои ухи», а, например, сначала здоровалась. Для этого:

  1. Сохраните файлы hello.mp3 и new_sound.mp3 с нужным вам звуком в папке стандартного действия.

  2. Вставьте в код два блока «Воспроизведение звука», например:

    # 1. Сначала приветствие
    msg = PlayAudioRequest()
    msg.path_to_file = script_path + 'hello.mp3'
    msg.is_blocking = 1  # Ждём, пока закончится приветствие
    msg.is_cycled = 0
    robohead_controller.speakers_driver_srv_PlayAudio(msg)
    
    # 2. Затем звук для ушей
    msg = PlayAudioRequest()
    msg.path_to_file = script_path + 'new_sound.mp3'
    msg.is_blocking = 0
    msg.is_cycled = 0
    robohead_controller.speakers_driver_srv_PlayAudio(msg)
  3. Обратите внимание, что is_blocking = 1 означает ожидание завершения воспроизведения аудио перед продолжением выполнения скрипта.

3.2 Настройка положения шеи

  • Изменение угла обзора Для более выразительной реакции можно поднять голову выше или опустить:

    - msg.horizontal_angle = 0
    - msg.vertical_angle = 30
    + msg.horizontal_angle = 15   # Повернуть голову вправо на 15°
    + msg.vertical_angle = -20     # Опустить голову вниз на 20°
  • Изменение скорости движения Параметр duration отвечает за время выполнения движения. Меньшее значение — более резкое движение:

    - msg.duration = 1
    + msg.duration = 0.5  # Шея повернется быстрее: за 0.5 секунды
  • Добавление паузы перед движением Чтобы голосовая команда сначала воспроизводила звук и изображение, а через секунду двигала шею:

    rospy.sleep(1)  # Пауза 1 секунда
    msg = NeckSetAngleRequest()
    # ...

    3.3 Настройка «анимации» ушей

По умолчанию уши подергиваются 5 раз с интервалом 0.5 секунды. Вот несколько примеров изменений:

  • Увеличить количество повторений Измените range(5) на большее значение, например:

    - for _ in range(5):
    + for _ in range(10):  # Подергивание 10 раз
  • Увеличить интервал Чтобы подергивания были медленнее (интервал 1 секунда):

    - rospy.sleep(0.5)
    + rospy.sleep(1)
  • Сложная анимация Можно задать последовательность углов в списке:

    angles = [-30, 0, 30, 0, -30]  # Последовательность позиций
    for angle in angles:
        msg.left_ear_angle = -angle
        msg.right_ear_angle = angle
        robohead_controller.ears_driver_srv_EarsSetAngle(msg)
        rospy.sleep(0.4)

4. Запуск пакета robohead_controller в ручном режиме

Для тестирования бывает удобно запустить пакет robohead_controller в ручном режиме, чтобы видеть появляющиеся ошибки и информацию для отладки (например, если в скрипте вы что-то выводили через функцию print()).

Шаг 1. Остановка Ubuntu-сервиса

По-умолчанию, пакет robohead_controller и все зависимости запускаются автоматически при загрузке Робоголовы при помощи Ubuntu-сервиса. Для отладки и запуска пакета в ручном режиме его необходимо остановить

sudo systemctl stop robohead.service

Шаг 2. Запуск пакета вручную

Запустите пакет отдельно через launch-файл:

roslaunch robohead_controller robohead_controller_py.launch

На экране терминала должен появиться примерно следующий вывод:

Запуск без ошибок

5. Отладка команд

В этом шаге описано как запускать стандартные действия, не произнося каждый раз голосом нужную команду.

Отлаживать команды можно как при автоматически запущенном robohead_controller (через Ubuntu-сервис), так и когда он запущен в ручном режиме (этот вариант предпочтительнее для отладки, так как видны все возникающие ошибки)

Откройте новое окно терминала, подключитесь к Робоголове и опубликуйте "покажи уши" в топик /robohead_controller/voice_recognizer_pocketsphinx/cmds_recognizer/commands

# Запустите в отдельном терминале
rostopic pub /robohead_controller/voice_recognizer_pocketsphinx/cmds_recognizer/commands std_msgs/String "data: 'покажи уши'"

После публикации команды Робоголова должна выполнить стандартное действие "Покажи уши".

Аналагично можно запускать и другие стандартные действия.

Last updated