Ros2Supervisor 节点
目标: 扩展接口以包括默认的 Supervisor 机器人,名称为 Ros2Supervisor
。
教程级别: 高级
时间: 10分钟
背景
在本教程中,您将学习如何启用 Ros2Supervisor
节点,通过创建额外的服务和主题来增强接口,以便在仿真运行时与仿真进行交互。例如,您可以在仿真运行时从 ROS 2 接口中记录动画或直接生成 Webots 节点。这些说明详细列出了当前实现的功能以及如何使用它们。
先决条件
在继续本教程之前,请确保您已完成以下内容:
理解了初学者教程中涵盖的 ROS 2 节点和主题内容 教程。
了解 Webots、ROS 2 及其接口包的知识。
熟悉 设置机器人仿真(基础)。
Ros2Supervisor
Ros2Supervisor
主要由两个主要部分组成:
在仿真世界中添加了一个 Webots 机器人节点。其
supervisor
字段设置为 TRUE。一个 ROS 2 节点,以外部控制器的方式连接到 Webots 机器人(类似于您自己的机器人插件)。
ROS 2 节点充当控制器,调用 Supervisor API 函数来控制或与仿真世界进行交互。用户与 ROS 2 节点的交互主要通过服务和主题进行。
可以使用 WebotsLauncher
中的 ros2_supervisor
参数在 Webots 启动时自动创建这些节点。
webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world]),
mode=mode,
ros2_supervisor=True
)
LaunchDescription
中必须包括 webots._supervisor
对象,该对象由启动文件返回。
return LaunchDescription([
webots,
webots._supervisor,
# This action will kill all nodes once the Webots simulation has exited
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots,
on_exit=[
launch.actions.EmitEvent(event=launch.events.Shutdown())
],
)
)
])
有关 webots_ros2
项目的启动文件的更多信息,请参阅 设置机器人仿真(基础)。
时钟主题
Ros2Supervisor
节点负责获取 Webots 仿真时间并将其发布到 /clock
主题。这意味着如果其他节点的 use_sim_time
参数设置为 true
,则必须生成 Ros2Supervisor
。有关 /clock
主题的更多信息,请参阅 ROS wiki。
导入 Webots 节点
Ros2Supervisor
节点还允许您通过服务从字符串中生成 Webots 节点。
该服务的名称为 /Ros2Supervisor/spawn_node_from_string
,类型为 webots_ros2_msgs/srv/SpawnNodeFromString
。 SpawnNodeFromString
类型期望以 data
字符串作为输入,并返回 success
布尔值。
从给定的字符串中,Supervisor 节点获取导入节点的名称并将其添加到一个内部列表,以供以后潜在的移除(参见 删除导入的 Webots 节点)。
使用 importMFNodeFromString(nodeString)
API 函数 导入节点。
以下是导入名为 imported_robot
的简单机器人的示例:
ros2 service call /Ros2Supervisor/spawn_node_from_string webots_ros2_msgs/srv/SpawnNodeFromString "data: Robot { name \"imported_robot\" }"
注解
如果您尝试在节点字符串中导入一些 PROTOs,则它们的相应 URL 必须在 .wbt 世界文件中声明为 EXTERNPROTO 或 IMPORTABLE EXTERNPROTO。
删除 Webots 导入的节点
一旦使用 /Ros2Supervisor/spawn_node_from_string
服务导入了一个节点,也可以将其删除。
这可以通过将节点的名称发送到类型为 std_msgs/msg/String
的主题 /Ros2Supervisor/remove_node
来实现。
如果节点确实在导入列表中,它将使用 remove()
API 方法 进行删除。
以下是如何删除名为 imported_robot
的机器人的示例:
ros2 topic pub --once /Ros2Supervisor/remove_node std_msgs/msg/String "{data: imported_robot}"
记录动画
Ros2Supervisor
节点还创建了两个额外的服务来记录 HTML5 动画。
/Ros2Supervisor/animation_start_recording
服务的类型为 webots_ros2_msgs/srv/SetString
,允许启动动画。SetString
类型期望一个 value
字符串作为输入,并返回一个 success
布尔值。输入的 value
表示动画文件应保存的目录的绝对路径。
以下是如何启动动画的示例:
ros2 service call /Ros2Supervisor/animation_start_recording webots_ros2_msgs/srv/SetString "{value: "<ABSOLUTE_PATH>/index.html"}"
/Ros2Supervisor/animation_stop_recording
服务的类型为 webots_ros2_msgs/srv/GetBool
,允许停止动画。
ros2 service call /Ros2Supervisor/animation_stop_recording webots_ros2_msgs/srv/GetBool "{ask: True}"