Navigation 2 Logo
latest
  • 开始使用
    • 安装
    • 运行示例
    • 导航
  • 开发指南
    • 构建和安装
      • 安装
      • 构建
        • 已发布的分发二进制文件
        • 滚动式开发源代码
        • Docker 容器映像
      • 生成 Doxygen
      • 帮助
        • 构建故障排除指南
    • 开发容器
      • 开发容器指南
        • 创建开发容器
        • 使用 Dev Containers
      • 什么、为什么、如何?
        • 什么是开发容器?
        • 为什么要使用开发容器?
        • 开发容器是如何工作的?
      • 前提条件
      • 入门
      • 安全性
    • 参与进来
      • 参与进来
      • 过程
      • 许可证
      • 开发者原产地认证(DCO)
  • 导航概念
    • ROS 2
      • 动作服务器
      • 生命周期节点和 Bond
    • 行为树
    • 导航服务器
      • 规划器、控制器、平滑器和恢复服务器
      • 规划器
      • 控制器
      • 行为
      • 平滑器
      • 路径点跟随
    • 状态估计
      • 标准
      • 全局定位:定位和SLAM
      • 里程计
    • 环境表示
      • 代价地图和层
      • 代价地图过滤器
      • 其他形式
    • Nav2学术概述
  • 首次机器人设置指南
    • 设置变换
      • 变换介绍
      • 静态变换发布器演示
      • Navigation2中的变换
      • 结论
    • 设置URDF
      • URDF和机器人状态发布器
      • 设置环境
      • 编写URDF
      • 构建和启动
      • 使用RVIZ进行可视化
      • 添加物理属性
      • 结论
    • 设置里程计
      • 里程计简介
      • 设置机器人的里程计
      • 使用 Gazebo 模拟 Odometry 系统
        • 设置和先决条件
        • 向 URDF 添加 Gazebo 插件
        • 启动和构建文件
        • 构建、运行和验证
      • 机器人定位演示
        • 配置机器人定位
        • 启动和构建文件
        • 构建、运行和验证
      • 结论
    • 设置传感器
      • 传感器介绍
        • 常用传感器消息
      • 使用Gazebo模拟传感器
        • 向 URDF 添加 Gazebo 插件
        • 启动和构建文件
        • 构建、运行和验证
      • 建图与定位
      • 二维代价地图
        • 配置 nav2_costmap_2d
        • 构建、运行和验证
      • 结论
    • 设置机器人的轮廓
      • 轮廓介绍
      • 配置机器人的轮廓
      • 构建、运行和验证
      • 在RViz中可视化足迹
      • 结论
    • 设置导航插件
      • 规划器和控制器服务器
      • 选择算法插件
        • 规划器服务器
        • 控制器服务器
      • 结论
  • 常规教程
    • 使用实体Turtlebot 3导航
      • 概述
      • 要求
      • 教程步骤
        • 0- 设置环境变量
        • 1- 启动Turtlebot 3
        • 2- 启动Nav2
        • 3- 启动RVIZ
        • 4- 初始化Turtlebot 3的位置
        • 5- 发送目标姿态
    • (SLAM)在制图时导航
      • 概述
      • 要求
      • 教程步骤
        • 0- 启动机器人接口
        • 1- 启动 Navigation2
        • 2- 启动 SLAM
        • 3- 使用 SLAM
        • 4- 快速入门简化
    • (STVL) 使用外部代价图插件
      • 概述
      • Costmap2D 和 STVL
      • 教程步骤
        • 0- 设置
        • 1- 安装 STVL
        • 1- 修改Navigation2参数
        • 2- 启动Navigation2
        • 3- RVIZ
    • Groot - 与行为树交互
      • 概述
      • 可视化行为树
      • 编辑行为树
      • 添加自定义节点
    • 相机校准
      • 概述
      • 要求
      • 教程步骤
    • 在ROS 2 / Nav2中获取回溯
      • 概述
      • 准备工作
      • 从一个节点开始
      • 从启动文件
      • 从大型项目
      • 来自Nav2 Bringup
      • 崩溃时自动获取回溯信息
    • 在 ROS 2 / Nav2 中进行性能分析
      • 概述
      • 准备工作
      • 来自节点的配置文件
      • 从启动文件中进行分析
      • 来自Nav2 Bringup
      • 解释结果
    • 动态对象跟随
      • 概述
      • 教程步骤
        • 0- 创建行为树
        • 1- 设置 Rviz 点击点
        • 2- 在Nav2仿真中运行动态物体跟随
    • 使用禁止区域进行导航
      • 概述
      • 要求
      • 教程步骤
        • 1. 准备过滤掩模
        • 2. 配置成本地图过滤器信息发布服务器
        • 3. 启用Keepout过滤器
        • 4. 运行Nav2堆栈
    • 带速度限制的导航
      • 概述
      • 要求
      • 教程步骤
        • 1. 准备过滤掩模
        • 2. 配置成本地图过滤器信息发布服务器
        • 3. 启用速度过滤器
        • 4. 运行Nav2堆栈
    • 使用旋转垫片控制器
      • 概述
      • 什么是旋转垫片控制器?
      • 配置旋转垫片控制器
      • 配置主控制器
      • 演示执行
    • 向BT添加平滑器
      • 概述
      • 要求
      • 教程步骤
        • 0- 熟悉平滑器BT节点
        • 1- 指定平滑器插件
        • 2- 修改您的BT XML
    • 使用碰撞监视器
      • 概述
      • 要求
      • 配置碰撞监视器
      • 准备Nav2堆栈
      • 演示执行
    • 添加一个新的Nav2任务服务器
      • 生命周期节点
      • 组合
      • 错误代码
      • 结论
    • 过滤噪声引起的障碍物
      • 概述
      • 要求
      • 教程步骤
        • 1. 启用去噪图层
        • 2. 运行Nav2 stack
      • 工作原理
  • 插件教程
    • 编写新的Costmap2D插件
      • 概述
      • 要求
      • 教程步骤
        • 1-编写一个新的Costmap2D插件
        • 2- 导出并制作 GradientLayer 插件
        • 3- 在Costmap2D中启用插件
        • 4- 运行GradientLayer插件
    • 编写一个新的规划器插件
      • 概述
      • 要求
      • 教程步骤
        • 1- 创建一个新的规划器插件
        • 2- 导出规划器插件
        • 3- 通过参数文件传递插件名称
        • 4- 运行 StraightLine 插件
    • 编写新的控制器插件
      • 概述
      • 要求
      • 教程步骤
        • 1- 创建一个新的控制器插件
        • 2- 导出控制器插件
        • 3- 通过参数文件传递插件名称
        • 4- 运行 Pure Pursuit Controller 插件。
    • 编写新的行为树插件
      • 概述
      • 要求
      • 教程步骤
        • 1- 创建一个新的BT插件
        • 2- 导出规划器插件
        • 3- 将插件库名称添加到配置中
        • 4- 运行您的自定义插件
    • 编写新的行为插件
      • 概述
      • 要求
      • 教程步骤
        • 1- 创建一个新的行为插件
        • 2- 导出行为插件
        • 3- 通过参数文件传递插件名称
        • 4- 运行行为插件
    • 编写新的导航器插件
      • 概述
      • 要求
      • 教程步骤
        • 1- 创建新的导航器插件
        • 2- 导出导航器插件
        • 3- 通过参数文件传递插件名称
        • 4- 运行插件
  • 配置指南
    • 行为树导航器
      • 参数
      • 示例
    • 行为树XML节点
      • 动作插件
        • 等待
        • Spin
        • 备份
        • DriveOnHeading
        • 辅助遥控
        • ComputePathToPose(计算路径到位姿)
        • FollowPath
        • NavigateToPose
        • 清除整个成本地图
        • ClearCostmapExceptRegion
        • ClearCostmapAroundRobot
        • ReinitializeGlobalLocalization(重新初始化全局定位)
        • TruncatePath
        • TruncatePathLocal
        • PlannerSelector(规划器选择器)
        • ControllerSelector
        • SmootherSelector
        • GoalCheckerSelector
        • NavigateThroughPoses
        • 计算路径通过姿势
        • RemovePassedGoals(移除已通过的目标)
        • CancelControl
        • CancelBackUp
        • CancelSpin
        • 取消等待
        • CancelDriveOnHeading
        • CancelAssistedTeleop
        • 平滑路径
      • 条件插件
        • 目标已达成
        • 可转换
        • DistanceTraveled
        • GoalUpdated
        • GloballyUpdatedGoal
        • 接收到初始姿势
        • 是否卡住
        • 时间已过期
        • 电池是否低电量
        • 路径是否有效
        • 路径到期计时器
        • 是否存在错误代码
        • 是否需要控制器恢复帮助
        • 是否需要规划器恢复帮助
        • WouldASmootherRecoveryHelp
        • 电池是否正在充电
      • 控制插件
        • 管道序列
        • RoundRobin
        • 恢复节点
      • 装饰器插件
        • RateController
        • DistanceController
        • SpeedController 速度控制器
        • 目标更新器
        • PathLongerOnApproach
        • SingleTrigger 单触发器
      • 示例
    • 二维代价地图
      • 二维代价地图 ROS 参数
      • 默认插件
      • 插件参数
        • 静态层参数
        • 膨胀层参数
        • 障碍物图层参数
        • 体素层参数
        • 范围传感器参数
        • 降噪层参数
      • 成本地图过滤器参数
        • 保护区过滤器参数
        • 速度过滤器参数
        • 二值过滤器参数
      • 示例
    • 生命周期管理器
      • 参数
      • 示例
    • 规划器服务器
      • 参数
      • 默认插件
      • 示例
    • NavFn规划器
      • 参数
      • 示例
    • Smac规划器
      • Provided Plugins
        • Smac 2D Planner
        • Smac混合A*规划器
        • Smac状态格规划器
      • 描述
    • Theta Star Planner
      • 参数
      • 示例
    • 控制器服务器
      • 参数
      • Provided Plugins
        • SimpleProgressChecker
        • PoseProgressChecker
        • SimpleGoalChecker"
        • StoppedGoalChecker
      • 默认插件
      • 示例
    • DWB控制器
      • 控制器
        • DWB控制器
        • XYTheta 迭代器
        • 运动学参数
        • 发布者
      • 插件
        • LimitedAccelGenerator
        • StandardTrajectoryGenerator(标准轨迹生成器)
      • 轨迹评论家
        • BaseObstacleCritic
        • GoalAlignCritic
        • GoalDistCritic
        • ObstacleFootprintCritic
        • OscillationCritic
        • PathAlignCritic
        • PathDistCritic
        • PreferForwardCritic
        • RotateToGoalCritic
        • TwirlingCritic
      • 示例
    • 规定纯追踪
      • 规定纯追踪参数
      • 示例
    • 模型预测路径积分控制器
      • MPPI 参数
        • 轨迹可视化
        • 路径处理器
        • 阿克曼运动模型
        • 约束评估器
        • 目标角度评价器
        • 目标评估器
        • 障碍物评估器
        • 路径对齐评论家
        • 路径角度评论器
        • 路径跟随评论家
        • 优先正向评论家
        • 旋转评论家
      • 示例
      • 用户注意事项
        • 智慧的一般性言论
        • 预测视野、成本地图尺寸和偏移量
        • 障碍物、膨胀层和路径跟踪
    • 旋转增益控制器
      • 旋转适配器控制器参数
      • 示例
    • 地图服务器/保存器
      • 地图保存器参数
      • 地图服务器参数
      • Costmap过滤器信息服务器参数
      • 示例
    • AMCL
      • 参数
      • 示例
    • 行为服务器
      • Behavior Server参数
      • 默认插件
      • 旋转行为参数
      • 后退行为参数
      • 按目标导航行为参数
      • 辅助遥操作行为参数
      • 示例
    • 平滑服务器
      • 平滑器服务器参数
      • 示例
    • 简单平滑器
      • 简单平滑器参数
      • 示例
    • Savitzky-Golay平滑器
      • Savitzky-Golay平滑器参数
      • 示例
    • 约束平滑器
      • 平滑器服务器参数
      • 示例
    • 速度平滑器
      • 速度平滑器参数
      • 示例
    • 碰撞监控
      • 特点
      • 参数
        • 多边形参数
        • 观测源参数
      • 示例
    • 路径点跟随器
      • 参数
      • Provided Plugins
        • WaitAtWaypoint
        • PhotoAtWaypoint
        • InputAtWaypoint
      • 默认插件
      • 示例
  • 调优指南
    • 膨胀潜力场
    • 机器人足迹与半径
    • 就地旋转行为
    • 规划器插件选择
    • 控制器插件选择
    • 在 Smac 规划器中缓存障碍物启发式函数
    • Nav2 启动选项
    • 其他我们愿意提供的页面
  • Nav2行为树
    • 导航2特定节点介绍
      • 动作节点
      • 条件节点
      • 装饰节点
      • Control: PipelineSequence
      • 控制:恢复
      • 控制:RoundRobin
    • 详细的行为树遍历
      • 概述
      • 前提条件
      • 使用重新规划和恢复导航到姿势
      • 导航子树
      • 恢复子树
    • 导航到姿势
    • 导航到姿态
    • 导航到姿势并在目标障碍物附近暂停
    • 使用一致重新规划和如果路径无效则导航到姿态
    • 跟随动态点
    • 里程计校准
  • 导航插件
    • 行为树导航器
    • Costmap Layers
    • 代价地图过滤器
    • 控制器
    • 规划器
    • 平滑器
    • 行为
    • 路径点任务执行器
    • 目标检查器
    • 进度检查器
    • 行为树节点
  • 迁移指南
    • 从Dashing到Eloquent
      • 新的包
      • 新插件
      • Navigation2架构更改
    • 从Eloquent升级到Foxy
      • 常规
      • 服务器更新
      • 新插件
      • 地图服务器重构
      • 新的粒子滤波器消息
      • 每个导航动作中的行为树选择
      • FollowPoint功能
      • 新的Costmap图层
    • Foxy到Galactic
      • NavigateToPose动作反馈更新
      • NavigateToPose BT节点接口更改
      • 新增了NavigateThroughPoses和ComputePathThroughPoses动作。
      • ComputePathToPose BT节点接口更改
      • ComputePathToPose Action接口变更
      • 备份BT节点接口更改
      • 备份恢复接口更改
      • Nav2控制器和目标检查器插件接口更改
      • FollowPath 的 goal_checker_id 属性
      • Groot 支持
      • 新插件
      • 代价地图过滤器
      • SmacPlanner
      • ThetaStarPlanner
      • RegulatedPurePursuitController
      • Costmap2D current_ 使用方法
      • 参数中的标准时间单位
      • 光线追踪参数
      • 障碍物标记参数
      • 恢复动作变更
      • 默认行为树变更
      • NavFn规划器参数
      • 新的 ClearCostmapExceptRegion 和 ClearCostmapAroundRobot BT 节点
      • 新的行为树节点
      • sensor_msgs/PointCloud to sensor_msgs/PointCloud2 Change
      • ControllerServer 新参数 failure_tolerance
      • 移除了BT XML启动配置
      • Nav2 RViz 面板的行动反馈信息
    • Galactic转换为Humble
      • 对Smac规划器进行了重大改进
      • 简单(Python)指令器
      • 减少节点和执行器
      • nav2_core的API更改
      • 扩展BtServiceNode以处理服务结果
      • 包括新的旋转Shim控制器插件
      • 在Gazebo中生成机器人
      • 恢复行为超时
      • 3个2D规划器的新参数``use_final_approach_orientation``
      • SmacPlanner2D和Theta*:修复目标方向被忽略的问题
      • SmacPlanner2D、NavFn和Theta*:修复小路径的边界情况
      • 更改和修复动态参数更改检测的行为
      • 动态参数
      • BT Action节点异常变更
      • BT Navigator Groot多导航器
      • 在 RPP 中移除了运动限制
      • 添加了更平滑的任务服务器
      • 在 RPP 中移除了使用接近速度缩放参数
      • 将 AMCL 运动模型重构为插件
      • 停止支持 Nav2 的实时 Groot 监控
      • 仅在路径无效时重新规划
      • 修复 CostmapLayer 清除区域的反转参数逻辑
      • 动态组合
      • BT取消节点
      • BT PathLongerOnApproach 节点
      • BT TruncatePathLocal 节点
      • 约束平滑器
      • 以恒定速率重新规划路径,如果路径无效则重新规划
      • 二维欧几里得距离
      • 恢复至行为
      • 启动和生命周期管理中的重新生成支持
      • 新增Nav2速度平滑器
      • 目标检查器API已更改
      • 新增辅助遥操作
    • 从Humble升级到Iron
      • 新增行为树导航插件
      • 添加了碰撞监测器。
      • 从 yaml 文件中移除了 use_sim_time。
      • Smac 规划器的运行时加速。
      • 对 Smac 和 Simple 平滑器进行了递归细化。
      • 简单指挥官 Python API
      • Smac 规划器路径包括起始姿态
      • 可参数化的 RPP 碰撞检查
      • 扩展规划器基准测试
      • Smac 规划器路径容差
      • costmap_2d_node 默认构造函数
      • 导航失败的反馈
      • 代价地图过滤器
      • Savitzky-Golay平滑器
      • 更改启动文件中map_server节点的地图yaml文件路径。
      • SmootherSelector BT节点
      • 发布Costmap图层
      • 让行为服务器访问两个Costmap
      • 新的模型预测路径积分控制器
      • 行为树使用错误代码
      • 从RViz的Nav2面板中加载、保存和循环使用路径点
      • DWB正向和反向修剪
      • 在长远的前瞻距离下对曲线进行更稳定的调节
      • 发布碰撞监视器状态
      • 碰撞监视器中的ROS参数已重命名
      • 碰撞监视器中新增了安全行为模型“limit”
      • 当超时时,速度平滑器应用减速
      • PoseProgressChecker插件
      • 允许多个目标检查器并更改参数progress_checker_plugin(s)的名称和类型
      • IsBatteryChargingCondition BT节点
      • 行为服务器错误代码
      • 新的去噪代价地图层插件
      • SmacPlannerHybrid viz_expansions 参数
  • 简单指挥官API
    • 概述
    • 指挥官 API
    • Costmap API
    • 足迹碰撞检查器 API
    • 示例和演示
  • 路线图
    • 铁路路线图
    • 谦虚的路线图
  • 关于和联系
    • 相关项目
    • ROS 到 ROS 2 导航
    • 关于
    • 联系方式
  • Robots Using
