设置机器人模拟(基础)
目标: 设置机器人模拟并从 ROS 2 控制它。
教程级别: 高级
时间: 30 分钟
背景
在本教程中,您将使用 Webots 机器人模拟器来设置和运行一个非常简单的 ROS 2 模拟场景。
webots_ros2
包提供了 ROS 2 和 Webots 之间的接口。
它包含几个子包,但在本教程中,您将仅使用``webots_ros2_driver`` 子包来实现控制模拟机器人的 Python 或 C++ 插件。
其他一些子包包含不同机器人的演示,例如 TurtleBot3。
它们记录在`Webots ROS 2 示例 <https://github.com/cyberbotics/webots_ros2/wiki/Examples>`_ 页面中。
先决条件
建议了解初学者 教程 中涵盖的基本 ROS 原理。 特别是,使用“turtlesim”、“ros2”和“rqt”、理解主题、创建工作区、创建包 和 创建启动文件 都是有用的先决条件。
本教程的 Linux 和 ROS 命令可以在标准 Linux 终端中运行。
以下页面 安装(Ubuntu) 解释了如何在 Linux 上安装 webots_ros2
包。
本教程的 Linux 和 ROS 命令必须在 WSL(Windows Subsystem for Linux)环境中运行。
以下页面 安装 (Windows) 解释了如何在 Windows 上安装 webots_ros2
包。
本教程的 Linux 和 ROS 命令必须在预先配置的 Linux 虚拟机 (VM) 中运行。
以下页面 安装 (macOS) 解释了如何在 macOS 上安装 webots_ros2
包。
本教程与“webots_ros2”和Webots R2023b的2023.1.0版本以及即将推出的版本兼容。
任务
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_driver
选项在 package.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
ros2 pkg create --build-type ament_cmake --license Apache-2.0 --node-name MyRobotDriver my_package --dependencies rclcpp geometry_msgs webots_ros2_driver pluginlib
--node-name MyRobotDriver
选项将在 my_package/src
子文件夹中创建一个 MyRobotDriver.cpp
模板 C++ 插件,您稍后将对其进行修改。
--dependencies rclcpp geometry_msgs webots_ros2_driver pluginlib
选项在 package.xml
文件中指定 MyRobotDriver
插件所需的包。
让我们在“my_package”文件夹中添加一个“launch”、“worlds”和一个“resource”文件夹。
cd my_package
mkdir launch
mkdir worlds
mkdir resource
必须创建两个附加文件:“MyRobotDriver”的头文件和“my_robot_driver.xml”插件库描述文件。
touch my_robot_driver.xml
touch include/my_package/MyRobotDriver.hpp
您最终应该得到以下文件夹结构:
src/
└── my_package/
├── include/
│ └── my_package/
│ └── MyRobotDriver.hpp
├── launch/
├── resource/
├── src/
│ └── MyRobotDriver.cpp
├── worlds/
├── CMakeList.txt
├── my_robot_driver.xml
└── package.xml
2 设置模拟世界
您需要一个包含机器人的世界文件来启动模拟。
下载此世界文件
并将其移动到 my_package/worlds/
内。
这实际上是一个相当简单的文本文件,您可以在文本编辑器中查看。
此 my_world.wbt
世界文件中已包含一个简单的机器人。
Note
如果您想了解如何在 Webots 中创建自己的机器人模型,可以查看此“教程 <https://cyberbotics.com/doc/guide/tutorial-6-4-wheels-robot>” 。
3 编辑 my_robot_driver
插件
webots_ros2_driver
子包会自动为大多数传感器创建 ROS 2 接口。
有关现有设备接口及其配置方法的更多详细信息,请参阅本教程的第二部分:设置机器人模拟(高级)。
在此任务中,您将通过创建自己的自定义插件来扩展此接口。
此自定义插件是相当于机器人控制器的 ROS 节点。
您可以使用它来访问 Webots 机器人 API 并创建自己的主题和服务来控制您的机器人。
Note
本教程的目的是展示一个具有最少依赖项的基本示例。 但是,您可以通过使用另一个名为“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 文件中给出的 XML 标签创建的字典 (4 创建 my_robot.urdf 文件),允许您将参数传递给控制器。
来自模拟 self.__robot
的机器人实例可用于访问 Webots 机器人 API。
然后,它获取两个电机实例并使用目标位置和目标速度初始化它们。
最后创建一个 ROS 节点,并为名为“/cmd_vel”的 ROS 主题注册一个回调方法,该方法将处理“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)
在您最喜欢的编辑器中打开“my_package/include/my_package/MyRobotDriver.hpp”并将其内容替换为以下内容:
#ifndef WEBOTS_ROS2_PLUGIN_EXAMPLE_HPP
#define WEBOTS_ROS2_PLUGIN_EXAMPLE_HPP
#include "rclcpp/macros.hpp"
#include "webots_ros2_driver/PluginInterface.hpp"
#include "webots_ros2_driver/WebotsNode.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
namespace my_robot_driver {
class MyRobotDriver : public webots_ros2_driver::PluginInterface {
public:
void step() override;
void init(webots_ros2_driver::WebotsNode *node,
std::unordered_map<std::string, std::string> ¶meters) override;
private:
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
cmd_vel_subscription_;
geometry_msgs::msg::Twist cmd_vel_msg;
WbDeviceTag right_motor;
WbDeviceTag left_motor;
};
} // namespace my_robot_driver
#endif
定义了类“MyRobotDriver”,它继承自“webots_ros2_driver::PluginInterface”类。 插件必须重写“step(…)”和“init(…)”函数。 更多详细信息请参阅“MyRobotDriver.cpp”文件。 插件内部使用的几个辅助方法、回调和成员变量被声明为私有。
然后,在您最喜欢的编辑器中打开“my_package/src/MyRobotDriver.cpp”,并将其内容替换为以下内容:
#include "my_package/MyRobotDriver.hpp"
#include "rclcpp/rclcpp.hpp"
#include <cstdio>
#include <functional>
#include <webots/motor.h>
#include <webots/robot.h>
#define HALF_DISTANCE_BETWEEN_WHEELS 0.045
#define WHEEL_RADIUS 0.025
namespace my_robot_driver {
void MyRobotDriver::init(
webots_ros2_driver::WebotsNode *node,
std::unordered_map<std::string, std::string> ¶meters) {
right_motor = wb_robot_get_device("right wheel motor");
left_motor = wb_robot_get_device("left wheel motor");
wb_motor_set_position(left_motor, INFINITY);
wb_motor_set_velocity(left_motor, 0.0);
wb_motor_set_position(right_motor, INFINITY);
wb_motor_set_velocity(right_motor, 0.0);
cmd_vel_subscription_ = node->create_subscription<geometry_msgs::msg::Twist>(
"/cmd_vel", rclcpp::SensorDataQoS().reliable(),
[this](const geometry_msgs::msg::Twist::SharedPtr msg){
this->cmd_vel_msg.linear = msg->linear;
this->cmd_vel_msg.angular = msg->angular;
}
);
}
void MyRobotDriver::step() {
auto forward_speed = cmd_vel_msg.linear.x;
auto angular_speed = cmd_vel_msg.angular.z;
auto command_motor_left =
(forward_speed - angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) /
WHEEL_RADIUS;
auto command_motor_right =
(forward_speed + angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) /
WHEEL_RADIUS;
wb_motor_set_velocity(left_motor, command_motor_left);
wb_motor_set_velocity(right_motor, command_motor_right);
}
} // namespace my_robot_driver
#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(my_robot_driver::MyRobotDriver,
webots_ros2_driver::PluginInterface)
一旦插件被 webots_ros2_driver
包加载,就会执行 MyRobotDriver::init
方法。
它需要两个参数:
指向由
webots_ros2_driver
定义的WebotsNode
的指针,允许访问 ROS 2 节点函数。parameters
参数是一个无序的字符串映射,由 URDF 文件中给出的 XML 标签创建 (4 创建 my_robot.urdf 文件),并允许将参数传递给控制器。本例中未使用它。
它通过设置机器人电机、设置它们的位置和速度以及订阅 /cmd_vel
主题来初始化插件。
void MyRobotDriver::init(
webots_ros2_driver::WebotsNode *node,
std::unordered_map<std::string, std::string> ¶meters) {
right_motor = wb_robot_get_device("right wheel motor");
left_motor = wb_robot_get_device("left wheel motor");
wb_motor_set_position(left_motor, INFINITY);
wb_motor_set_velocity(left_motor, 0.0);
wb_motor_set_position(right_motor, INFINITY);
wb_motor_set_velocity(right_motor, 0.0);
cmd_vel_subscription_ = node->create_subscription<geometry_msgs::msg::Twist>(
"/cmd_vel", rclcpp::SensorDataQoS().reliable(),
[this](const geometry_msgs::msg::Twist::SharedPtr msg){
this->cmd_vel_msg.linear = msg->linear;
this->cmd_vel_msg.angular = msg->angular;
}
);
}
订阅回调被声明为一个 lambda 函数,它将为在 /cmd_vel
主题上收到的每条 Twist 消息调用,并将其保存在 cmd_vel_msg
成员变量中。
[this](const geometry_msgs::msg::Twist::SharedPtr msg){
this->cmd_vel_msg.linear = msg->linear;
this->cmd_vel_msg.angular = msg->angular;
}
在模拟的每个时间步骤中都会调用 step()
方法。
在每个时间步骤中,该方法将从 cmd_vel_msg
中检索所需的 forward_speed
和 angular_speed
。
由于电机由角速度控制,该方法会将 forward_speed
和 angular_speed
转换为每个车轮的单独命令。
这种转换取决于机器人的结构,更具体地说取决于车轮的半径和它们之间的距离。
void MyRobotDriver::step() {
auto forward_speed = cmd_vel_msg.linear.x;
auto angular_speed = cmd_vel_msg.angular.z;
auto command_motor_left =
(forward_speed - angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) /
WHEEL_RADIUS;
auto command_motor_right =
(forward_speed + angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) /
WHEEL_RADIUS;
wb_motor_set_velocity(left_motor, command_motor_left);
wb_motor_set_velocity(right_motor, command_motor_right);
}
该文件的最后几行定义了“my_robot_driver”命名空间的结尾,并包含一个宏,使用“PLUGINLIB_EXPORT_CLASS”宏将“MyRobotDriver”类导出为插件。 这允许 Webots ROS2 驱动程序在运行时加载该插件。
#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(my_robot_driver::MyRobotDriver,
webots_ros2_driver::PluginInterface)
Note
虽然该插件是用 C++ 实现的,但必须使用 C API 才能与 Webots 控制器库交互。
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
负责根据指定的包和模块加载类。
<?xml version="1.0" ?>
<robot name="My robot">
<webots>
<plugin type="my_robot_driver::MyRobotDriver" />
</webots>
</robot>
type
属性指定要加载的命名空间和类名。
pluginlib
负责根据指定的信息加载类。
Note
这个简单的 URDF 文件不包含有关机器人的任何链接或关节信息,因为本教程不需要这些信息。 但是,URDF 文件通常包含更多信息,如 URDF 教程中所述。
Note
这里插件不接受任何输入参数,但可以使用包含参数名称的标签来实现。
<plugin type="my_package.my_robot_driver.MyRobotDriver">
<parameterName>someValue</parameterName>
</plugin>
<plugin type="my_robot_driver::MyRobotDriver">
<parameterName>someValue</parameterName>
</plugin>
这即用于将参数传递给现有的 Webots 设备插件(参见:doc:设置机器人模拟(高级))。
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 和共享内存的自定义协议与模拟机器人进行通信。
该节点(在 WSL 中)将能够通过 TCP 连接与模拟机器人(在原生 Windows 上的 Webots 中)进行通信。
该节点(在 docker 容器中)将能够通过 TCP 连接与模拟机器人(在原生 macOS 上的 Webots 中)进行通信。
在您的案例中,您需要运行此节点的单个实例,因为模拟中只有一个机器人。
但是,如果您在模拟中有更多机器人,则必须为每个机器人运行此节点的一个实例。
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())],
)
)
Note
有关“WebotsController”和“WebotsLauncher”参数的更多详细信息,请参阅节点参考页面<https://github.com/cyberbotics/webots_ros2/wiki/References-Nodes>`_。
6 编辑其他文件
在启动启动文件之前,您必须修改“setup.py”文件以包含您添加的额外文件。 打开“my_package/setup.py”并将其内容替换为:
from setuptools import find_packages, 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=find_packages(exclude=['test']),
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.wbt”、“my_robot.urdf”和“robot_launch.py”。
在启动启动文件之前,您必须修改“CMakeLists.txt”和“my_robot_driver.xml”文件:
CMakeLists.txt
defines the compilation rules of your plugin.my_robot_driver.xml
is necessary for the pluginlib to find your Webots ROS 2 plugin.
打开“my_package/my_robot_driver.xml”并将其内容替换为:
<library path="my_package">
<!-- The `type` attribute is a reference to the plugin class. -->
<!-- The `base_class_type` attribute is always `webots_ros2_driver::PluginInterface`. -->
<class type="my_robot_driver::MyRobotDriver" base_class_type="webots_ros2_driver::PluginInterface">
<description>
This is a Webots ROS 2 plugin example
</description>
</class>
</library>
打开“my_package/CMakeLists.txt”并将其内容替换为:
cmake_minimum_required(VERSION 3.5)
project(my_package)
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
# Besides the package specific dependencies we also need the `pluginlib` and `webots_ros2_driver`
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(webots_ros2_driver REQUIRED)
# Export the plugin configuration file
pluginlib_export_plugin_description_file(webots_ros2_driver my_robot_driver.xml)
# MyRobotDriver library
add_library(
${PROJECT_NAME}
SHARED
src/MyRobotDriver.cpp
)
target_include_directories(
${PROJECT_NAME}
PRIVATE
include
)
ament_target_dependencies(
${PROJECT_NAME}
pluginlib
rclcpp
webots_ros2_driver
)
install(TARGETS
${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)
# Install additional directories.
install(DIRECTORY
launch
resource
worlds
DESTINATION share/${PROJECT_NAME}/
)
ament_export_include_directories(
include
)
ament_export_libraries(
${PROJECT_NAME}
)
ament_package()
CMakeLists.txt 使用“pluginlib_export_plugin_description_file()”导出插件配置文件,定义 C++ 插件“src/MyRobotDriver.cpp”的共享库,并使用“ament_target_dependencies()”设置包含和库依赖项。
然后,该文件将库、目录“launch”、“resource”和“worlds”安装到“share/my_package”目录。 最后,它分别使用“ament_export_include_directories()”和“ament_export_libraries()”导出包含目录和库,并使用“ament_package()”声明包。
7 测试代码
从 ROS 2 工作区中的终端运行:
colcon build
source install/local_setup.bash
ros2 launch my_package robot_launch.py
这将启动模拟。 如果尚未安装,Webots 将在第一次运行时自动安装。
从 WSL ROS 2 工作区中的终端运行:
colcon build
export WEBOTS_HOME=/mnt/c/Program\ Files/Webots
source install/local_setup.bash
ros2 launch my_package robot_launch.py
确保在 Webots 安装文件夹路径前使用“/mnt”前缀,以便从 WSL 访问 Windows 文件系统。
这将启动模拟。 如果尚未安装,Webots 将在第一次运行时自动安装。
在 macOS 上,必须在主机上启动本地服务器才能从 VM 启动 Webots。 本地服务器可以在 webots-server 存储库 上下载。
在主机的终端(而不是 VM 中)中,指定 Webots 安装文件夹(例如 /Applications/Webots.app
)并使用以下命令启动服务器:
export WEBOTS_HOME=/Applications/Webots.app python3 local_simulation_server.py从 ROS 2 工作区中 Linux VM 的终端,使用以下命令构建并启动自定义包:
colcon build source install/local_setup.bash ros2 launch my_package robot_launch.py
Note
如果您想手动安装 Webots,您可以从`这里<https://github.com/cyberbotics/webots/releases/latest>`_下载。
然后,打开第二个终端并发送命令:
ros2 topic pub /cmd_vel geometry_msgs/Twist "linear: { x: 0.1 }"
机器人正在向前移动。
此时,机器人能够盲目地遵循你的电机命令。 但当你命令它向前移动时,它最终会撞到墙上。
关闭 Webots 窗口,这也会关闭从启动器启动的 ROS 节点。 在第二个终端中使用“Ctrl+C”关闭主题命令。
摘要
在本教程中,您使用 Webots 设置了一个真实的机器人模拟,并实现了一个自定义插件来控制机器人的电机。
后续步骤
为了改进模拟,可以使用机器人的传感器来检测障碍物并避开它们。 本教程的第二部分展示了如何实现这种行为: