设置机器人仿真(基础)

**目标:**设置机器人仿真并通过ROS 2进行控制。

教程级别: 高级

**时间:**30分钟

背景

在本教程中,您将使用Webots机器人仿真器来设置和运行一个非常简单的ROS 2仿真场景。

webots_ros2 包提供了ROS 2和Webots之间的接口。它包含了几个子包,但在本教程中,您只会使用``webots_ros2_driver``子包来实现一个控制模拟机器人的Python或C++插件。其他一些子包包含了不同机器人的演示,比如TurtleBot3。它们在 Webots ROS 2 examples 页面有文档记录。

先决条件

建议您先了解在初学者教程 教程 中介绍的基本ROS原理。特别是 使用 turtlesim 、 ros2 和 rqt理解话题创建一个工作空间创建软件包创建一个启动文件 是有用的先决条件。

本教程中的Linux和ROS命令可以在标准的Linux终端中运行。下一页 安装(Ubuntu) 解释了如何在Linux上安装 webots_ros2 包。

本教程与 webots_ros2 的版本 2023.1.0 和 Webots R2023b 以及即将发布的版本兼容。

任务

1 创建软件包结构

我们将在一个自定义的ROS 2软件包中组织代码。从ROS 2工作空间的 src 文件夹中创建一个名为 my_package 的新软件包。将终端的当前目录更改为 ros2_ws/src 并运行以下命令:

ros2 pkg create --build-type ament_python --license Apache-2.0 --node-name my_robot_driver my_package --dependencies rclpy geometry_msgs webots_ros2_driver

选项 --node-name my_robot_driver 将在 my_package 子文件夹中创建一个名为 my_robot_driver.py 的模板Python插件,稍后您将对其进行修改。选项 --dependencies rclpy geometry_msgs webots_ros2_driverpackage.xml 文件中指定了 my_robot_driver.py 插件所需的软件包。

让我们在 my_package 文件夹内添加一个 launch 和一个 worlds 文件夹。

cd my_package
mkdir launch
mkdir worlds

最终你应该得到以下的文件结构:

src/
└── my_package/
    ├── launch/
    ├── my_package/
    │   ├── __init__.py
    │   └── my_robot_driver.py
    ├── resource/
    │   └── my_package
    ├── test/
    │   ├── test_copyright.py
    │   ├── test_flake8.py
    │   └── test_pep257.py
    ├── worlds/
    ├── package.xml
    ├── setup.cfg
    └── setup.py

2 设置仿真世界

您需要一个包含机器人的世界文件来启动仿真。:download:`下载这个世界文件 <Code/my_world.wbt>`并将其移动到``my_package/worlds/``文件夹中。

实际上,这是一个相当简单的文本文件,您可以在文本编辑器中查看。这个``my_world.wbt``世界文件中已经包含了一个简单的机器人。

注解

如果您想学习如何在Webots中创建自己的机器人模型,您可以查看这个`教程 <https://cyberbotics.com/doc/guide/tutorial-6-4-wheels-robot>`_。

3 编辑``my_robot_driver``插件

``webots_ros2_driver``子包会自动为大多数传感器创建ROS 2接口。关于现有设备接口的更多细节以及如何配置它们,请参阅教程的第二部分: 设置机器人模拟(高级)。在这个任务中,您将通过创建自己的自定义插件来扩展这个接口。这个自定义插件是一个等效于机器人控制器的ROS节点。您可以使用它来访问`Webots机器人API <https://cyberbotics.com/doc/reference/robot?tab-language=python>`_,并创建自己的话题和服务来控制您的机器人。

注解

本教程的目的是展示一个最小依赖的基本示例。但是,您可以通过使用另一个名为``webots_ros2_control``的``webots_ros2``子包来避免使用此插件,这将引入新的依赖项。该子包创建了与``ros2_control``包的接口,以便更容易控制差分轮式机器人。

在您喜欢的编辑器中打开``my_package/my_package/my_robot_driver.py``并将其内容替换为以下内容:

import rclpy
from geometry_msgs.msg import Twist

HALF_DISTANCE_BETWEEN_WHEELS = 0.045
WHEEL_RADIUS = 0.025