Navigation 2
Edit
  • »
  • 常规教程 »
  • 使用禁止区域进行导航

使用禁止区域进行导航

  • 概述

  • 要求

  • 教程步骤

概述

本教程演示了如何简单地利用无法进入的禁止/安全区域以及工业环境和仓库中移动的机器人的首选车道。所有这些功能都由“KeepoutFilter”代价地图过滤器插件提供,该插件将在本文档中启用并使用。

要求

假设已安装或本地构建了ROS 2、Gazebo和TurtleBot3软件包。请确保Nav2项目也在本地构建,就像在:ref:`build-instructions`中所述一样。

教程步骤

1. 准备过滤掩模

如在:ref:`概念`中所述,任何代价地图过滤器(包括Keepout过滤器)都会读取过滤掩码文件中标记的数据。过滤掩码是一个通常通过PGM、PNG或BMP栅格文件进行分发的Nav2 2D地图,其元数据包含在一个YAML文件中。以下步骤有助于理解如何制作新的过滤掩码:

创建一个新的图像,格式为PGM/PNG/BMP:从``Nav2``存储库中复制用于世界模拟中的主地图``turtlebot3_world.pgm``到新的``keepout_mask.pgm``文件中。

在您喜欢的栅格图形编辑器中打开“keepout_mask.pgm”(例如,可以使用GIMP编辑器作为示例)。掩码上每个像素的亮度代表您将要使用的特定代价地图过滤器的编码信息。每个像素的颜色亮度属于“[0..255]”范围(或者百分比刻度下的“[0..100]”),其中“0”表示黑色,而“255”表示白色。另一个术语“黑暗”将被理解为亮度的确切相反。换句话说,“颜色黑暗度 = 100% - 颜色亮度”。

