< >
Home » ROS2与webots入门教程 » ros2与webots入门教程-使用 ROS 2 进行 Webbots 模拟重置

ros2与webots入门教程-使用 ROS 2 进行 Webbots 模拟重置

ros2与webots入门教程-使用 ROS 2 进行 Webbots 模拟重置

说明: 

  • 介绍如何使用 ROS 2 进行 Webbots 模拟重置
  • Webots 重置按钮将世界恢复到初始状态并重新启动控制器。
  • 这很方便,因为它可以快速重置模拟,但在 ROS 2 的上下文中,机器人控制器不会再次启动,从而使模拟停止。控制器无法启动,因为不允许 Webot 启动在 ROS 2 启动文件中生成的外部控制器(来自 ROS 上下文中的 webots_ros2_driver 包的驱动程序节点)。
  • 注意:对于开发分支,必须使用 Ros2SupervisorLauncher 进程启动另一个名为 Ros2Supervisor 的节点,以用于每个 Web 机器人模拟。
  • 因此,必须手动处理驱动节点的重启,如下面的 generate_launch_description 函数:
def generate_launch_description():
    webots_driver = Node(
        package='webots_ros2_driver',
        executable='driver',
        parameters=[
            {'robot_description': robot_description,
             'set_robot_state_publisher': True }
        ],

        # The following line is important!
        # Every time one resets the simulation the controller is automatically respawned
        respawn=True
    )

    # Starts Webots
    webots = WebotsLauncher(world=PathJoinSubstitution([package_dir, 'worlds', world]))

    # Starts the Ros2Supervisor node, with by default respawn=True
    ros2_supervisor = Ros2SupervisorLauncher() # Only with the develop branch!

    return LaunchDescription([
        webots,
        ros2_supervisor, # Only with the develop branch!
        webots_driver,
        launch.actions.RegisterEventHandler(
            event_handler=launch.event_handlers.OnProcessExit(
                target_action=webots,
                on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
            )
        )
    ])
  • 在重置时,Webots 会杀死所有驱动程序节点。 因此,要在重置完成后再次启动它们,您可以将驱动程序节点的 respawn 属性设置为 True。 它将确保驱动程序节点在重置后启动并运行。

  • 如果您有一些其他节点必须重新启动(例如 ros2_control),那么您可以使用 OnProcessExit 事件处理程序:

def get_ros2_control_spawners(*args):
    return [
        Node(
            package='controller_manager',
            executable='spawner.py',
            arguments=['diffdrive_controller']
        )
    ]

def generate_launch_description():
    webots_driver = Node(
        package='webots_ros2_driver',
        executable='driver',
        parameters=[
            {'robot_description': robot_description,
             'set_robot_state_publisher': True }
        ],

        # The following line is important!
        # Every time one resets the simulation the controller is automatically respawned
        respawn=True
    )

    # Starts Webots
    webots = WebotsLauncher(world=PathJoinSubstitution([package_dir, 'worlds', world]))

    # Starts the Ros2Supervisor node, with by default respawn=True
    ros2_supervisor = Ros2SupervisorLauncher() # Only with the develop branch!

    return LaunchDescription([
        webots,
        ros2_supervisor, # Only with the develop branch!
        webots_driver,
        launch.actions.RegisterEventHandler(
            event_handler=launch.event_handlers.OnProcessExit(
                target_action=webots,
                on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
            )
        ),

        # The following line is important!
        # This event respawns ros2_controllers on the `driver` node shutdown.
        launch.actions.RegisterEventHandler(
            event_handler=launch.event_handlers.OnProcessExit(
                target_action=webots_driver,
                on_exit=get_ros2_control_spawners,
            )
        )
    ] + get_ros2_control_spawners())

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros2与webots入门教程