МОСКОВСКИЙ ГОСУДАРСТВЕННЫЙ ТЕХНИЧЕСКИЙ УНИВЕРСИТЕТ ИМЕНИ Н.Э. БАУМАНА | Дмитровский филиал | English


Регистрация и вход в систему

   Вход в систему

   Регистрация

   Поменять пароль

   Выход из системы

Общие сведения о функционально-моделирующем стенде

   Принцип действия

   Состав

   Программное обеспечение

   Моделирующая система реального времени

   Пульт управления манипулятором

   Система избегания столкновений

   Система подготовки миссий

   Управление исполнительными устройствами

   Обработка внешних воздействий

   Средства оценки операторов

   Исполнительные устройства

   Промышленные роботы

   Трехпальцевый центрирующий схват

   Очувствленная кисть

   Системы очувствления

   Системы технического зрения

   Система измерения сил и моментов

   Тактильные сенсоры кисти

   Обзорные камеры

   Органы управления

Видео

Удаленное управление функционально-моделирующим стендом

   Методика удаленного управления

   Схема удаленного доступа

   Интерфейс удаленного управления

   Формирование миссии робота

Проведение удаленного эксперимента

Контактная информация

Библиография

Введение в ROS

   Уроки

   Тестирование
 
 Урок 7

Урок 7

Урок 7. Универсальный формат описания файлов

Введение

К настоящему моменту вы уже освоили ключевые концепции ROS: научились работать с узлами, темами, сервисами и действиями, разобрались в системе управления пакетами catkin и создали собственные проекты. Вы умеете использовать графические инструменты для анализа топологии системы, работаете с симулятором Gazebo, применяете контейнеризацию Docker для изоляции и запуска сложных систем, а также используете сервер параметров и запись данных с помощью rosbag.

Теперь настало время перейти к следующему важному этапу — работе с моделями роботов. Чтобы эффективно управлять роботами, тестировать их поведение и моделировать взаимодействие с окружающей средой, необходимо иметь точное описание их конструкции и физических свойств. Для этих целей в ROS используется универсальный формат описания роботов — URDF (Unified Robot Description Format).

В этом уроке вы:

  • Познакомитесь с RViz — мощным инструментом визуализации, который позволяет отображать модель робота, данные с датчиков и информацию об окружении.
  • Изучите структуру URDF-файлов и научитесь описывать как простые, так и сложные модели роботов.
  • Создадите свою первую модель — от базового цилиндра до полноценного робота R2D2.
  • Научитесь добавлять материалы, цвета, текстуры и даже внешние 3D-модели с помощью mesh.
  • Разберётесь с кинематическими соединениями, заданием осей вращения и ограничений движения.
  • Добавите физические свойства вашим звеньям: массы, инерционные характеристики, зоны столкновений.
  • Подготовите модель робота для работы в симуляторе Gazebo, где сможете протестировать её поведение в реалистичной физической среде.

Этот урок станет логическим продолжением ваших знаний: вы начнёте не просто управлять данными и событиями, но и строить собственные представления о том, как должен выглядеть и двигаться робот в виртуальном или реальном мире.

7.1 Среда визуализации RViz

Gazebo достаточно серьезный инструмент со своей системой визуализации, но это в первую очередь симулятор. Если же у нас есть реальный робот, который не нужно моделировать, а только показывать на экране графическую модель его и его окружения, то и использовать симулятор смысла не имеет. В этом случае как раз и стоит использовать RViz – инструмент 3D-визуализации ROS. RViz позволяет просматривать графическую модель робота, модель окружения, данные с камер, лидаров, прочих датчиков. RViz входит в установку ROS Desktop-Full. Теперь посмотрим, как работает RViz, на примере коллаборативного робота UR5, разработанного компанией Universal Robots. Заодно мы познакомимся с файлами унифицированного формата описания роботов ROS urdf (Unified Robot Description Format), которые похожи на sdf-файлы описания для Gazebo. Ничего удивительного в этой похожести нет, так как оба этих формата основаны xml и описывают роботы. Кстати, Gazebo понимает urdf-файлы.

7.1.1 Подготовка docker-файла

Давайте опять создадим docker-образ, в котором и запустим RViz с моделью UR5. В каталоге ~/dockerfiles/ur_rviz создадим docker-файл:

FROM osrf/ros:noetic-desktop-full
FROM ros:noetic

RUN apt update -y && apt upgrade -y && apt install git -y
RUN echo "source /opt/ros/noetic/setup.bash" >> /home/.bashrc

WORKDIR /home/catkin_ws/src
RUN git clone -b $ROS_DISTRO-devel https://github.com/ros-industrial/universal_robot.git

WORKDIR /home/catkin_ws
RUN rosdep update && rosdep install --rosdistro $ROS_DISTRO --ignore-src --from-paths src -y

WORKDIR /home/catkin_ws
RUN /bin/bash -c '. /opt/ros/noetic/setup.bash; catkin_make'
RUN echo "source /home/catkin_ws/devel/setup.bash" >> /home/.bashrc

RUN apt update -y && apt upgrade -y && apt install ros-$ROS_DISTRO-urdf-tutorial -y

COPY ur5_rviz.urdf /home/ur5_rviz.urdf
COPY launch.sh /home/launch.sh
RUN chmod +x /home/launch.sh

ENTRYPOINT [ "/home/launch.sh" ]

Мы видим уже знакомое нам начало – мы берём за основу docker-образ osrf/ros:noetic-desktop-full FROM osrf/ros:noetic-desktop-full, затем устанавливаем git RUN apt update -y && apt upgrade -y && apt install git -y, посылаем настройки среды в .bashrc RUN echo "source /opt/ros/noetic/setup.bash" >> /home/.bashrc. Теперь, чтобы в нашей визуализации была 3d-модель реального робота, а не просто набор систем координат, и сделать это максимально простым образом, мы должны в каталог исходников рабочего пространства WORKDIR /home/catkin_ws/src установить ROS-пакет с библиотеками, инструментами и драйверами индустриального оборудования для роботов UR RUN git clone -b $ROS_DISTRO-devel https://github.com/ros-industrial/universal_robot.git и установить в рабочей области WORKDIR /home/catkin_ws все зависимости для пакетов RUN rosdep update && rosdep install --rosdistro $ROS_DISTRO --ignore-src --from-paths src -y. Переходим в каталог рабочего пространства WORKDIR /home/catkin_ws и строим его RUN /bin/bash -c '. /opt/ros/noetic/setup.bash; catkin_make'. После построения рабочего пространства настройки рабочего пространства посылаем в .bashrc RUN echo "source /home/catkin_ws/devel/setup.bash" >> /home/.bashrc. Запускать визуализацию на базе нашего urdf-файла, который мы создадим чуть позже, будем с помощью ROS-пакета urdf_tutorial, который и установим RUN apt update -y && apt upgrade -y && apt install ros-$ROS_DISTRO-urdf-tutorial -y. Теперь скопируем urdf-файл COPY ur5_rviz.urdf /home/ur5_rviz.urdf и скрипт запуска из хост-машины в образ COPY launch.sh /home/launch.sh, дадим скрипту право на запуск RUN chmod +x /home/launch.sh и зададим его точкой входа для контейнера ENTRYPOINT [ "/home/launch.sh" ]. Пусковой скрипт у нас совсем простой:

#!/usr/bin/env bash

