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

Каждое стандартное действие можно настраивать ещё чуть более тонко.

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

Для его настройки перейдите в соотвествующую ему папку: ~/robohead_ws/src/robohead/robohead_controller/scripts/robohead_controller_actions/std_ears

В этой папке расположены четыре файла:

  • ears.png

  • ears.mp3

  • ears_2.mp3

  • action.py

ears.png, ears.mp3, ears_2.mp3 это рассмотренные ранее (см. смена ресурс-пака) медиа-ресурсы. Вся логика и последовательность действий описана в скрипте action.py:

from robohead_controller_actions.main import *

def run(robohead_controller:RoboheadController, cmds:str): # Обязательно наличие этой функции, именно она вызывается при голосовой команде
    script_path = os.path.dirname(os.path.abspath(__file__)) + '/' # Получание абсолютный путь до директории с исполняемым скриптом
    
    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 с сформированным сообщением

    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) # Вызываем сервис с сформированным сообщением

    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) # Вызываем сервис с сформированным сообщением

    msg = EarsSetAngleRequest() # Создаем сообщение для вызова сервиса EarsSetAngle пакета ears_driver
    msg.left_ear_angle = -30 # Левое ухо в положение -30
    msg.right_ear_angle = 30 # Правое ухо в положенеи 30
    robohead_controller.ears_driver_srv_EarsSetAngle(msg) # Вызываем сервис с сформированным сообщением
    
    k=-1 # Переменная, меняющая направление положения ушей
    for _ in range(5): # Цикл, повторяющий подергивания ушей 5 раз
        rospy.sleep(0.5) # "засыпам" на 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) # Вызываем сервис с сформированным сообщением

Например, для воспроизведения своего видео (вместо картинки) во время этого действия:

  1. Поместите своё видео, например video.mp4, в директорию со скриптом

  2. Отредактируйте строчку 9: из msg.path_to_file = script_path + 'ears.png' в msg.path_to_file = script_path + 'video.mp4'

Если вы хотите изменить положение головы, во время выполнения этого действия:

  1. Отредактируйте строки 19 и 20: msg.horizontal_angle = 0 и msg.vertical_angle = 30

Внесенный изменения вступят в силу сразу после сохранения файла скрипта action.py. Сохраните файл и произнесите соответствующую голосовую команду, чтобы убедиться в этом.

Подробнее о методах вызываемых методах читайте в robohead_controller.

Last updated