ROS Navigation-----dwa_local_planner(DWA)简介

    该包使用DWA(Dynamic Window Approach)算法实现了平面上移动机器人局部导航功能。 输入全局规划和代价地图后,局部规划器将会生成发送给移动底座的命令。该包适用于其footprint可以表示为凸多边形或者圆形的机器人,它导出配置参数为ROS参数形式,可以在启动文件进行配置,当然也可以动态配置。 这个包的ROS封装接口继承了BaseLocalPlanner接口。

1 Overview

  dwa_local_planner包实现了一个驱动底座移动的控制器,该控制器将路径规划器和机器人底座连在了一起。该规划器使用地图创建运动轨迹让机器人从起点到达目标点。移动过程中规划器会在机器人周围创建可以表示为珊格地图的评价函数。这里的控制器的主要任务就是利用评价函数确定发送给底座的速度(dx,dy,dtheta)。

local_plan.png

 DWA算法基本思路如下:

  1. 在机器人控制空间进行速度离散采样(dx,dy,dtheta)
  2. 对每一个采样速度执行前向模拟,看看使用该采样速度移动一小段段时间后会发生什么
  3. 评价前向模拟中每个轨迹,评价准则如: 靠近障碍物,靠近目标,贴近全局路径和速度;丢弃非法轨迹(如哪些靠近障碍物的轨迹)
  4. 挑出得分最高的轨迹并发送相应速度给移动底座
  5. 重复上面步骤.

一些有价值的参考:

2 DWAPlannerROS

 dwa_local_planner::DWAPlannerROS对象是dwa_local_planner::DWAPlanner对象的ROS封装,在初始化时指定的ROS命名空间使用,继承了nav_core::BaseLocalPlanner接口。

如下是一个简单的dwa_local_planner::DWAPlannerROS对象使用示例:

#include <tf/transform_listener.h>
#include <costmap_2d/costmap_2d_ros.h>
#include <dwa_local_planner/dwa_planner_ros.h>

...

tf::TransformListener tf(ros::Duration(10));
costmap_2d::Costmap2DROS costmap("my_costmap", tf);

dwa_local_planner::DWAPlannerROS dp;
dp.initialize("my_dwa_planner", &tf, &costmap);

2.1 API Stability

  • The C++ API is stable
  • The ROS API is stable

2.1.1Published Topics
~<name>/global_plan ( nav_msgs/Path)
  • 局部规划器当前正在跟踪的全局规划的一部分。Used primarily for visualization purposes.
~<name>/local_plan ( nav_msgs/Path)
  • 上一个周期的局部规划或者得分最高的轨迹。Used primarily for visualization purposes.

2.1.2 Subscribed Topics
odom ( nav_msgs/Odometry)
  • Odometry信息用于给局部规划器提供机器人当前移动速度。  本消息中的速度信息被假定使用了与TrajectoryPlannerROS对象的代价地图参数robot_base_frame设定值坐标系一致的坐标系。 关于参数robot_base_frame用法详见costmap_2d

2.2 Parameters

    有很多ROS参数可以用来配置dwa_local_planner::DWAPlannerROS的行为。 这些参数被分成了几组:: robot configuration, goal tolerance, forward simulation, trajectory scoring, oscillation prevention, and global plan.

    这些参数多数可以用 dynamic_reconfigure 进行动态配置,这样便于在系统运行时tune局部规划器。

2.2.1 Robot Configuration Parameters

~<name>/acc_lim_x (double, default: 2.5)

  • The x acceleration limit of the robot in meters/sec^2
~<name>/acc_lim_y ( double, default: 2.5)
  • The y acceleration limit of the robot in meters/sec^2
~<name>/acc_lim_th ( double, default: 3.2)
  • The rotational acceleration limit of the robot in radians/sec^2
~<name>/max_trans_vel ( double, default: 0.55)
  • The absolute value of the maximum translational velocity for the robot in m/s
~<name>/min_trans_vel ( double, default: 0.1)
  • The absolute value of the minimum translational velocity for the robot in m/s
~<name>/max_vel_x ( double, default: 0.55)
  • The maximum x velocity for the robot in m/s.
~<name>/min_vel_x ( double, default: 0.0)
  • The minimum x velocity for the robot in m/s, negative for backwards motion.