. /home/.bashrc
# Всегда программный рендеринг
export LIBGL_ALWAYS_SOFTWARE=1
# Запустить urdf_tutorial с отображением urdf-файла
roslaunch urdf_tutorial display.launch model:='/home/ur5_rviz.urdf'

Здесь при присваивании стоило бы написать model:=/home/ur5_rviz.urdf.. При передаче пути в команде roslaunch кавычки не обязательны и могут быть опущены, если путь не содержит пробелов. В ROS-проектах принято использовать имена без пробелов, поэтому кавычки часто опускают для упрощения и лучшей читаемости команд. Это также снижает риск ошибок при автоматизации и использовании переменных окружения.

Однако, в примерах или на этапе обучения кавычки можно использовать, чтобы явно показать, что значение параметра — это единая строка. Так мы избежим путаницы и сделаем синтаксис более понятным.

Ещё одна ремарка. Переменная LIBGL_ALWAYS_SOFTWARE=1 форсирует использование CPU для рендеринга вместо GPU. Это временное решение для случаев, когда приложение с графическим интерфейсом типа Gazebo/RViz не запускаются из-за проблем с видеодрайверами. Для реальных задач стоит настроить аппаратное ускорение (например, NVIDIA Docker для контейнеров).

Хорошо, скрипт у нас был простой, а вот urdf-файл пока сложный для нашего понимания и смотреть на него мы не будем, а для начала обратимся к уроку по созданию urdf-файлов из ROS Wiki, но перед этим проверим, как там наш docker-файл, построим образ и запустим контейнер:

docker build . --tag ur5_rviz
docker run -it --rm --env="DISPLAY" --env="QT_X11_NO_MITSHM=1" --volume="/tmp/.X11-unix:/tmp/.X11-unix:rw" ur5_rviz

У нас должна появиться окно, в котором мы можем видеть модель робота UR5 и даже поменять точку обзора: rviz_ur5.png Мы с вами сейчас использовали готовый urdf-файл с моделью робота, но мы же хотим создавать такие файлы сами. Давайте начнём.

7.2 Построение модели робота в формате urdf

7.2 Построение визуальной модели робота

Первым делом давайте создадим каталог ~/urdf, в нём файл 01-myfirst.urdf и откроем файл:

mkdir ~/urdf
touch ~/urdf/01-myfirst.urdf
gedit ~/urdf/01-myfirst.urdf

Вставим в него текст:

<?xml version="1.0"?>
<robot name="myfirst">
  <link name="base_link">
    <visual>
      <geometry>
        <cylinder length="0.6" radius="0.2"/>
      </geometry>
    </visual>
  </link>
</robot>

Если перевести xml на русский, то в файле можно прочитать, что здесь говорится о роботе с именем myfirst, содержащем всего одно звено с именем base_link. Визуально это звено представляет собой цилиндр длиной 0,6 метра и радиусом 0,2 метра. Давайте запустим вашу первую urdf-модель:

cd ~/urdf/
roslaunch urdf_tutorial display.launch model:=01-myfirst.urdf

ROS загрузит нашу модель на сервер параметров, запустит паблишер состояния шарниров (который нам пока будет только мешать) и запустит RViz, а мы увидим следующую картину: rviz-step-1.png Ура, у нас есть визуализация робота с одним звеном в виде цилиндра. Если мы будем вращать модель, то увидим, что цилиндр “разрублен пополам” сеткой, так как он имеет начало в своём геометрическом центре и с ним же – центром – связана сейчас базовая система координат нашего “робота”. Теперь давайте наш urdf-файл дополним ещё одним звеном right_leg и свяжем эти звенья кинематическим соединением, которые я в дальнейшем не всегда корректно могу называть шарнирами. В ROS термин “joint” (соединение) технически точнее, чем “шарнир”, хотя в учебных материалах часто используется привычное “шарнир”. Joint — это элемент, описывающий связь между звеньями с возможностью движения: вращательное, поступательное или фиксированное.

Мы будем использовать оба термина:

  • Шарнир – в общих рассуждениях, чтобы сохранить понятность;
  • joint – в технических разделах и примерах кода, как принято в URDF и ROS.

Главное — понимать, что речь идёт об одном и том же элементе модели робота.

И так, добавим соединение с именем base_to_right_leg:

<?xml version="1.0"?>
<robot name="multipleshapes">
  <link name="base_link">
    <visual>
      <geometry>
        <cylinder length="0.6" radius="0.2"/>
      </geometry>
    </visual>
  </link>

  <link name="right_leg">
    <visual>
      <geometry>
        <box size="0.6 0.1 0.2"/>
      </geometry>
    </visual>
  </link>

  <joint name="base_to_right_leg" type="fixed">
    <parent link="base_link"/>
    <child link="right_leg"/>
  </joint>

</robot>

Звено right_leg – это прямоугольный параллелепипед. Ненавижу произносить это словосочетание. > Тому, кто это придумал, надо в голову гвоздь забить.

В общем, это будет просто коробка размерами 0,6 м на 0,1 м и на 0,2 м, которую мы попробуем прицепить к цилиндру. Коробка у нас с именем. А имя его нам понадобиться для связи звеньев посредством соединения. Для каждого соединения определены родительское звено parent link="имя родительского звена" и дочернее звено child link="имя дочернего звена". Естественно, звенья с заданными именами должны быть описаны в данном urdf-файле. Есть ещё и не очень явное ограничение. Предположим, что у нас есть робот, в котором четыре звена: A, B, C, D. Эти звенья мы связали тремя соединениями: One, Two, Three:

  <joint name="One">
    <parent link="A"/>
    <child link="B"/>
  </joint>
  <joint name="Two">
    <parent link="A"/>
    <child link="C"/>
  </joint>
  <joint name="Three">
    <parent link="C"/>
    <child link="D"/>
  </joint>

Если мы представим эту кинематическую цепь в виде ориентированного графа, то получим:

stateDiagram-v2
    state "Звено A" as lA
    state "Звено B" as lB
    state "Звено C" as lC
    state "Звено D" as lD
    lA --> lB: One
    lA --> lC: Two
    lC --> lD: Three

Такая схема робота валидна. Теперь предположим, что мы добавили ещё одно соединение Four, которым соединили звенья B и D:

  <joint name="Four">
    <parent link="B"/>
    <child link="D"/>
  </joint>

Мы получим такой граф:

stateDiagram-v2
    state "Звено A" as lA
    state "Звено B" as lB
    state "Звено C" as lC
    state "Звено D" as lD
    lA --> lB: One
    lA --> lC: Two
    lC --> lD: Three
    lB --> lD: Four

И вот такая схема валидной уже не будет. Хотя мы никак не нарушили правила написания urdf-файла, цепь мы замкнули, а такого urdf не допускает. Циклов в графе быть не должно. Запустим RViz с исправленным файлом: rviz-step-2.png
> Смешались в кучу кони, люди…

Не очень понятная мешанина получилась. А получилась она из-за того, что мы не сказали коробке, куда и как она должна встать. Больше того, мы должны не просто прицепить коробку к цилиндру, а учесть, что прицепляем её через соединение. Дополним описание соединения строкой <origin xyz="0 -0.22 0.25"/>, которая говорит, что соединение следует сдвинуть на 0 м по оси X, -0,22 м по оси Y и 0,25 м по оси Z системы координат Родителя.