在GIMP中,亮度通过颜色分量值(例如,百分比比例中的``R``)来表示,并可以通过移动颜色更改工具中的``L``滑块来设置:

../../_images/ligtness_in_GIMP.png

地图服务器正在读取传入的掩码文件,并将其转换为来自“[0..100]”范围的“OccupancyGrid”值(其中“0”表示空闲单元格,“100”表示占用单元格,介于两者之间的任何值表示地图上更少或更多的占用单元格),或等于未知值的“-1”。在Nav2堆栈中,每个地图都具有“mode”属性,可以是“trinary”、“scale”或“raw”。根据所选的“mode”,PGM/PNG/BMP的颜色亮度将按照以下原则之一转换为“OccupancyGrid”:

  • trinary``(默认模式):暗度大于等于``occupied_thresh``表示地图被占用(``100)。暗度小于等于``free_thresh``表示地图为空闲(0)。两者之间的值表示地图上的未知状态(-1)。

  • “scale”:Alpha < 1.0 - 未知。黑暗度 >= “occupied_thresh”表示地图已占用(“100”)。黑暗度 <= “free_thresh” - 地图为空闲(“0”)。介于两者之间 - 线性插值到“[0..100]”范围内最近的整数。

  • raw:亮度为``0``(暗色)表示地图为空闲(0)。亮度为``100``(绝对值)表示地图被占用(100)。两者之间的值表示``OccupancyGrid``的值等于亮度。亮度大于等于``101``表示未知(-1)。

