zoukankan      html  css  js  c++  java
  • 7.1-Move_base 参数调整

    Move_base Tuining

    前言

    参考

    Basic Guide
    Local Planner
    Move_base setup
    Move_base Param
    局部规划器的动态窗口法
    航迹推演odometry
    DWA算法分析
    base_local_planner

    任务要求

    • 了解dynamic window局部规划原理,调整局部规划器的功能,使得正常避障。
    • 了解当前上层规划策略,调整move_base离散规划的策略,重点是调整其状态机。
    • 看看Action功能能不能和LV端协作起来完成功能。

      本项目立足未知大环境下的导航,特点是:只有基于节点的拓扑地图,没有使用激光SLAM工具制图与定位,因为在未知大环境下,无法预先进行制图,即使进行SLAM,环境数据太大太多,故使用先验的全局地图,机器人在运行过程中动态维护该地图(如基于视觉的语义标签),在维护的过程中进行动态的语义规划,激光等传感器只用于局部规划器,在局部的动态环境中进行路劲规划是用于避障。
      路径规划的定义:在约束条件(能量消耗最少,路径最短,躲避障碍)下对机器人(在其工作空间中)从一个状态到另一个状态的路径的求解。
      SLAM:同时定位和制图,主要包括三个点,定位,制图,导航(路径规划,包括全局路径规划,局部路径规划,轨迹生成)
      全局路径规划

    学习记录

    基本调参指南

    确定激光或者声纳的完整性

    • 一般可以通过rviz来确认
    • 本项目中,传感器的有效性由购买的先锋机器人保证

    里程计的有效性

    • 一般分为旋转和平移,旋转可以使用原地旋转,平移可以沿着墙行走看看位置数据变化。
    • 本项目中,里程计由先锋机器人的IMU保证

    定位的有效性

    • 查看AMCL是否运行有效
    • 本项目中,使用人工定位方法,即机器人在出生点时被指定当前坐标。

    代价地图

    • 机器人导航所用地图有多种,包括拓扑地图(节点地图),精确分解地图,占据栅格地图(不精确的分解地图)等,ROS导航包中采用分层的栅格代价地图,这是David.Lu!!在13-14年接手NavStack后所做的一些工作,如一层sensor_msgs/Range构建的激光地图range_sensor_layer,一层由监测到的人的位置所构建的social_layer,每一层接收一种特定的传感特征信息或执行一种特定权值计算算法,通过不同的栅格赋值策略,将costmap的值修改,达到改变机器人行为的目的。到底是如何改变机器人行为的呢,主要是在局部规划中改变机器人的运动轨迹。
    • 代价地图分层,具体做法是将不同类型的栅格赋值过程通过pluginlib进行解耦和隔离, 每一种不同的栅格类型抽象成一层,layer,每一层可以使用不同的传感器数据输入, 不同的栅格赋值策略,当然最后还是合成一个当前内置的地图层包括:Static Map Layer; Obstacle Map Layer(二维或三维); Inflation Layer
    • costmap_2d package中实现了带权栅格地图 的环境表示方式. 作为导航架构中环境表示模块,承担了与传感器数据流交互,暴露接口给planner进行规划
    • Costmap_2d主要流程为输入激光雷达laserscan 或者点云 pointcloud 数据(当然可以自己定义别的), 从tf tree上获取定位数据, 进行已知定位数据的建图处理. 因为是根据已知定位数据的建图算法,假设定位数据精确. 所以如何选取全局定位坐标系,很大程度上决定了建图质量, 很多问题也源于此.
    • Costmap 除去参数设置和多线程调度, 已知定位数据的建图 核心步骤是raytrace过程.算法过程如下:
    1. 得到当前时刻的机器人当前的全局位置pos, 传感器相对机器人中心坐标系偏移offset, 将不同的传感器数据统一处理成点云, 将传感器中心以及点云数据转换到全局坐标系.
    2. 根据传感器模型,从传感器中心到点云的连线, 这一部分空间为没有障碍物的安全空间free, 点云的位置为障碍物所在位置occupied, 根据我们对于costmap中, 栅格cost的定义, 对连线上赋权值. 一般使用bresenham算法将直线离散化到栅格中.
    3. 确定了free 和 occupied的栅格, 根据costmap 中对栅格权值的分类,将unkown 和inflation 等部分的权值填上, inflation 使用广度优先的方式进行扩展栅格, 将occupied 的栅格入队, 然后层层扩展,得到膨胀出去的栅格,并赋值.

    局部规划器

    • 首先需要选择是dwa还是base_local_planner
    • 最重要的参数是加速度的上限值需要明确和一致,因为局部规划器就是基于这些值做模拟,

    局部规划器原理

    <1 由移动底盘的运动学模型得到速度的采样空间.
    在给定的速度加速度限制下, 在给定时间间隔下, 没有碰撞的速度为admission velocity.
    (这些给定的限制都是我们需要调试的参数)
    <2 在采样空间中, 我们计算每个样本的目标函数:
    NF =α ⋅vel + β ⋅nf +γ ⋅Δnf +δ ⋅ goal
    Vel 当前速度值
    Nf 到当前目标点的相关的cost 值
    Δnf 与全局路径的贴合程度的cost 值
    Goal 到全局目标点的距离值.
    还有一些cost可以自己定义, navigation实现中还有对最大最小障碍物距离的cost 与倾向于向前走的cost.
    然后α,β,γ,δ 都是权重参数, 调节这些参数可以极大影响机器人避障行为
    <3 得到期望速度, 插值成轨迹输出给move_base

    各模块参数

    代价地图

    • Coordinate frame and tf parameters
    ~<name>/global_frame (string, default: "/map")
    The global frame for the costmap to operate in.代价地图在哪一个坐标系的基础上制作
    ~<name>/robot_base_frame (string, default: "base_link")
    The name of the frame for the base link of the robot.传感器数据转换为地图上数据的桥梁
    ~<name>/transform_tolerance (double, default: 0.2)
    Specifies the delay in transform (tf) data that is tolerable in seconds. This parameter serves as a safeguard to losing a link in the tf tree while still allowing an amount of latency the user is comfortable with to exist in the system. For example, a transform being 0.2 seconds out-of-date may be tolerable, but a transform being 8 seconds out of date is not. If the tf transform between the coordinate frames specified by the global_frame and robot_base_frame parameters is transform_tolerance seconds older than ros::Time::now(), then the navigation stack will stop the robot.延迟时间,和实时性要求有关,这个时间参数实际上是允许TF传输延迟,参数设置过大会影响机器人的行为。
    • Rate parameters
    ~<name>/update_frequency (double, default: 5.0)
    The frequency in Hz for the map to be updated.图的更新频率,需要配合传感器数据的发布频率。考虑机器人处理器速度。
    ~<name>/publish_frequency (double, default: 0.0)
    The frequency in Hz for the map to be publish display information.发布频率,主要被RViz接收,需要考虑地图大小来设置发布频率。
    • Map management parameters
    ~<name>/rolling_window (bool, default: false)
    Whether or not to use a rolling window version of the costmap. If the static_map parameter is set to true, this parameter must be set to false.
    ~<name>/always_send_full_costmap (bool, default: false)
    If true the full costmap is published to "~<name>/grid" every update. If false only the part of the costmap that has changed is published on the "~<name>/grid_updates" topic.
    • The following parameters can be overwritten by some layers, namely the static map layer.
    ~<name>/width (int, default: 10)
    The width of the map in meters.地图的几何参数,也会影响路径规划精度。
    ~<name>/height (int, default: 10)
    The height of the map in meters.
    ~<name>/resolution (double, default: 0.05)
    The resolution of the map in meters/cell.
    ~<name>/origin_x (double, default: 0.0)
    The x origin of the map in the global frame in meters.
    ~<name>/origin_y (double, default: 0.0)
    The y origin of the map in the global frame in meters. 

    障碍层地图参数

    障碍地图基于激光点云数据,给代价地图标上障碍物信息。

    Sensor management parameters
    ~<name>/observation_sources (string, default: "")
    A list of observation source names separated by spaces. This defines each of the <source_name> namespaces defined below.
    Each source_name in observation_sources defines a namespace in which parameters can be set:
    ~<name>/<source_name>/topic (string, default: source_name)
    The topic on which sensor data comes in for this source. Defaults to the name of the source.
    ~<name>/<source_name>/sensor_frame (string, default: "")
    The frame of the origin of the sensor. Leave empty to attempt to read the frame from sensor data. The frame can be read from both sensor_msgs/LaserScan, sensor_msgs/PointCloud, and sensor_msgs/PointCloud2 messages.
    ~<name>/<source_name>/observation_persistence (double, default: 0.0)
    How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading.
    ~<name>/<source_name>/expected_update_rate (double, default: 0.0)
    How often to expect a reading from a sensor in seconds. A value of 0.0 will allow infinite time between readings. This parameter is used as a failsafe to keep the navigation stack from commanding the robot when a sensor has failed. It should be set to a value that is slightly more permissive than the actual rate of the sensor. For example, if we expect a scan from a laser every 0.05 seconds we might set this parameter to be 0.1 seconds to give a generous buffer and account for some amount of system latency.
    ~<name>/<source_name>/data_type (string, default: "PointCloud")
    The data type associated with the topic, right now only "PointCloud", "PointCloud2", and "LaserScan" are supported.
    ~<name>/<source_name>/clearing (bool, default: false)
    Whether or not this observation should be used to clear out freespace.
    ~<name>/<source_name>/marking (bool, default: true)
    Whether or not this observation should be used to mark obstacles.
    ~<name>/<source_name>/max_obstacle_height (double, default: 2.0)
    The maximum height in meters of a sensor reading considered valid. This is usually set to be slightly higher than the height of the robot. Setting this parameter to a value greater than the global max_obstacle_height parameter has no effect. Setting this parameter to a value less than the global max_obstacle_height will filter out points from this sensor above that height.
    ~<name>/<source_name>/min_obstacle_height (double, default: 0.0)
    The minimum height in meters of a sensor reading considered valid. This is usually set to be at ground height, but can be set higher or lower based on the noise model of your sensor.
    ~<name>/<source_name>/obstacle_range (double, default: 2.5)
    The maximum range in meters at which to insert obstacles into the costmap using sensor data.
    ~<name>/<source_name>/raytrace_range (double, default: 3.0)
    The maximum range in meters at which to raytrace out obstacles from the map using sensor data.
    ~<name>/<source_name>/inf_is_valid (bool, default: false)
    Allows for Inf values in "LaserScan" observation messages. The Inf values are converted to the laser maximun range.
    Global Filtering Parameters

    Apply to all sensors.

    ~<name>/max_obstacle_height (double, default: 2.0)障碍高度
    The maximum height of any obstacle to be inserted into the costmap in meters. This parameter should be set to be slightly higher than the height of your robot.
    ~<name>/obstacle_range (double, default: 2.5)障碍范围:多少米范围内的障碍物被标识出来
    The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters. This can be over-ridden on a per-sensor basis.
    ~<name>/raytrace_range (double, default: 3.0)不知道啊,只知道raytrace是一种代价值传播的方法。
    The default range in meters at which to raytrace out obstacles from the map using sensor data. This can be over-ridden on a per-sensor basis.
    ObstacleCostmapPlugin

    This parameter is only used by the ObstacleCostmapPlugin

    ~<name>/track_unknown_space (bool, default: false)
    Specifies whether or not to track what space in the costmap is unknown, meaning that no observation about a cell has been seen from any sensor source.
    VoxelCostmapPlugin

    The following parameters are only used by the VoxelCostmapPlugin

    ~<name>/origin_z (double, default: 0.0)
    The z origin of the map in meters.
    ~<name>/z_resolution (double, default: 0.2)
    The z resolution of the map in meters/cell.
    ~<name>/z_voxels (int, default: 10)
    The number of voxels to in each vertical column, the height of the grid is z_resolution * z_voxels.
    ~<name>/unknown_threshold (int, default: ~<name>/z_voxels)
    The number of unknown cells allowed in a column considered to be "known"
    ~<name>/mark_threshold (int, default: 0)
    The maximum number of marked cells allowed in a column considered to be "free".
    ~<name>/publish_voxel_map (bool, default: false)
    Whether or not to publish the underlying voxel grid for visualization purposes. 
    膨胀地图

    膨胀地图指的是代价值从障碍物处向外侧进行的传播,传播后代价值有5个标识值:254,253,128,1,0。以127为界,以上为可能有障碍物,以下为应该没有障碍物。

    ~<name>/inflation_radius (double, default: 0.55) 
    The radius in meters to which the map inflates obstacle cost values.
    ~<name>/cost_scaling_factor (double, default: 10.0)
    A scaling factor to apply to cost values during inflation. The cost function is computed as follows for all cells in the costmap further than the inscribed radius distance and closer than the inflation radius distance away from an actual obstacle: exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1), where costmap_2d::INSCRIBED_INFLATED_OBSTACLE is currently 254. NOTE: since the cost_scaling_factor is multiplied by a negative in the formula, increasing the factor will decrease the resulting cost values. 

    move_base参数

    ~base_global_planner (string, default: "navfn/NavfnROS" For 1.1+ series)
    The name of the plugin for the global planner to use with move_base, see pluginlib documentation for more details on plugins. This plugin must adhere to the nav_core::BaseGlobalPlanner interface specified in the nav_core package. (1.0 series default: "NavfnROS")
    ~base_local_planner (string, default: "base_local_planner/TrajectoryPlannerROS" For 1.1+ series)
    The name of the plugin for the local planner to use with move_base see pluginlib documentation for more details on plugins. This plugin must adhere to the nav_core::BaseLocalPlanner interface specified in the nav_core package. (1.0 series default: "TrajectoryPlannerROS")
    ~recovery_behaviors (list, default: [{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: rotate_recovery, type: rotate_recovery/RotateRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}] For 1.1+ series) 
    ~controller_frequency (double, default: 20.0)
    The rate in Hz at which to run the control loop and send velocity commands to the base.
    ~planner_patience (double, default: 5.0)
    How long the planner will wait in seconds in an attempt to find a valid plan before space-clearing operations are performed.
    ~controller_patience (double, default: 15.0)
    How long the controller will wait in seconds without receiving a valid control before space-clearing operations are performed. 

    move_base状态机宏观行为控制

    ~conservative_reset_dist (double, default: 3.0)
    The distance away from the robot in meters at which obstacles will be cleared from the costmap when attempting to clear space in the map. Note, this parameter is only used when the default recovery behaviors are used for move_base.
    ~recovery_behavior_enabled (bool, default: true)
    Whether or not to enable the move_base recovery behaviors to attempt to clear out space.在本项目中应该为否
    ~clearing_rotation_allowed (bool, default: true)
    Determines whether or not the robot will attempt an in-place rotation when attempting to clear out space. Note: This parameter is only used when the default recovery behaviors are in use, meaning the user has not set the recovery_behaviors parameter to anything custom.在本项目中应该为否
    ~shutdown_costmaps (bool, default: false)
    Determines whether or not to shutdown the costmaps of the node when move_base is in an inactive state
    ~oscillation_timeout (double, default: 0.0)
    How long in seconds to allow for oscillation before executing recovery behaviors. A value of 0.0 corresponds to an infinite timeout. New in navigation 1.3.1
    ~oscillation_distance (double, default: 0.5)
    How far in meters the robot must move to be considered not to be oscillating. Moving this far resets the timer counting up to the ~oscillation_timeout New in navigation 1.3.1
    ~planner_frequency (double, default: 0.0)
    The rate in Hz at which to run the global planning loop. If the frequency is set to 0.0, the global planner will only run when a new goal is received or the local planner reports that its path is blocked. New in navigation 1.6.0

    恢复行为状态定制

    ~<name>/sim_granularity (double, default: 0.017)
    The distance in radians between checks for obstacles when checking if an in-place rotation is safe. Defaults to 1 degree.
    ~<name>/frequency (double, default: 20.0)
    The frequency in HZ at which to send velocity commands to the mobile base. 

    可以定制的地方

    • 这里记录除了参数调整之外,还可以进行程序定制的模块。
    • 机器人64X50X65cm
    • 全局规划器(采用不同的规划策略,离散策略都可以)
    • 局部规划器
    • 恢复行为
    • move_base状态机
    • 动作服务端编程
    • 层次代价地图(局部规划器,改变机器人行为,改动潜力大)
    • 地图维护

    参数调整要点

    • 全局代价地图所在坐标系与局部代价地图一样都在odometry,全局代价地图尺寸建议比局部地图大。
    • 查看计算机性能的一个指标是CPU利用率
    • 全局代价地图的膨胀半径应该比局部的大一点,这样可以在全局规划时规划出较安全的路径,而在局部规划时给与较大的自由。(个人理解)
    • 地图分辨率可不可以设小一点,更加精确。
    • 膨胀地图半径一般为机器人的半径,如果想要机器人更加冒险,应该增加cose_scaling_factor值,比如到100
    • 将move_base的恢复行为去掉
    • 代价地图的分辨率不可设置太小,不然全局路径可能会不平滑。但是平滑的轨迹不是由全局路径规划器来决定的,而是局部规划器来决定的,所以局部分辨率可以设置得高,但是会增加计算机压力,地图的生成会变慢,对于真机应该不是问题。
    • 为了使机器人运动更精确,尝试使局部规划器的位置公差参数调整至+-0.05。

    实际调参笔记

    • 全局代价地图的膨胀距离过大,需要调小,建议与局部规划器地图一样大
    • 记得开启zsProxy
    • 计算机性能不是问题,参数设置良好,局部规划器比较准
    • 网络有点卡,建议降低数据发布频率或者降低地图分辨率(只是显示卡,还是不改了)
    • 在真机上实验需要修改若干文件

    以前的笔记

    代价地图

    综述

    • 红色的是障碍物,蓝色的是障碍物的膨胀区域,红色多边形是机器人的轮廓,要做到避障,机器人的轮廓始终不能穿过蓝色区域,更不用说红色区域
    • 现有的功能是二维地图,只能做平面规划,但是障碍层地图可以是三维的

    标记与清除

    • 通过订阅特定传感器主题消息来更新地图

    占据与释放,未知区域(区域的三种属性)

    • 每一个网格都都可以有255种值(颜色),不过一般来讲只有三种颜色,要么是空的,要么是占据的,要么是未知的

    地图更新

    • 更新频率可以用参数控制

    tf

    • 为了适当地插入传感器数据,需要有合适的左边变换

    代价值

    • Lethal
      • 一个确定的障碍物
    • Inscribed(记名的)
      • 是一个障碍物,只是距离较远
    • Possibly circumscribed
      • 使用另一个距离阈值来度量的障碍物
    • Freespace
      • 零,没有任何东西,机器人不应该去那儿
    • Unknown
      • 没有信息
    • 其他

    地图类型

    • 第一种是static_map,第二种是设定好长和宽的rolling_window,这种地图会随着机器人的移动而移动。
  • 相关阅读:
    返回一个一维整数数组中最大子数组的和02
    软工作业04四则运算网页版
    所有子数组的和的最大值
    学习进度表(第五,六周)
    学习进度表(第四周)
    四则运算2的单元测试
    《构建之法》阅读笔记02
    软工作业03
    单元测试练习
    学习进度表(第三周)
  • 原文地址:https://www.cnblogs.com/lizhensheng/p/11117583.html
Copyright © 2011-2022 走看看