Теперь дополним описание визуальной составляющей звена. Каждое звено имеет систему координат, но визуальный элемент может быть смещён относительно неё. Для этого используется тег <origin>. Дополним элемент <visual> строкой <origin rpy="0 1.57075 0" xyz="0 0 -0.3"/>. Здесь мы задаём не только смещение xyz на -0,3 м по оси Z, но и поворот rpy на Π/2 вокруг оси Y.

Давайте внесём правки в urdf-файл и посмотрим, что получилось: rviz-step-3.png
Я не стал гасить обозначения систем координат, оси которых обозначены цветами по схеме rgb = xyz, так что мы можем видеть, что СК правой ноги смещён в минус по оси Y и в плюс по оси Z. СК сместилась вместе с шарниром, а шарнир мы и просили сдвинуть приблизительно так. Ещё мы видим, СК правой ноги у нас в центре одной из поверхностей коробки, как будто коробка ушла вниз на половину своего размера по оси Z, а ведь мы и просили сместить визуальную составляющую звена на -0,3, то есть, половину от размера, по оси Z в СК правой ноги. > Этa нога — у того, у кого надо нога.

Кстати, что это за правая нога, что за модель мы строим? А строим мы его модель: R2D2.png
Получается страшненько, но R2-D2 не сильно обидчивый. Но вот хоть отруби мне обе, Оби-Ван Кеноби, красным он не был. Давайте сделаем его бело-синим. Ну и вторую ногу приделаем, в конце концов, не Дарт Вейдер же он, без ног ходить:

<?xml version="1.0"?>
<robot name="materials">

  <material name="blue">
    <color rgba="0 0 0.8 1"/>
  </material>

  <material name="white">
    <color rgba="1 1 1 1"/>
  </material>


  <link name="base_link">
    <visual>
      <geometry>
        <cylinder length="0.6" radius="0.2"/>
      </geometry>
      <material name="blue"/>
    </visual>
  </link>

  <link name="right_leg">
    <visual>
      <geometry>
        <box size="0.6 0.1 0.2"/>
      </geometry>
      <origin rpy="0 1.57075 0" xyz="0 0 -0.3"/>
      <material name="white"/>
    </visual>
  </link>

  <joint name="base_to_right_leg" type="fixed">
    <parent link="base_link"/>
    <child link="right_leg"/>
    <origin xyz="0 -0.22 0.25"/>
  </joint>

  <link name="left_leg">
    <visual>
      <geometry>
        <box size="0.6 0.1 0.2"/>
      </geometry>
      <origin rpy="0 1.57075 0" xyz="0 0 -0.3"/>
      <material name="white"/>
    </visual>
  </link>

  <joint name="base_to_left_leg" type="fixed">
    <parent link="base_link"/>
    <child link="left_leg"/>
    <origin xyz="0 0.22 0.25"/>
  </joint>

</robot>

Давайте удалим предыдущий текст и скопируем этот в urdf-файл и запустим RViz снова: rviz-step-4.png Здесь мы определили два материала с именами blue и white, у которых задан только цвет, записанный в формате цветовой модели rgba:

  <material name="blue">
    <color rgba="0 0 0.8 1"/>
  </material>

  <material name="white">
    <color rgba="1 1 1 1"/>
  </material>

Чтобы модель выглядела реалистичнее, мы добавили описание материалов — <material name="blue"> и <material name="white">. Эти блоки задают цвета для звеньев. Здесь rgba означает цвет в формате Red-Green-Blue-Alpha. Значения от 0 до 1 определяют интенсивность цвета и прозрачность. В данном случае это тёмно-синий и белый цвета без прозрачности. Далее мы можем ссылаться на этот материал при описании визуальной составляющей, например, <material name="white"/>.

Теперь давайте возьмём полный код модели и заменим им тот, что был в urdf-файле:

<?xml version="1.0"?>
<robot name="visual">

  <material name="blue">
    <color rgba="0 0 0.8 1"/>
  </material>
  <material name="black">
    <color rgba="0 0 0 1"/>
  </material>
  <material name="white">
    <color rgba="1 1 1 1"/>
  </material>

  <link name="base_link">
    <visual>
      <geometry>
        <cylinder length="0.6" radius="0.2"/>
      </geometry>
      <material name="blue"/>
    </visual>
  </link>

  <link name="right_leg">
    <visual>
      <geometry>
        <box size="0.6 0.1 0.2"/>
      </geometry>
      <origin rpy="0 1.57075 0" xyz="0 0 -0.3"/>
      <material name="white"/>
    </visual>
  </link>

  <joint name="base_to_right_leg" type="fixed">
    <parent link="base_link"/>
    <child link="right_leg"/>
    <origin xyz="0 -0.22 0.25"/>
  </joint>

  <link name="right_base">
    <visual>
      <geometry>
        <box size="0.4 0.1 0.1"/>
      </geometry>
      <material name="white"/>
    </visual>
  </link>

  <joint name="right_base_joint" type="fixed">
    <parent link="right_leg"/>
    <child link="right_base"/>
    <origin xyz="0 0 -0.6"/>
  </joint>

  <link name="right_front_wheel">
    <visual>
      <origin rpy="1.57075 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.1" radius="0.035"/>
      </geometry>
      <material name="black"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
    </visual>
  </link>
  <joint name="right_front_wheel_joint" type="fixed">
    <parent link="right_base"/>
    <child link="right_front_wheel"/>
    <origin rpy="0 0 0" xyz="0.133333333333 0 -0.085"/>
  </joint>

  <link name="right_back_wheel">
    <visual>
      <origin rpy="1.57075 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.1" radius="0.035"/>
      </geometry>
      <material name="black"/>
    </visual>
  </link>
  <joint name="right_back_wheel_joint" type="fixed">
    <parent link="right_base"/>
    <child link="right_back_wheel"/>
    <origin rpy="0 0 0" xyz="-0.133333333333 0 -0.085"/>
  </joint>

  <link name="left_leg">
    <visual>
      <geometry>
        <box size="0.6 0.1 0.2"/>
      </geometry>
      <origin rpy="0 1.57075 0" xyz="0 0 -0.3"/>
      <material name="white"/>
    </visual>
  </link>

  <joint name="base_to_left_leg" type="fixed">
    <parent link="base_link"/>
    <child link="left_leg"/>
    <origin xyz="0 0.22 0.25"/>
  </joint>

  <link name="left_base">
    <visual>
      <geometry>
        <box size="0.4 0.1 0.1"/>
      </geometry>
      <material name="white"/>
    </visual>
  </link>

  <joint name="left_base_joint" type="fixed">
    <parent link="left_leg"/>
    <child link="left_base"/>
    <origin xyz="0 0 -0.6"/>
  </joint>

  <link name="left_front_wheel">
    <visual>
      <origin rpy="1.57075 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.1" radius="0.035"/>
      </geometry>
      <material name="black"/>
    </visual>
  </link>
  <joint name="left_front_wheel_joint" type="fixed">
    <parent link="left_base"/>
    <child link="left_front_wheel"/>
    <origin rpy="0 0 0" xyz="0.133333333333 0 -0.085"/>
  </joint>

  <link name="left_back_wheel">
    <visual>
      <origin rpy="1.57075 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.1" radius="0.035"/>
      </geometry>
      <material name="black"/>
    </visual>
  </link>
  <joint name="left_back_wheel_joint" type="fixed">
    <parent link="left_base"/>
    <child link="left_back_wheel"/>
    <origin rpy="0 0 0" xyz="-0.133333333333 0 -0.085"/>
  </joint>

  <joint name="gripper_extension" type="fixed">
    <parent link="base_link"/>
    <child link="gripper_pole"/>
    <origin rpy="0 0 0" xyz="0.19 0 0.2"/>
  </joint>

  <link name="gripper_pole">
    <visual>
      <geometry>
        <cylinder length="0.2" radius="0.01"/>
      </geometry>
      <origin rpy="0 1.57075 0 " xyz="0.1 0 0"/>
    </visual>
  </link>

  <joint name="left_gripper_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0.2 0.01 0"/>
    <parent link="gripper_pole"/>
    <child link="left_gripper"/>
  </joint>

  <link name="left_gripper">
    <visual>
      <origin rpy="0.0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://urdf_tutorial/meshes/l_finger.dae"/>
      </geometry>
    </visual>
  </link>

  <joint name="left_tip_joint" type="fixed">
    <parent link="left_gripper"/>
    <child link="left_tip"/>
  </joint>

  <link name="left_tip">
    <visual>
      <origin rpy="0.0 0 0" xyz="0.09137 0.00495 0"/>
      <geometry>
        <mesh filename="package://urdf_tutorial/meshes/l_finger_tip.dae"/>
      </geometry>
    </visual>
  </link>
  <joint name="right_gripper_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0.2 -0.01 0"/>
    <parent link="gripper_pole"/>
    <child link="right_gripper"/>
  </joint>

  <link name="right_gripper">
    <visual>
      <origin rpy="-3.1415 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://urdf_tutorial/meshes/l_finger.dae"/>
      </geometry>
    </visual>
  </link>

  <joint name="right_tip_joint" type="fixed">
    <parent link="right_gripper"/>
    <child link="right_tip"/>
  </joint>

  <link name="right_tip">
    <visual>
      <origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/>
      <geometry>
        <mesh filename="package://urdf_tutorial/meshes/l_finger_tip.dae"/>
      </geometry>
    </visual>
  </link>

  <link name="head">
    <visual>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
      <material name="white"/>
    </visual>
  </link>
  <joint name="head_swivel" type="fixed">
    <parent link="base_link"/>
    <child link="head"/>
    <origin xyz="0 0 0.3"/>
  </joint>

  <link name="box">
    <visual>
      <geometry>
        <box size="0.08 0.08 0.08"/>
      </geometry>
      <material name="blue"/>
    </visual>
  </link>

  <joint name="tobox" type="fixed">
    <parent link="head"/>
    <child link="box"/>
    <origin xyz="0.1814 0 0.1414"/>
  </joint>