其中“free_thresh”和“occupied_thresh”阈值以最大亮度/黑暗度级别(“255”)的百分比表示。地图模式和阈值放置在YAML元数据文件中(见下文),作为“mode”、“free_thresh”和“occupied_thresh”字段。

注解

在YAML元数据文件中还有另一个参数叫做``negate``。默认情况下,它被设置为``false``。当它被设置为``true``时,较黑的像素将被视为可通行的,较白的像素将被视为占用的。在这种情况下,对于``trinary``和``scale``模式,我们应该计算颜色的亮度而不是暗度。``negate``对``raw``模式没有影响。

对于Keepout过滤器,“OccupancyGrid”值与与此单元格对应的区域的可通行性成比例:较高的值表示不可通过的区域更多。具有占用值的单元格覆盖了机器人永远不会进入或通过的禁止区域。通过将“OccupancyGrid”设置为介于“[1-99]”之间的非占用值,Keepout过滤器也可以作为“加权区域层”。机器人被允许在这些区域中移动,但是它在那里的存在将是“不可取的”(值越高,规划器越早尝试将机器人移出该区域)。

Keepout Filter还涵盖了首选车道的情况,即机器人只能在预定义的车道和允许的区域内移动,例如在仓库中。要使用此功能,您需要准备一个掩膜图像,在该图像中车道和允许的区域将被标记为可通行的值,而所有其他区域将被占用。在``trinary``或``scale``模式下绘制掩膜的提示:通常,属于车道的像素数量远少于覆盖其他区域的像素。在这种情况下,最初可以使用黑色铅笔在白色背景上绘制所有车道数据,然后(在保存PGM之前)可以使用图像光栅编辑器中的“颜色反转”工具。