~<name>/max_vel_y ( double, default: 0.1)
  • The maximum y velocity for the robot in m/s
~<name>/min_vel_y ( double, default: -0.1)
  • The minimum y velocity for the robot in m/s
~<name>/max_rot_vel ( double, default: 1.0)
  • The absolute value of the maximum rotational velocity for the robot in rad/s
~<name>/min_rot_vel ( double, default: 0.4)
  • The absolute value of the minimum rotational velocity for the robot in rad/s

2.2.2 Goal Tolerance Parameters

~<name>/yaw_goal_tolerance (double, default: 0.05)

  • The tolerance in radians for the controller in yaw/rotation when achieving its goal
~<name>/xy_goal_tolerance ( double, default: 0.10)
  • The tolerance in meters for the controller in the x & y distance when achieving a goal
~<name>/latch_xy_goal_tolerance ( bool, default: false)
  • If goal tolerance is latched, if the robot ever reaches the goal xy location it will simply rotate in place, even if it ends up outside the goal tolerance while it is doing so.

2.2.3 Forward Simulation Parameters

~<name>/sim_time (double, default: 1.7)

  • The amount of time to forward-simulate trajectories in seconds
~<name>/sim_granularity ( double, default: 0.025)
  • The step size, in meters, to take between points on a given trajectory
~<name>/vx_samples ( integer, default: 3)
  • The number of samples to use when exploring the x velocity space
~<name>/vy_samples ( integer, default: 10)
  • The number of samples to use when exploring the y velocity space
~<name>/vtheta_samples ( integer, default: 20)
  • The number of samples to use when exploring the theta velocity space
~<name>/controller_frequency ( double, default: 20.0)
  • The frequency at which this controller will be called in Hz. Uses searchParam to read the parameter from parent namespaces if not set in the namespace of the controller. For use withmove_base, this means that you only need to set its "controller_frequency" parameter and can safely leave this one unset.

2.2.4 Trajectory Scoring Parameters

The cost function used to score each trajectory is in the following form:

cost =
  path_distance_bias * (distance to path from the endpoint of the trajectory in meters)
  + goal_distance_bias * (distance to local goal from the endpoint of the trajectory in meters)
  + occdist_scale * (maximum obstacle cost along the trajectory in obstacle cost (0-254))

~<name>/path_distance_bias (double, default: 32.0)

  • The weighting for how much the controller should stay close to the path it was given
~<name>/goal_distance_bias ( double, default: 24.0)
  • The weighting for how much the controller should attempt to reach its local goal, also controls speed
~<name>/occdist_scale ( double, default: 0.01)
  • The weighting for how much the controller should attempt to avoid obstacles
~<name>/forward_point_distance ( double, default: 0.325)
  • The distance from the center point of the robot to place an additional scoring point, in meters
~<name>/stop_time_buffer ( double, default: 0.2)
  • The amount of time that the robot must stop before a collision in order for a trajectory to be considered valid in seconds
~<name>/scaling_speed ( double, default: 0.25)
  • The absolute value of the veolicty at which to start scaling the robot's footprint, in m/s
~<name>/max_scaling_factor ( double, default: 0.2)
  • The maximum factor to scale the robot's footprint by

2.2.5 Oscillation Prevention Parameters

~<name>/oscillation_reset_dist (double, default: 0.05)

  • How far the robot must travel in meters before oscillation flags are reset

2.2.6 Global Plan Parameters

~<name>/prune_plan (bool, default: true)

  • Defines whether or not to eat up the plan as the robot moves along the path. If set to true, points will fall off the end of the plan once the robot moves 1 meter past them.

2.3 C++ API

For C++ level API documentation on the base_local_planner::TrajectoryPlannerROS class, please see the following page:DWAPlannerROS C++ API

3 DWAPlanner

 dwa_local_planner::DWAPlanner实现了DWA和Trajectory Rollout的实现。要在ROS中使用dwa_local_planner::DWAPlanner,请使用进行了ROS封装的格式,不推荐直接使用它。

3.1 API Stability

  • The C++ API is stable. However, it is recommended that you use theDWAPlannerROS wrapper instead of using thedwa_local_planner::TrajectoryPlanner on its own.

3.2 C++ API

For C++ level API documentation on the dwa_local_planner::DWAPlanner class, please see the following page: DWAPlanner C++ API
  • 5
    点赞
  • 47
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值