</robot>

Получается вот такая модель: rviz-step-5.png Чтобы нам не мешали СК и робот был не прозрачным, в интерфейсе слева снимем галочку с TF и для RobotModel параметр Alpha установим равным 1: rviz-only-visual.png Я практически уверен, что теперь urdf-файл для вас “открытая книга”. Например, найдите в файле “голову” модели – читаем текст, и нам понятно, что она задана сферой с радиусом 0,2 м, хотя раньше про сферу мы ничего не знали. Или возьмём элемент модели left_gripper, с ним тоже всё понятно … было, пока мы не дошли до геометрии. Давайте разберемся, что же здесь написано:

  <link name="left_gripper">
    <visual>
      <origin rpy="0.0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://urdf_tutorial/meshes/l_finger.dae"/>
      </geometry>
    </visual>
  </link>

А написана здесь замечательная вещь – вид элемента модели можно задать с помощью заранее подготовленного в файла с 3D-моделью. Список простых фигур в urdf ограничен: box, cylinder, sphere. Здесь же мы взяли сложную 3D-модель, которую сделали для нас и поместили в ROS-пакет urdf_tutorial. При необходимости, мы можем самостоятельно подготовить такую модель любой сложной формы с помощью программы Blender, например.

Стоит отметить, что 3D-модели или мешы (mesh) можно использовать не только для визуальной части, но и для контроля столкновений.В URDF для описания сложных 3D-форм используются файлы .dae (Collada) и .stl(STereoLithography).

Формат .dae обычно применяется в теге <visual> — он поддерживает материалы, текстуры и сложные формы, что делает его идеальным для визуализации в RViz или Gazebo.

Формат .stl чаще используется в теге <collision>, так как содержит только геометрию (сетку треугольников), без текстур. Это упрощает и ускоряет расчёты столкновений в симуляторе.

Хотя .stl можно использовать и для визуализации, делать это не рекомендуется — отсутствие материалов делает модель слишком простой для восприятия.

Напротив, применять .dae в зоне коллизий неэффективно — из-за высокой детализации растёт вычислительная нагрузка.

Это разделение позволяет сохранить баланс между качеством графики и производительностью симуляции.

7.1.3 Описание кинематических соединений

Плохо, что робот у нас сейчас является просто скульптурой. Давайте разрешим шарнирам нашего робота двигаться. Как можно заметить, у всех соединений модели указан неподвижный тип type="fixed". Давайте их поменяем.

У нас есть возможность использовать четыре типа соединений:

Тип Описание Пример использования
fixed Жёсткое соединение Корпус робота
revolute Вращательный шарнир (ограниченный) Колено манипулятора
continuous Неограниченное вращение Колесо
prismatic Поступательное движение Линейный привод

Для соединения head_swivel установим тип type="continuous" и укажем ось вращения Z <axis xyz="0 0 1"/>. Такой тип соединения применяется в случаях, когда вращение не ограничено, например для колёс. Итак, для головы описание шарнира будет таким:

  <joint name="head_swivel" type="continuous">
    <parent link="base_link"/>
    <axis xyz="0 0 1"/>
    <child link="head"/>
    <origin xyz="0 0 0.3"/>
  </joint>

Для пальцев захватного устройства мы применим другой тип соединения revolute, для каждого из которых также зададим оси вращения, и установим ограничения на их повороты в радианах (кроме ограничений на повороты также устанавливаются ограничения на усилие и скорость вращения, но здесь мы про это говорить не будем). Опишем шарнир левого пальца:

  <joint name="left_gripper_joint" type="revolute">
    <axis xyz="0 0 1"/>
    <limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
    <origin rpy="0 0 0" xyz="0.2 0.01 0"/>
    <parent link="gripper_pole"/>
    <child link="left_gripper"/>
  </joint>

А теперь правого:

  <joint name="right_gripper_joint" type="revolute">
    <axis xyz="0 0 -1"/>
    <limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
    <origin rpy="0 0 0" xyz="0.2 -0.01 0"/>
    <parent link="gripper_pole"/>
    <child link="right_gripper"/>
  </joint>

Как видите, их описания скорректированы практически одинаково, только оси вращения направлены в противоположные стороны. И наконец, используем поступательное соединение с одной степенью свободы для руки. Оно имеет тип prismatic, оси для него задавать не нужно, а ограничения устанавливаются аналогично соединениям revolute, только не в радианах, а в метрах. Поправим текст для соединения gripper_extension следующим образом:

  <joint name="gripper_extension" type="prismatic">
    <parent link="base_link"/>
    <child link="gripper_pole"/>
    <limit effort="1000.0" lower="-0.38" upper="0" velocity="0.5"/>
    <origin rpy="0 0 0" xyz="0.19 0 0.2"/>
  </joint>

Теперь можно сохранить файл и запустить RViz с ним. Если в модели ошибок нет, мы увидим изображение нашего робота и GUI паблишера, который раньше нам только мешал, а теперь даёт возможность управления четырьмя шарнирами: joint_state_publ.png Попробуйте подвигать различные шарниры. Все соединения я расфиксировать не стал, если интересно, по ссылке есть готовый urdf-файл.

7.1.4 Контроль столкновений и физические свойства

До сих пор мы описывали наши звенья только с помощью визуальной составляющей. Однако, если мы хотим работать с реальным железом, то стоит контролировать столкновения. Параметры тела, для контроля столкновений описываются по тегом <collision>. Давайте для базового звена нашего R2-D2 установим в качестве зоны возможного столкновения цилиндр с почти теми же параметрами, что и у визуализации. Увеличим радиус цилиндра на 2 сантиметра. Будем считать, что наш робот может врезаться куда-нибудь, главное, чтобы не пытался туда же проехать. Итак, дополним перед закрывающим тегом </link> для базового звена <link name="base_link"> описание следующим текстом:

    <collision>
      <geometry>
        <cylinder length="0.6" radius="0.22"/>
      </geometry>
    </collision>

Давайте попробуем запустить RViz с такой правкой и убедимся, что модель не сломана и работает. Если мы поставим галочку Collision Enabled в интерфейсе модели робота, то увидим, как появится цилиндр для описания зоны столкновения: rviz-collision.png

Мы видим, что геометрия зоны столкновения описывается тегом <geometry>, как и геометрия визуализации. В принципе, можно подумать, что это лишний элемент, если он повторяет визуализацию, но достаточно часто параметры зоны столкновения не совпадает с параметрами визуализации. Например, у вас есть сложное звено, отрисовка которого уже значительно загружает вычислительные мощности компьютера, если мы просто скопируем параметры визуализации для контроля столкновений, мы получим очень точный, но очень медленный программный продукт. И второй момент – а нам нужна такая высокая точность контроля столкновений? Да нет, конечно. Мы можем серьёзно упростить фигуры для контроля столкновений, так как именно столкновения нам не нужны, а мы планируем работать с машинами, у которых есть физические свойства, инерция, например. Остановить такие машины в микроне от препятствия фактически невозможно. Кстати, о физических свойствах. Если мы всё-таки хотим использовать urdf-файлы в Gazebo, нам надо задать инерционные параметры. Их можно задать для каждого звена с помощью тега inertial. Например:

    <inertial>
      <mass value="10"/>
      <inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
    </inertial>

Здесь мы устанавливаем массу в килограммах и матрицу тензора инерции. Тензор инерции – это математическое представление распределения массы звена относительно его осей. Он учитывается при моделировании движения робота и влияет на устойчивость и динамику. Тензор записывается в виде матрицы 3×3, где диагональные элементы (ixx, iyy, izz) — это моменты инерции относительно осей X, Y и Z соответственно. Остальные элементы (ixy, ixz, iyz) описывают асимметрию распределения массы.

Например, для куба массой m = 1 кг и длиной ребра a = 0.2 м:

ixx = iyy = izz = (1/6) * m * a² = (1/6) * 1 * 0.04 = 0.0067 кг·м²

Матрица симметрична и для упрощения записи задана шестью элементами без нижней поддиагонали. В URDF такие значения задаются внутри тега <inertial>.

<inertial>
  <mass value="1.0"/>
  <origin xyz="0 0 0"/>
  <inertia ixx="0.0067" ixy="0.0" ixz="0.0"
           iyy="0.0067" iyz="0.0"
           izz="0.0067"/>
</inertial>

Правильное описание тензора инерции позволяет симулятору (например, Gazebo) точнее рассчитывать поведение звеньев робота при движении и взаимодействии с объектами.

Ещё внутри элемента <inertial> с помощью тега origin мы имеем возможность сместить центр масс звена <origin xyz="0 0 0"/>относительно системы координат звена.

Также мы можем дополнить физическое описание контактными коэффициентами, которые определят трение при контакте и параметрами соединения. Но пока нам это не нужно, я уверен, что мы уже способны понять urdf-файл манипулятора UR5.

7.1.5 Кинематика модели в urdf

Итак, у нас есть файл, который описывает манипулятор:

<?xml version="1.0" encoding="utf-8"?>

<robot name="ur5">
  <link name="base_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/base.dae"/>
      </geometry>
    </visual>
  </link>
  <joint name="shoulder_pan_joint" type="revolute">
    <parent link="base_link"/>
    <child link="shoulder_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.089159"/>
    <axis xyz="0 0 1"/>
    <limit effort="150.0" lower="-3.14159265" upper="3.14159265" velocity="3.15"/>
  </joint>
  <link name="shoulder_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/shoulder.dae"/>
      </geometry>
    </visual>
  </link>
  <joint name="shoulder_lift_joint" type="revolute">
    <parent link="shoulder_link"/>
    <child link="upper_arm_link"/>
    <origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.13585 0.0"/>
    <axis xyz="0 1 0"/>
    <limit effort="150.0" lower="-3.14159265" upper="3.14159265" velocity="3.15"/>
  </joint>
  <link name="upper_arm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/upperarm.dae"/>
      </geometry>
    </visual>
  </link>
  <joint name="elbow_joint" type="revolute">
    <parent link="upper_arm_link"/>
    <child link="forearm_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 -0.1197 0.425"/>
    <axis xyz="0 1 0"/>
    <limit effort="150.0" lower="-3.14159265" upper="3.14159265" velocity="3.15"/>
  </joint>
  <link name="forearm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/forearm.dae"/>
      </geometry>
    </visual>
  </link>
  <joint name="wrist_1_joint" type="revolute">
    <parent link="forearm_link"/>
    <child link="wrist_1_link"/>
    <origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.0 0.39225"/>
    <axis xyz="0 1 0"/>
    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
  </joint>
  <link name="wrist_1_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/wrist1.dae"/>
      </geometry>
    </visual>
  </link>
  <joint name="wrist_2_joint" type="revolute">
    <parent link="wrist_1_link"/>
    <child link="wrist_2_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.093 0.0"/>
    <axis xyz="0 0 1"/>
    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
  </joint>
  <link name="wrist_2_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/wrist2.dae"/>
      </geometry>
    </visual>
  </link>
  <joint name="wrist_3_joint" type="revolute">
    <parent link="wrist_2_link"/>
    <child link="wrist_3_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.09465"/>
    <axis xyz="0 1 0"/>
    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
  </joint>
  <link name="wrist_3_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/wrist3.dae"/>
      </geometry>
    </visual>
  </link>
</robot>

Как мы видим, здесь не задаются ни зоны столкновений, ни физические параметры, фактически, файл описывает кинематическую схему манипулятора. Давайте её и разберём. Модель манипулятора состоит из семи звеньев:

  • Основание – base_link,
  • Ключица (назовём так) – shoulder_link,
  • Плечо – upper_arm_link,
  • Предплечье – forearm_link,
  • Первое звено запястья – wrist_1_link,
  • Второе звено запястья – wrist_2_link,
  • Третье звено запястья – wrist_3_link. Звенья соединены шестью шарнирами:
  • Шарнир рыскания плеча – shoulder_pan_joint,
  • Шарнир тангажа плеча – shoulder_lift_joint,
  • Локтевой шарнир (тангаж) – elbow_joint,
  • Первый шарнир кисти (тангаж) – wrist_1_joint,
  • Второй шарнир кисти (рыскание) – wrist_2_joint,
  • Третий шарнир кисти (крен) – wrist_3_joint. Схему можно представить в виде такого графа:
graph LR
    lB(("base_link"))
    lSh(("shoulder_link"))
    lUA(("upper_arm_link"))
    lFA(("forearm_link"))
    lW1(("wrist_1_link"))
    lW2(("wrist_2_link"))
    lW3(("wrist_3_link"))
    lB-->|"shoulder_pan_joint (0, 0, 0)"|lSh
    lSh-->|"shoulder_lift_joint (0, &pi;/2, 0)"|lUA
    lUA-->|"elbow_joint (0, 0, 0)"|lFA
    lFA-->|"wrist_1_joint (0, &pi;/2, 0)"|lW1
    lW1-->|"wrist_2_joint (0, 0, 0)"|lW2
    lW2-->|"wrist_3_joint (0, 0, 0)"|lW3

Вот тут придётся напрячься. Начнём с того, что здесь мы не строим модель манипулятора в некотором классическом виде, например, методом Денавита-Хартенберга. Строим мы здесь её графическое (как мы выяснили – не только, но в основном графическое) представление. То есть, здесь соединения не обязательно вращаются вокруг оси Z своей системы координат, а СК звена не обязательно расположена, а чаще всего и не расположена в его конечной точке. Модель из urdf-файла в математическую модель за нас потом переведёт ROS. Придётся нам снова отойти от UR5. Итак, работаем с визуализацией.

<?xml version="1.0" encoding="utf-8"?>

<robot name="dummy">
  <link name="base_link">
    <visual>
      <geometry>
  <cylinder length="0.05" radius="0.1"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0.025"/>
    </visual>
  </link>
  <link name="shoulder">
    <visual>
      <geometry>
  <cylinder length="0.1" radius="0.12"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0.05"/>
    </visual>
  </link>
  <link name="link2">
    <visual name="body">
      <geometry>
  <box size="0.08 0.08 0.6"/>
      </geometry>
      <origin rpy="0 0.0 0" xyz="0 0 0.0"/>
    </visual>
  </link>
  <joint name="base_roll" type="fixed">
    <parent link="base_link"/>
    <child link="shoulder"/>
    <origin rpy="0 1.57075 0" xyz="0.0 0.0 0.17"/>
  </joint>
  <joint name="shoulder_joint" type="fixed">
    <parent link="shoulder"/>
    <child link="link2"/>
    <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  </joint>
</robot>

У звена мы можем сместить его визуализацию помощью тега origin. Предположим, у нас есть брусок с размерами <box size="0.08 0.08 0.6"/>, то есть, он имеет длину вдоль оси Z 0,6 метра. Мы можем сместить визуализацию на +0,3 метра по оси Z <origin rpy="0 0 0" xyz="0 0 0.3"/>: visual-plus-03.png

Можем сместить на -0,3 метра по оси Z <origin rpy="0 0 0" xyz="0 0 -0.3"/>: visual-minus-03.png

А можем никуда не смещать <origin rpy="0 0 0" xyz="0 0 0"/>: vusal-minus-03.png

Мы можем даже повернуть визуализацию, система координат нашего звена от этого никуда не сместиться <origin rpy="0 0.7854 0" xyz="0 0 -0.3"/>: visual-shift-rotate.png

Её положение и поворот должны быть заданы тегом origin соединения, для которого звено является дочерним. Подробнее, центр системы координат дочернего для соединения звена “приравнивается” к СК центра соединения.

Давайте теперь чуть усложним визуализацию и разберёмся с шарнирами. Я чуть усложнил предыдущую urdf-модель манипулятора с тремя звеньями, базой, плечом и балкой, визуализацию которой мы только что перемещали и вращали. Я добавил к балке ещё один элемент, назовём его выходным валом привода. Получилась такая модель: dummy-zero.png

Построена она на основе вот такого urdf-файла:

<?xml version="1.0" encoding="utf-8"?>

<robot name="dummy">
  <link name="base_link">
    <visual>
      <geometry>
  <cylinder length="0.05" radius="0.1"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0.025"/>
    </visual>
  </link>
  <link name="shoulder">
    <visual>
      <geometry>
  <cylinder length="0.1" radius="0.12"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0.05"/>
    </visual>
  </link>
  <link name="boom">
    <visual name="spindle">
      <geometry>
  <cylinder length="0.1" radius="0.08"/>
      </geometry>
      <origin rpy="0 0.0 0" xyz="0 0 0.05"/>
    </visual>
    <visual name="body">
      <geometry>
  <box size="0.08 0.08 0.6"/>
      </geometry>
      <origin rpy="0 0.0 0" xyz="0 0 0.3"/>
    </visual>
  </link>
<joint name="base_roll" type="revolute">
    <parent link="base_link"/>
    <child link="shoulder"/>
    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
    <origin rpy="0 1.57075 0" xyz="0.0 0.0 0.17"/>
  </joint>
  <joint name="shoulder_joint" type="revolute">
    <parent link="shoulder"/>
    <child link="boom"/>
    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  </joint>
</robot>

Первое, что я хотел бы продемонстрировать, это вынести балку влево по предыдущему рисунку, сместив шарнир. Положение и поворот СК соединения задаётся также тегом origin, но уже для соединения, и задаётся в системе координат родительского звена. На СК видно плохо, поэтому посмотрим поближе, прозрачность модели повысим, а все TF, кроме shoulder погасим. Мы видим, что смещать нам надо по синей оси, то есть по Z: dummy-shoulder-tf.png

Сместим шарнир на половину высоты “выходного вала”. В звене boom это элемент spindle – вы ведь заметили, что там два элемента visual, да, так можно, кстати, и с зонами столкновений тоже можно – и его параметр length="0.1". Теперь для соединения shoulder исправим origin вот так <origin rpy="0 0 0" xyz="0.0 0.0 0.05"/> и запустим модель в RViz: dummy-shifted-boom.png

Результат замечательный, мы сделали, что хотели. Давайте теперь повращаем шарниры нашего “робота”. Первым делом я повернул первый шарнир на -45° и увидел, что это хорошо. dummy-rotate-first.png

“Хорошо-хорошо, да не очень-то”.

Чего это он у нас вокруг оси X вращается? А вот как написали, так и вращается. По умолчанию все шарниры вращаются вокруг оси X их собственной СК, ну или СК дочернего звена, что для нас здесь одно и то же. Вот тут у меня нехорошее предчувствие, что же будет со вторым шарниром – его мне бы хотелось вращать вокруг оси Z, ведь вокруг оси X “манипулятор” уже поворачивает предыдущий шарнир. Не будем долго раздумывать, решительно сбросим углы до нулевых значений и повернём второй шарнир на те же -45°, что и первый: dummy-rotate-sec.png

Нет, ребята, всё не так! Всё не так, ребята…

Получилась ерунда какая-то, но дело поправимое, давайте просто изменим ось вращения второго шарнира, добавив к описанию шарнира единичный вектор, который и будет осью вращения. Зададим его так: <axis xyz="0 0 1"/> и попробуем повернуть шарнир теперь: dummy-isnt-dummy.png

Замечательно, теперь вращается как надо. Если хотите, можете установить ось вращения соединения какого-нибудь экзотического направления, например <axis xyz="0 0.7071 0.7071"/>, и посмотреть, что получится.

7.3 Использование urdf в Gazebo

Как мы уже говорили, urdf-файлы могут содержать информацию не только о визуальной модели робота, но и некоторых о его физических параметрах. Это может нам пригодиться, если мы моделируем робот с помощью Gazebo. Gazebo понимает формат urdf, может его прочитать и перевести в собственный формат sdf.

Давайте подготовим среду для запуска симуляции UR5 в Gazebo.

7.3.1 Подготовка docker-файла

Для начала подготовим docker-файл.

Файл Dockerfile:

FROM osrf/ros:noetic-desktop-full

WORKDIR /home/urdf
COPY ur5_gazebo.urdf /home/urdf/ur5_gazebo.urdf

RUN apt update -y && apt upgrade -y && apt install git -y
RUN echo "source /opt/ros/noetic/setup.bash" >> /home/.bashrc

WORKDIR /home/catkin_ws/src
RUN git clone -b $ROS_DISTRO-devel https://github.com/ros-industrial/universal_robot.git

WORKDIR /home/catkin_ws
RUN rosdep update && rosdep install --rosdistro $ROS_DISTRO --ignore-src --from-paths src -y

WORKDIR /home/catkin_ws
RUN /bin/bash -c '. /opt/ros/noetic/setup.bash; catkin_make'
RUN echo "source /home/catkin_ws/devel/setup.bash" >> /home/.bashrc

COPY launch.sh /home/launch.sh
RUN chmod +x /home/launch.sh

ENTRYPOINT [ "/home/launch.sh" ]

Теперь, когда мы уже достаточно уверенно понимаем docker-файлы, мы видим, что в образ нам надо будет скопировать urdf-файл с моделью робота UR5 для Gazebo ur5_gazebo.urdf и скрипт запуска launch.sh, который запустит пустой мир Gazebo. Почему пустой – разберёмся чуть позже, сейчас мы возьмём уже готовый urdf-файл и найдём в нём новое для нас.

7.3.2 Элементы urdf-файла, полезные для использования в Gazebo

Давайте рассмотрим urdf-файл из репозитория роботов universal_robot сообщества ROS-Industrial. ROS-Industrial – это открытый проект, расширяющий ROS для промышленного применения, предоставляющий готовые пакеты для промышленных роботов (включая UR, Fanuc, KUKA) и стандартизированные инструменты для их интеграции в производственные процессы.

<?xml version="1.0" encoding="utf-8"?>

<robot name="ur5">
  <link name="base_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/base.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/base.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4.0"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
    </inertial>
  </link>
  <joint name="shoulder_pan_joint" type="revolute">
    <parent link="base_link"/>
    <child link="shoulder_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.089159"/>
    <axis xyz="0 0 1"/>
    <limit effort="150.0" lower="-3.14159265" upper="3.14159265" velocity="3.15"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="shoulder_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/shoulder.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="3.7"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.010267495893" ixy="0.0" ixz="0.0" iyy="0.010267495893" iyz="0.0" izz="0.00666"/>
    </inertial>
  </link>
  <joint name="shoulder_lift_joint" type="revolute">
    <parent link="shoulder_link"/>
    <child link="upper_arm_link"/>
    <origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.13585 0.0"/>
    <axis xyz="0 1 0"/>
    <limit effort="150.0" lower="-3.14159265" upper="3.14159265" velocity="3.15"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="upper_arm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/upperarm.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/upperarm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="8.393"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.28"/>
      <inertia ixx="0.22689067591" ixy="0.0" ixz="0.0" iyy="0.22689067591" iyz="0.0" izz="0.0151074"/>
    </inertial>
  </link>
  <joint name="elbow_joint" type="revolute">
    <parent link="upper_arm_link"/>
    <child link="forearm_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 -0.1197 0.425"/>
    <axis xyz="0 1 0"/>
    <limit effort="150.0" lower="-3.14159265" upper="3.14159265" velocity="3.15"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="forearm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/forearm.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/forearm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="2.275"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.25"/>
      <inertia ixx="0.049443313556" ixy="0.0" ixz="0.0" iyy="0.049443313556" iyz="0.0" izz="0.004095"/>
    </inertial>
  </link>
  <joint name="wrist_1_joint" type="revolute">
    <parent link="forearm_link"/>
    <child link="wrist_1_link"/>
    <origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.0 0.39225"/>
    <axis xyz="0 1 0"/>
    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_1_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/wrist1.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/wrist1.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.219"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.111172755531" ixy="0.0" ixz="0.0" iyy="0.111172755531" iyz="0.0" izz="0.21942"/>
    </inertial>
  </link>
  <joint name="wrist_2_joint" type="revolute">
    <parent link="wrist_1_link"/>
    <child link="wrist_2_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.093 0.0"/>
    <axis xyz="0 0 1"/>
    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_2_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/wrist2.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/wrist2.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.219"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.111172755531" ixy="0.0" ixz="0.0" iyy="0.111172755531" iyz="0.0" izz="0.21942"/>
    </inertial>
  </link>
  <joint name="wrist_3_joint" type="revolute">
    <parent link="wrist_2_link"/>
    <child link="wrist_3_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.09465"/>
    <axis xyz="0 1 0"/>
    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_3_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/visual/wrist3.dae"/>
      </geometry>
      <material name="LightGrey">
        <color rgba="0.7 0.7 0.7 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/wrist3.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1879"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.0171364731454" ixy="0.0" ixz="0.0" iyy="0.0171364731454" iyz="0.0" izz="0.033822"/>
    </inertial>
  </link>
  <joint name="ee_fixed_joint" type="fixed">
    <parent link="wrist_3_link"/>
    <child link="ee_link"/>
    <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0823 0.0"/>
  </joint>
  <link name="ee_link">
    <collision>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.01 0 0"/>
    </collision>
  </link>
  <!-- define the ur5's position and orientation in the world coordinate system -->
  <link name="world"/>
  <joint name="world_joint" type="fixed">
    <parent link="world"/>
    <child link="base_link"/>
    <!-- TODO: check base_link name of robot -->
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  </joint>
</robot>

Мы имеем уже готовый файл urdf-моделью UR5 и представляем, как строится кинематическая схема, но пока не знаем ничего об элементах, необходимых для симуляции: описание масс-инерционных параметров звеньев, зоны столкновений, динамика приводов. Также мы увидим, что робота есть физическая связь с миром симулятора, основание манипулятора связано с “землёй”. Пойдём по неведомым нам пока дорожкам.

Масс-инерционные характеристики

Давайте для примера рассмотрим элемент под тегом inertial для звена upper_arm_link:

    <inertial>
      <mass value="8.393"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.28"/>
      <inertia ixx="0.22689067591" ixy="0.0" ixz="0.0" iyy="0.22689067591" iyz="0.0" izz="0.0151074"/>
    </inertial>

Мы видим, что у нас есть звено с 8.393 кг. и центром масс, смещённым на 0,28 по оси Z СК звена (обозначил красной точкой на рисунке ниже): upper-arm-cm.png Матрица тензора инерции здесь диагональная, поэтому я не думаю, что эти параметры очень точные, но UR5 – достаточно популярный робот, поэтому при желании найти для него данные не составит проблемы. Эти данные, а точнее, весь urdf-файл, я взял из учебного пособия и думаю им довериться, так как сейчас для нас их точность не играет никакой роли. Но, конечно же, если вы разрабатываете модель робота самостоятельно, старайтесь найти данные из достоверного источника. Ну и ещё раз напомню, что нам нужно задать только шесть чисел для матрицы тензора инерции, так как она симметричная.

Зоны столкновений