为简化起见,在示例中使用黑色填充区域(在``trinary``模式下表示占用地图)来标记为禁止区域:

../../_images/drawing_keepout_mask.png

填充所有保留区域后保存``keepout_mask.pgm``图像。

与所有其他地图一样,过滤器掩码应具有自己的YAML元数据文件。将`turtlebot3_world.yaml <https://github.com/ros-planning/navigation2/blob/main/nav2_bringup/bringup/maps/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``字段,以便将过滤器掩码正确放置在原始地图上。

注解

另一个重要说明是,由于Costmap2D不支持方向性,origin``向量的最后一个``yaw``分量应该等于零。例如:``origin: [1.25, -5.18, 0.0]。

2. 配置成本地图过滤器信息发布服务器

每个costmap过滤器在``nav2_msgs/CostmapFilterInfo``类型的消息中读取传入的元信息(例如过滤器类型或数据转换系数)。这些消息由`Costmap Filter Info Publisher Server <https://github.com/ros-planning/navigation2/tree/main/nav2_map_server/src/costmap_filter_info>`_发布。服务器作为生命周期节点运行。根据`设计文档 <https://github.com/ros-planning/navigation2/blob/main/doc/design/CostmapFilters_design.pdf>`_,``nav2_msgs/CostmapFilterInfo``消息与``OccupancyGrid``过滤器掩膜主题成对出现。因此,在启用Costmap Filter Info Publisher Server的同时,应启用一个新的Map Server实例,并配置它来发布过滤器掩膜。

为了在配置中启用禁止区域过滤器,两个服务器都应作为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``变

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"

请注意:

  • 对于Keepout过滤器,costmap过滤器的“type”应设置为“0”。

  • 过滤器掩码主题名称应与成本地图过滤器信息发布服务器的``mask_topic``参数和地图服务器的``topic_name``参数相等。

  • 根据Costmap过滤器的设计,OccupancyGrid的值在过滤器空间中被线性转换为特征图。对于Keepout过滤器,这些值直接作为过滤器空间的值传递,而不进行线性转换。即使在Keepout过滤器中未使用基础(base)和乘数(multiplier)系数,它们应分别设置为“0.0”和“1.0”,以明确表示我们从OccupancyGrid的值转换为过滤器值空间时是一对一的关系。

可在``navigation2_tutorials``存储库的``nav2_costmap_filters_demo``目录中找到完全可用的独立Python启动脚本、带有ROS参数和Keepout Filter示例的YAML文件。要简单运行Filter Info Publisher服务器和Map服务器以及在Turtlebot3标准仿真中进行调优,按照:ref:getting_started`中的说明构建演示并启动``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. 启用Keepout过滤器

Costmap Filters是Costamp2D插件。您可以通过在``nav2_params.yaml``的``plugins``参数中添加``keepout_filter``来启用Costmap2D中的``KeepoutFilter``插件。您可以将其放置在``global_costmap``中以便进行带有禁区的规划,将其放置在``local_costmap``中以确保机器人不会试图穿越禁区。KeepoutFilter插件应定义以下参数:

  • “plugin”:插件的类型。在我们的例子中为“nav2_costmap_2d::KeepoutFilter”。

  • filter_info_topic:过滤器信息主题名称。这个参数需要与上面章节中的Costmap Filter Info Publisher Server的``filter_info_topic``参数相等。

“KeepoutFilter”支持的参数的完整列表请参考:ref:`keepout_filter`页面。

重要的是要注意,仅在``global_costmap``中启用``KeepoutFilter``将导致路径规划器在绕过禁区时建立计划。仅在``local_costmap``中启用``KeepoutFilter``将导致机器人不进入禁区,但路径仍然可能穿过禁区。因此,最佳做法是在``nav2_params.yaml``中同时将其添加到``global_costmap``和``local_costmap``中,以同时启用全局和局部costmap的``KeepoutFilter``。然而,并不总是必须如此。在某些情况下,全局costmap和局部costmap的禁区可能不同,例如,如果机器人不允许有意进入禁区,但如果在禁区内,机器人可以非常快速地进入和离开,只要它碰到一个边缘或角落。对于这种情况,不需要使用局部costmap副本的额外资源。

要为全局和局部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"

注解

所有costmap过滤器都应通过``filters``参数启用-尽管在分层costmap中包含它们也是可行的。这是为了防止干扰层,尤其是膨胀层。

4. 运行Nav2堆栈

在启动Costmap Filter Info Publisher Server和Map Server并为全局/局部costmap启用Keepout Filter后,按照:ref:`getting_started`中的说明运行Nav2堆栈:

ros2 launch nav2_bringup tb3_simulation_launch.py

请确保过滤器按照下面的图片正确工作(第一张图片显示全局代价地图启用了keepout过滤器,第二张图片显示大小不同的`keepout_mask.pgm`过滤器掩码):

../../_images/keepout_global.gif ../../_images/keepout_mask.png

© 版权所有 2020.