class MyRobotDriver:
    def init(self, webots_node, properties):
        self.__robot = webots_node.robot

        self.__left_motor = self.__robot.getDevice('left wheel motor')
        self.__right_motor = self.__robot.getDevice('right wheel motor')

        self.__left_motor.setPosition(float('inf'))
        self.__left_motor.setVelocity(0)

        self.__right_motor.setPosition(float('inf'))
        self.__right_motor.setVelocity(0)

        self.__target_twist = Twist()

        rclpy.init(args=None)
        self.__node = rclpy.create_node('my_robot_driver')
        self.__node.create_subscription(Twist, 'cmd_vel', self.__cmd_vel_callback, 1)

    def __cmd_vel_callback(self, twist):
        self.__target_twist = twist

    def step(self):
        rclpy.spin_once(self.__node, timeout_sec=0)

        forward_speed = self.__target_twist.linear.x
        angular_speed = self.__target_twist.angular.z

        command_motor_left = (forward_speed - angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) / WHEEL_RADIUS
        command_motor_right = (forward_speed + angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) / WHEEL_RADIUS

        self.__left_motor.setVelocity(command_motor_left)
        self.__right_motor.setVelocity(command_motor_right)

正如您所看到的,``MyRobotDriver``类实现了三个方法。

第一个方法名为``init(self, ...)`',实际上是Python中``__init__(self, ...)`构造函数的ROS节点对应方法。``init``方法始终接受两个参数:

  • ``webots_node``参数包含对Webots实例的引用。

  • ``properties``参数是从URDF文件(4 创建my_robot.urdf文件)中提取的XML标签创建的字典,它允许您将参数传递给控制器。

来自仿真的机器人实例``self.__robot``可用于访问`Webots机器人API<https://cyberbotics.com/doc/reference/robot?tab-language=python>`_。然后,它获取两个电机实例,并使用目标位置和目标速度进行初始化。最后,创建一个ROS节点,并为名为``/cmd_vel``的ROS主题注册一个回调方法,该回调方法将处理``Twist``消息。

def init(self, webots_node, properties):
    self.__robot = webots_node.robot

    self.__left_motor = self.__robot.getDevice('left wheel motor')
    self.__right_motor = self.__robot.getDevice('right wheel motor')

    self.__left_motor.setPosition(float('inf'))
    self.__left_motor.setVelocity(0)

    self.__right_motor.setPosition(float('inf'))
    self.__right_motor.setVelocity(0)

    self.__target_twist = Twist()

    rclpy.init(args=None)
    self.__node = rclpy.create_node('my_robot_driver')
    self.__node.create_subscription(Twist, 'cmd_vel', self.__cmd_vel_callback, 1)

然后,实现了``__cmd_vel_callback(self, twist)``回调私有方法,该方法将在``/cmd_vel``主题接收到每个``Twist``消息时被调用,并将其保存在``self.__target_twist``成员变量中。

def __cmd_vel_callback(self, twist):
    self.__target_twist = twist

最后,在仿真的每个时间步骤中调用``step(self)``方法。调用``rclpy.spin_once()``是为了保持ROS节点的平稳运行。在每个时间步骤中,该方法将从``self.__target_twist``中获取所需的``forward_speed``和``angular_speed``。由于电机受到角速度的控制,该方法将把``forward_speed``和``angular_speed``转换为每个轮子的单独命令。此转换取决于机器人的结构,更具体地说是轮子的半径和它们之间的距离。

def step(self):
    rclpy.spin_once(self.__node, timeout_sec=0)

    forward_speed = self.__target_twist.linear.x
    angular_speed = self.__target_twist.angular.z

    command_motor_left = (forward_speed - angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) / WHEEL_RADIUS
    command_motor_right = (forward_speed + angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) / WHEEL_RADIUS

    self.__left_motor.setVelocity(command_motor_left)
    self.__right_motor.setVelocity(command_motor_right)

4 创建 my_robot.urdf 文件

您现在需要创建一个URDF文件来声明``MyRobotDriver``插件。这将允许``webots_ros2_driver`` ROS节点启动插件并将其连接到目标机器人。

在``my_package/resource``文件夹中创建一个名为``my_robot.urdf``的文本文件,其内容如下:

<?xml version="1.0" ?>
<robot name="My robot">
    <webots>
        <plugin type="my_package.my_robot_driver.MyRobotDriver" />
    </webots>
</robot>

``type``属性指定了根据文件的层次结构给出的类路径。``webots_ros2_driver``负责根据指定的软件包和模块加载类。

注解

这个简单的URDF文件不包含关于机器人的任何链接或关节信息,因为在本教程中不需要。然而,URDF文件通常包含更多的信息,如在 URDF 教程中所解释的。

注解

这里的插件不接受任何输入参数,但可以通过包含参数名的标签来实现。

<plugin type="my_package.my_robot_driver.MyRobotDriver">
    <parameterName>someValue</parameterName>
</plugin>

这主要用于向现有的Webots设备插件传递参数(参见 设置机器人模拟(高级))。

5 创建启动文件

让我们创建启动文件,以便可以通过一个命令轻松启动仿真和ROS控制器。在``my_package/launch``文件夹中创建一个名为``robot_launch.py``的新文本文件,并使用以下代码:

import os
import launch
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
from webots_ros2_driver.webots_launcher import WebotsLauncher
from webots_ros2_driver.webots_controller import WebotsController