Как мы уже говорили, для корректной симуляции или отработки на реальном оборудовании необходимо просчитывать возможные столкновения робота с окружением и соударения звеньев. Такие зоны задаются элементами звеньев с тегом collision. Этот элемент похож на элемент визуализации, однако обычно его делают более простым для расчётов, чем визуальные модели. В нашем случае модель зоны столкновения для звена задаётся файлом формата STL (stereolithography), в котором поверхность описывается сеткой из треугольников. В отличии от dae-файлов, в котором мы можем задавать текстуры и блики, например, файлы stl такими возможностями не обладают. Однако, stl-файл могут быть значительно меньше dae-файлов, поэтому есть смысл применять их для задания зон столкновений, если 3D-модель задаётся с помощью сеток (mesh). Удобно также то, что разработанную dae-модель звена мы можем легко преобразовать в формат stl с упрощением, при необходимости. То есть, нам не надо дополнительно разрабатывать модель для зон столкновения. В нашем случае для звена upper_arm_link зона столкновения задаётся так:

    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/upperarm.stl"/>
      </geometry>
    </collision>

Ограничения и динамика соединений

Внутри элемента по тегом joint, мы уже задавали ограничения limit. Кроме ограничений на максимум и минимум здесь есть параметр effort, определяющий, какое максимальное усилие может приложить к шарниру привод (в Ньютонах для поступательных пар и Нм для вращательных) .Превышение этого значения может привести к аварии или остановке.

Также мы можем добавить настройку динамики соединения dynamics с возможностью задать демпфирование и статическое трение соединения.

<limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
<dynamics damping="0.0" friction="0.0"/>

Давайте разберёмся, что определяют новые для на нас параметры и вспомним, что мы говорили про ограничения.

Все эти параметры определяют физическое поведение соединения в симуляции Gazebo или при управлении реальным роботом при написании так называемых контроллеров ROS:

  1. limit — ограничения шарнира:
    • effort="ЧИСЛО" — максимальное усилие (в Н·м для вращательных шарниров, Н для поступательных). Превышение может привести к остановке привода.
    • lower="ЧИСЛО" и upper="ЧИСЛО" — минимальный и максимальный угол (в радианах) или ограничения на линейное перемещение (в метрах). Для type="continuous" игнорируются.
    • velocity="ЧИСЛО" — предельная скорость (рад/с или м/с).
  2. dynamics — динамические свойства:
    • damping="ЧИСЛО" — коэффициент демпфирования (вязкого трения). Чем выше, тем быстрее шарнир “тормозит” при отсутствии усилия.
    • friction="ЧИСЛО" — статическое трение. Ненулевое значение имитирует сопротивление в начале движения (например, люфт редуктора).

В примере для упрощения настройки симуляции мы взяли нулевые damping и friction, но в реальном проекте их нужно настраивать по данным производителя.

Закрепление робота на “земле”

В качестве последнего шага создания модели добавим дополнительное соединение в наш urdf-файл. Это замороженный шарнир “крепление к миру”, если можно так сказать. Его единственная цель – закрепить нашего робота в моделируемом мире, поэтому мы определим world как родительскую ссылку и base_link как дочернюю ссылку:

<link name="world"/>
<joint name="world_joint" type="fixed">
  <parent link="world"/>
  <child link="base_link"/>
  <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>

Теперь с urdf-файлом для Gazebo мы закончили.

7.3.3 Запуск симуляции

Для запуска мы подготовим скрипт launch.sh:

#!/usr/bin/env bash

. /home/.bashrc
export LIBGL_ALWAYS_SOFTWARE=1

roslaunch gazebo_ros empty_world.launch

Файл empty_world.launch используется как минимальная стартовая точка для запуска симулятора Gazebo без предустановленных объектов, чтобы можно было загрузить туда свою модель робота. Это позволяет начать с “чистого листа” и избежать влияния лишних объектов на симуляцию.

И теперь, когда у нас есть всё необходимое, построим docker-образ и запустим Gazebo:

docker build . --tag ur5_gazebo
docker run -it --rm --env="DISPLAY" --env="QT_X11_NO_MITSHM=1" --volume="/tmp/.X11-unix:/tmp/.X11-unix:rw" ur5_gazebo

Теперь мы должны добавить нашу urdf-модель в Gazebo. Отмечу, что здесь мы именно добавляем модель робота в симуляцию Gazebo, а не файл, описывающий модель, в docker-файл.

Давайте выполним эти команды:

docker ps
# Здесь мы получим идентификаторы контейнеров, из которых возьмём нужный CONTAINER_ID для подключения
docker exec -it <CONTAINER_ID> bash
# После подключения к контейнеру
. /home/.bashrc
rosrun gazebo_ros spawn_model -file /home/urdf/ur5_gazebo.urdf -urdf -x 0 -y 0 -z 0.1 -model ur5

Чтобы выполнить команду rosrun, нам пришлось подключиться к работающему контейнеру. Если бы мы это делали не в контейнере, просто вызвали бы второй терминал и запустили последнюю команду. Кстати, чтобы не запрашивать каждый раз идентификатор контейнера, мы можем подключаться к контейнеру по имени, которое присвоим сами. В этом поможет простой советский ключ --name <заданное имя контейнера> при запуске контейнера. Теперь нам не надо выяснять, как зовут контейнер, мы можем подключиться к нему docker exec -it <заданное имя контейнера> bash. Удобно? Несомненно. Хорошо, наша модель заспавнилась в Gazebo:

UR5-gazebo.png

Пока что неподвижная модель робота в Gazebo это всё, что нам нужно. А вот на следующем занятии мы попробуем этот механизм подвигать как робот в симуляции.

7.4 Заключение

Заключение

Сегодня вы сделали важный шаг в понимании того, как роботы “видят” себя — а точнее, как мы описываем их конструкцию для компьютера. В мире робототехники важно не только уметь управлять датчиками и двигателями, но и знать, с чем именно вы работаете. Для этого в ROS используется специальный язык описания — URDF (Unified Robot Description Format).

Вы научились создавать модели роботов, используя звенья (link) и соединения (joint), задавать форму и цвет деталей, указывать массу и распределение инерции. Это похоже на то, как конструктор собирает модель из конструктора LEGO, только вместо пластмассовых блоков вы используете XML-теги. Такие файлы позволяют не только визуализировать робот в RViz, но и запускать его в симуляторе Gazebo, где он взаимодействует с окружающим миром с учётом физики.

Важно, что теперь вы можете подключить эти модели к реальным системам управления, например, использовать данные из топиков или писать Python-скрипты, которые двигают шарниры, анализируют положение звеньев или готовят робота к работе с захватом. Это становится возможным благодаря тому, что URDF — это не просто чертёж, а полноценная структура данных, которую используют другие части системы, такие как планировщики движений или контроллеры.

Кроме того, вы продолжили осваивать контейнеризацию Docker, применяя её для запуска сложных симуляций без перегрузки своей машины. Это как работать в отдельной “лаборатории”, куда можно принести всё необходимое — библиотеки, модели, инструменты — и при этом не беспокоиться о совместимости с вашей системой.

Сегодняшний урок стал мостиком между программированием, физикой и визуализацией. Вы получили навыки, которые лежат в основе таких задач, как: - управление манипуляторами, - взаимодействие с объектами в трёхмерном пространстве.

Теперь вы можете взять описание любого робота, загрузить его в симулятор, проверить, как он будет двигаться, и подготовить его к управлению. Это открывает перед вами возможность не просто наблюдать за роботами, а проектировать их поведение.