导航禁止区 [校准@mzebra]
概述
本教程展示了如何简单地利用机器人不能进入的禁区/安全区,以及机器人在工业环境和仓库中移动的首选通道。所有这些功能都被 ``KeepoutFilter``成本地图过滤器插件所包含,该插件将在本文中启用和使用。 [校准@混沌无形]
要求
假设ROS 2、Gazebo和TurtleBot3包是在本地安装或编译的。请确保Nav2工程也是在本地编译的,因为它是在 编译和安装 提到的。 [校准@混沌无形]
Tutorial Steps
1.准备过滤器掩码
正如 导航相关概念 所写,任何成本地图过滤器 (包括Keepout过滤器) 都在读取过滤器掩码文件中标记的数据。过滤器掩码-是通过PGM、PNG或BMP位图文件分发的通常的Nav2 2D地图,其元数据包含在YAML文件中。以下步骤有助于了解如何制作新的过滤器掩码: [校准@混沌无形]
创建具有PGM/PNG/BMP格式的新图像: 将用于世界模拟的 turtlebot3_world.pgm 主地图从 Nav2
仓库复制到新的 keepout_mask.pgm
文件中。 [校准@混沌无形]
在您最喜欢的位图图像编辑器中打开 keepout_mask.pgm
(例如,可以采用GIMP编辑器)。掩码上每个像素的亮度意味着您要使用的特定成本地图过滤器的编码信息。每个像素的颜色亮度属于 [0..255]
范围 (或 [0..100]
百分比范围),其中 0
的意思是黑色和 255
为白色。另一个术语 "darkness" 将被理解为与明亮的意思完全相反。换句话说,“颜色 _ 黑暗(color_darkness) = 100%-颜色 _ 明亮(color_lightness)”。 [校准@混沌无形]
In the GIMP lightness is expressed through color components value (e.g. R
in percent scale) and might be set by moving L
slider in color changing tool:
地图服务器正在读取传入的掩码文件,并将其转换为``[0..100]``范围内的``OccupancyGrid``值 (地图上的占据栅格中, 0
表示空闲的栅格单元, 100
表示占据的栅格单元,介于两者之间的任何情况--较少或较多) 或等于 -1
表示未知值。在Nav2的每个地图 mode
属性可以是 trinary
, scale
或 raw
。根据所选择的 mode
,PGM/PNG/BMP的颜色亮度将通过以下原则之一转换为 OccupancyGrid
: [校准@混沌无形]
trinary
(默认模式): Darkness >=occupied_thresh
表示地图中占据的部分 (100
). Darkness <=free_thresh
- 表示地图中空闲区域 (0
). Anything in between - 地图中的位置状态 (-1
). [校准@混沌无形]scale
: Alpha <1.0
- 未知. Darkness >=occupied_thresh
表示地图中的被占据的区域 (100
). Darkness <=free_thresh
- 表示地图中的空闲区域 (0
). Anything in between - 从[0..100]
范围内线性插值到最近的整数。 [校准@混沌无形]raw
: Lightness =0
(dark color) 表示地图中的空闲区域 (0
). Lightness =100
(绝对值) - 表示地图中被占据的区域 (100
). Anything in between -OccupancyGrid
value = lightness. Lightness >=101
- 未知区域 (-1
). [校准@混沌无形]
其中 free_thresh
和 occupied_thresh
阈值以最大亮/暗水平 ( 255
) 的百分比表示。地图模式和阈值如 mode
、 free_thresh
和 occupied_thresh
字段放置在YAML元数据文件 (见下文) 中。 [校准@混沌无形]
备注
YAML元数据文件中有另一个参数,称为 negate
。默认情况下,它设置为 false
。当它被设置为 true
时,黑色像素将被认为是空闲区域,白色像素-表示被占据区域。在这种情况下,在这种情况下,我们应该计算颜色的亮度,而不是计算 trinary
和 ``scale``模式的暗度。negate'对`raw'模式没有影响。 `[校准@混沌无形]
对于禁止区域(Keepout)过滤器``OccupancyGrid``的值与该单元的相关区域的可接受性成正比: 偏高的值意味着不可逾越的地区。有占据值的单元格涵盖了机器人永远不会进入或通过的禁区。 KeepoutFilter
也可以作为"weighted areas layer" 将``[1-99]`` 之间的值作为非占据值设置 OccupancyGrid
。机器人被允许在这些区域移动,但是它在那里的存在将是 "undesirable(不受欢迎的)" (数值越高,规划器就会越早地试图让机器人离开这个区域)。 [校准@混沌无形]
Keepout Filter也包括首选通道的情况,即机器人只能在预先定义的通道和允许的区域移动,例如在仓库。要使用这一功能,你需要准备好掩码图像,其中车道和允许的区域将被标记为自由值,而所有其他区域将被占用。在 trinary
或 scale
模式下绘制掩码的提示: 通常,属于车道的像素量远远少于覆盖其他区域的像素量。在这种情况下,最初所有的车道数据都可以用黑色铅笔在白色背景上绘制,然后 (就在保存PGM之前) 可以使用位图图像编辑器中的 "color inversion" 工具。 [校准@混沌无形]
为简单起见,在示例中用黑色填充区域 (在 trinary
模式下,这意味着被占据的地图),您将其标记为禁区: [校准@混沌无形]
在所有禁止区域被填满后,保存 keepout_mask.pgm
图像。 [校准@混沌无形]
像所有其他地图一样,过滤器掩码应该有自己的YAML元数据文件。将 turtlebot3_world.yaml 复制到 keepout_mask.yaml
。打开 keepout_mask.yaml
并校正``image`` 领域的一个新的PGM掩码: [校准@混沌无形]
image: turtlebot3_world.pgm
->
image: keepout_mask.pgm
由于过滤器掩码图像是作为主地图的副本创建的,因此不需要更改YAML文件的其他字段。保存 keepout_mask.yaml
,新的过滤器掩码就可以使用了。 [校准@混沌无形]
备注
世界地图本身和过滤掩码可以有不同的尺寸、原点和分辨率,这对于过滤掩码在地图上覆盖较小的区域或一个过滤掩码被多次重复使用的情况可能很有用(比如为酒店中相同形状的房间注释一个禁区)。在这种情况下,您还需要更正YAML中的 resolution
和 origin
字段,以便将过滤器掩码正确放置在原始地图的顶部。 [校准@混沌无形]
2.配置成本地图过滤器信息发布服务器 [校准@混沌无形]
每个成本过滤器读取 nav2_msgs/CostmapFilterInfo
类型消息中的传入元信息 (例如过滤器类型或数据转换系数)。这些信息由 Costmap Filter Info Publisher Server 发布。服务器作为生命周期节点运行。根据 `设计文档<https://github.com/ros-planning/navigation2/blob/main/doc/design/CostmapFilters_design.pdf>`_ 的说法, nav2_msgs/CostmapFilterInfo
的消息与 OccupancyGrid
的过滤掩码话题成对。因此,与成本地图过滤器信息发布服务器一起,应该启用配置为发布过滤器掩码的地图服务器的新实例。 [校准@混沌无形]
为了在配置中启用禁止区域过滤器(Keepout Filter),应在Python启动文件中将两个服务器作为生命周期节点启用。例如,这可能如下所示: [校准@混沌无形]
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from nav2_common.launch import RewrittenYaml
def generate_launch_description():
# Get the launch directory
costmap_filters_demo_dir = get_package_share_directory('nav2_costmap_filters_demo')
# Create our own temporary YAML files that include substitutions
lifecycle_nodes = ['filter_mask_server', 'costmap_filter_info_server']
# Parameters
namespace = LaunchConfiguration('namespace')
use_sim_time = LaunchConfiguration('use_sim_time')
autostart = LaunchConfiguration('autostart')
params_file = LaunchConfiguration('params_file')
mask_yaml_file = LaunchConfiguration('mask')
# Declare the launch arguments
declare_namespace_cmd = DeclareLaunchArgument(
'namespace',
default_value='',
description='Top-level namespace')
declare_use_sim_time_cmd = DeclareLaunchArgument(
'use_sim_time',
default_value='true',
description='Use simulation (Gazebo) clock if true')
declare_autostart_cmd = DeclareLaunchArgument(
'autostart', default_value='true',
description='Automatically startup the nav2 stack')
declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
default_value=os.path.join(costmap_filters_demo_dir, 'params', 'keepout_params.yaml'),
description='Full path to the ROS 2 parameters file to use')
declare_mask_yaml_file_cmd = DeclareLaunchArgument(
'mask',
default_value=os.path.join(costmap_filters_demo_dir, 'maps', 'keepout_mask.yaml'),
description='Full path to filter mask yaml file to load')
# Make re-written yaml
param_substitutions = {
'use_sim_time': use_sim_time,
'yaml_filename': mask_yaml_file}
configured_params = RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True)
# Nodes launching commands
start_lifecycle_manager_cmd = Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_costmap_filters',
namespace=namespace,
output='screen',
emulate_tty=True, # https://github.com/ros2/launch/issues/188
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
{'node_names': lifecycle_nodes}])
start_map_server_cmd = Node(
package='nav2_map_server',
executable='map_server',
name='filter_mask_server',
namespace=namespace,
output='screen',
emulate_tty=True, # https://github.com/ros2/launch/issues/188
parameters=[configured_params])
start_costmap_filter_info_server_cmd = Node(
package='nav2_map_server',
executable='costmap_filter_info_server',
name='costmap_filter_info_server',
namespace=namespace,
output='screen',
emulate_tty=True, # https://github.com/ros2/launch/issues/188
parameters=[configured_params])
ld = LaunchDescription()
ld.add_action(declare_namespace_cmd)
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_mask_yaml_file_cmd)
ld.add_action(start_lifecycle_manager_cmd)
ld.add_action(start_map_server_cmd)
ld.add_action(start_costmap_filter_info_server_cmd)
return ld
在 params_file
变量应设置YAML文件有ROS参数成本地图过滤器信息发布服务器和地图服务器节点。这些参数及其含义列在 Map Server / Saver 页面。请参考信息。 params_file
示例如下: [校准@混沌无形]
costmap_filter_info_server:
ros__parameters:
use_sim_time: true
type: 0
filter_info_topic: "/costmap_filter_info"
mask_topic: "/keepout_filter_mask"
base: 0.0
multiplier: 1.0
filter_mask_server:
ros__parameters:
use_sim_time: true
frame_id: "map"
topic_name: "/keepout_filter_mask"
yaml_filename: "keepout_mask.yaml"
请注意: [待校准@1325]
对于禁止区域过滤器(Keepout Filter),成本地图过滤器的
type
应设置为0
。 [校准@混沌无形]过滤器掩码的话题名称应与成本地图过滤器信息发布服务器的
mask_topic
参数和地图服务器的``topic_name``参数相同。 [校准@混沌无形]根据成本地图过滤器设计,在过滤器空间中,
OccupancyGrid
值被线性转换为特征图。对于禁止区域过滤器,这些值直接作为过滤器空间值传递,而无需进行线性转换。即使base
和multiplier
系数没有用于禁止区域过滤器,它们应该被相应地设置为0.0
和1.0
,以明确地表明我们有从OccupancyGrid
值-> 到过滤器值空间的一对一转换。 [校准@混沌无形]
在 nav2_costmap_filters_demo 目录 navigation2_tutorials
库中,可以找到现成的独立Python启动脚本、带有ROS参数的YAML文件以及禁止区域过滤器的过滤器掩码示例。要简单地在Turtlebot3标准模拟器上调整运行过滤器信息发布器服务器和地图服务器,写在 入门 ,构建示例并启动``costmap_filter_info.launch.py`` 如下: [校准@混沌无形]
$ mkdir -p ~/tutorials_ws/src
$ cd ~/tutorials_ws/src
$ git clone https://github.com/ros-planning/navigation2_tutorials.git
$ cd ~/tutorials_ws
$ colcon build --symlink-install --packages-select nav2_costmap_filters_demo
$ source ~/tutorials_ws/install/setup.bash
$ ros2 launch nav2_costmap_filters_demo costmap_filter_info.launch.py params_file:=src/navigation2_tutorials/nav2_costmap_filters_demo/params/keepout_params.yaml mask:=src/navigation2_tutorials/nav2_costmap_filters_demo/maps/keepout_mask.yaml
3.启用禁止区域过滤器 [校准@混沌无形]
成本地图过滤器是Costamp2D插件。您可以在Costmap2D中启用 KeepoutFilter
插件添加 keepout_filter
的 plugins
参数 nav2_params.yaml
。你可以把它放在 global_costmap
中,以便在规划时考虑到禁区,而 local_costmap
则确保机器人不会试图驶过禁区。KeepoutFilter插件应该有以下参数定义: [校准@混沌无形]
plugin
: 插件类型. 在我们的案例中,nav2_costmap_2d::KeepoutFilter
. [校准@混沌无形]上一章中的成本地图过滤器信息发布者服务器的``filter_info_topic``: 过滤器信息话题名称. 这需要和
filter_info_topic
参数对应。 [校准@混沌无形]
参数 KeepoutFilter
支持的参数的完整列表列在 保留过滤器参数 [待校准@2901] 页面。 [待校准@1334]
重要的是要注意,只允许 KeepoutFilter
使用 global_costmap
会导致planner绕过禁区建立规划。只为 local_costmap
启用 KeepoutFilter
会导致机器人不进入禁区,但路径可能仍然会穿过它们。所以,最佳实用技术是启用 KeepoutFilter
同时把它添加在 nav2_params.yaml``文件中的全局成本地图 ``global_costmap
和 局部成本地图``local_costmap`` 。然而,这并不总是对的。在某些情况下,全局和局部成本地图的保留区域不必相同,例如,如果机器人不允许故意进入保留区域,但如果它在那里,如果机器人夹住一个边缘或角落,它可以快速进出。对于这种情况,不需要使用本地成本地图副本的额外资源。 [校准@混沌无形]
要为全局和本地成本地图启用具有相同掩码的 KeepoutFilter
,请使用以下配置: [校准@混沌无形]
global_costmap:
global_costmap:
ros__parameters:
...
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
filters: ["keepout_filter"]
...
keepout_filter:
plugin: "nav2_costmap_2d::KeepoutFilter"
enabled: True
filter_info_topic: "/costmap_filter_info"
...
local_costmap:
local_costmap:
ros__parameters:
...
plugins: ["voxel_layer", "inflation_layer"]
filters: ["keepout_filter"]
...
keepout_filter:
plugin: "nav2_costmap_2d::KeepoutFilter"
enabled: True
filter_info_topic: "/costmap_filter_info"
备注
所有的成本地图过滤器都应该通过一个 filters
参数来启用 -- 尽管在技术上可以包括在分层成本图本身。这是与图层插件分开的,以防止对图层的干扰,特别是膨胀层。 [校准@混沌无形]
4.运行Nav2软件 [校准@混沌无形]
在启动成本地图过滤器的信息发布服务器和地图服务器,并为全局/局部成本地图启用禁区过滤器之后,运行Nav2软件的情况写在 入门 : [校准@混沌无形]
ros2 launch nav2_bringup tb3_simulation_launch.py
并检查过滤器是否正常工作,如下图所示 (第一张图片显示为全局成本地图启用了禁区过滤器,第二张为尺寸不同的 keepout_mask.pgm
过滤器掩码): [校准@混沌无形]