def generate_launch_description():
    package_dir = get_package_share_directory('my_package')
    robot_description_path = os.path.join(package_dir, 'resource', 'my_robot.urdf')

    webots = WebotsLauncher(
        world=os.path.join(package_dir, 'worlds', 'my_world.wbt')
    )

    my_robot_driver = WebotsController(
        robot_name='my_robot',
        parameters=[
            {'robot_description': robot_description_path},
        ]
    )

    return LaunchDescription([
        webots,
        my_robot_driver,
        launch.actions.RegisterEventHandler(
            event_handler=launch.event_handlers.OnProcessExit(
                target_action=webots,
                on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
            )
        )
    ])

``WebotsLauncher``对象是一个自定义动作,可以启动Webots仿真实例。您需要在构造函数中指定模拟器将打开的世界文件。

webots = WebotsLauncher(
    world=os.path.join(package_dir, 'worlds', 'my_world.wbt')
)

然后,创建与模拟机器人交互的 ROS 节点。此节点名为 WebotsController,位于 webots_ros2_driver 包中。

该节点将能够使用基于IPC和共享内存的自定义协议与模拟机器人通信。

在您的情况下,您需要运行此节点的单个实例,因为仿真中只有一个机器人。但是,如果您的仿真中有多个机器人,您需要为每个机器人运行一个此节点的实例。robot_name 参数用于定义驱动程序应连接到的机器人的名称。robot_description 参数包含指向 MyRobotDriver 插件的 URDF 文件的路径。您可以将 WebotsController 节点视为连接控制器插件与目标机器人的接口。

my_robot_driver = WebotsController(
    robot_name='my_robot',
    parameters=[
        {'robot_description': robot_description_path},
    ]
)

之后,这两个节点被设置为在``LaunchDescription``构造函数中启动:

return LaunchDescription([
    webots,
    my_robot_driver,

最后,为了在Webots终止时关闭所有节点(例如,当从图形用户界面关闭时),添加了一个可选部分。

launch.actions.RegisterEventHandler(
    event_handler=launch.event_handlers.OnProcessExit(
        target_action=webots,
        on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
    )
)

注解

有关 WebotsControllerWebotsLauncher 参数的详细信息可以在 节点参考页面上找到

6 编辑附加文件

在您启动启动文件之前,您必须修改``setup.py``文件以包括您添加的额外文件。打开``my_package/setup.py``并用以下内容替换其内容:

from setuptools import setup

package_name = 'my_package'
data_files = []
data_files.append(('share/ament_index/resource_index/packages', ['resource/' + package_name]))
data_files.append(('share/' + package_name + '/launch', ['launch/robot_launch.py']))
data_files.append(('share/' + package_name + '/worlds', ['worlds/my_world.wbt']))
data_files.append(('share/' + package_name + '/resource', ['resource/my_robot.urdf']))
data_files.append(('share/' + package_name, ['package.xml']))

setup(
    name=package_name,
    version='0.0.0',
    packages=[package_name],
    data_files=data_files,
    install_requires=['setuptools'],
    zip_safe=True,
    maintainer='user',
    maintainer_email='user.name@mail.com',
    description='TODO: Package description',
    license='TODO: License declaration',
    tests_require=['pytest'],
    entry_points={
        'console_scripts': [
            'my_robot_driver = my_package.my_robot_driver:main',
        ],
    },
)

这个设置了包并在``data_files``变量中添加了新增的文件:my_world.wbtmy_robot.urdf``和``robot_launch.py

7 测试代码

在ROS 2工作空间的终端中运行:

colcon build
source install/local_setup.bash
ros2 launch my_package robot_launch.py

这将启动模拟。如果尚未安装Webots,则在第一次运行时将自动安装。

注解

如果您想手动安装Webots,您可以从`此处 <https://github.com/cyberbotics/webots/releases/latest>`_ 下载。

然后,打开第二个终端并发送以下命令:

ros2 topic pub /cmd_vel geometry_msgs/Twist  "linear: { x: 0.1 }"

机器人现在正在向前移动。

../../../../_images/Robot_moving_forward.png

此时,机器人能够盲目地按照您的电机指令行动。但是,当您命令它向前移动时,它最终会撞到墙上。

../../../../_images/Robot_colliding_wall.png

关闭Webots窗口,这也会关闭从启动器启动的ROS节点。同时,在第二个终端中使用``Ctrl+C``关闭话题命令。

总结

在本教程中,您使用Webots设置了一个逼真的机器人仿真,并实现了一个自定义插件来控制机器人的电机。

下一步

为了改善仿真效果,可以使用机器人的传感器来检测障碍物并避开它们。教程的第二部分展示了如何实现这样的行为: