< >
Home » ROS与navigation教程 » ROS与navigation教程-dwa_local_planner(DWA)

ROS与navigation教程-dwa_local_planner(DWA)

ROS与navigation教程-dwa_local_planner(DWA)

说明:

  • 介绍dwa_local_planner(DWA)的概念和相关知识。

代码库

概要

  • 该包使用DWA(Dynamic Window Approach)算法实现了平面上移动机器人局部导航功能。

  • 给定一个全局路径规划和代价地图,局部路径规划器生成的速度命令发送到移动基座。

  • 该包支持任何footprint表示为凸多边形或圆形的机器人,同时将其配置公开为可在启动文件中设置的ROS参数。 该规划器的参数也可重新动态配置。

  • 该包的ROS封装继承了BaseLocalPlanner接口。

  • dwa_local_planner包提供了一个驱动平面中移动基座的控制器,其将路径规划器和机器人连接到一起。

  • 移动过程中,路径规划器会在机器人周围创建可以表示为栅格地图的评价函数。其中控制器的主要任务就是利用评价函数确定发送给基座的速度(dx,dy,dtheta)。

请输入图片描述

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);

( 1 ) API Stability

  • C++ API 是稳定的。

  • ROS API 是稳定的。

( 1.1 ) Published Topics

~<name>/global_plan ([nav_msgs/Path][6]) 
  • 局部路径规划器当前正在跟踪的全局路径规划的一部分。主要用于可视化。
~<name>/local_plan ([nav_msgs/Path][7]) 
  • 上一个周期中得分最高的局部路径规划或轨迹。 主要用于可视化。

( 1.2 ) Subscribed Topics

odom ([nav_msgs/Odometry][8]) 
  • 提供机器人当前速度的里程计信息到局部路径规划器。假定该消息中的速度信息使用与TrajectoryPlannerROS对象中包含的代价地图的robot_base_frame相同的坐标系。 有关robot_base_frame参数的信息,请参阅costmap_2d 包。

( 2 ) Parameters

  • 可以通过设置ROS参数来定制dwa_local_planner :: DWAPlannerROS的行为。

  • 这些参数分为几类:机器人配置,目标公差,前向仿真,轨迹评分,防振和全局计划。

  • 这些参数中的大多数也可以使用dynamic_reconfigure进行更改,以便于在正在运行的系统中调整本地路径规划器。。
    ( 2.1 ) Robot Configuration Parameters

~<name>/acc_lim_x (double, default: 2.5) 
  • 机器人在x方向的加速度极限,单位为 meters/sec^2 。
~<name>/acc_lim_y (double, default: 2.5) 
  • 机器人在y方向的速度极限,单位为 meters/sec^2 。
~<name>/acc_lim_th (double, default: 3.2) 
  • 机器人的角加速度极限,单位为 radians/sec^2 。
~<name>/max_trans_vel (double, default: 0.55) 
  • 机器人最大平移速度的绝对值,单位为 m/s 。
~<name>/min_trans_vel (double, default: 0.1) 
  • 机器人最小平移速度的绝对值,单位为 m/s 。
~<name>/max_vel_x (double, default: 0.55) 
  • 机器人在x方向到最大速度,单位为 m/s 。
~<name>/min_vel_x (double, default: 0.0) 
  • 机器人在x方向到最小速度,单位为 m/s 。

  • 若设置为负数,则机器人向后移动。

~<name>/max_vel_y (double, default: 0.1) 
  • 机器人在y方向到最大速度,单位为 m/s 。
~<name>/min_vel_y (double, default: -0.1) 
  • 机器人在y方向到最小速度,单位为 m/s 。
~<name>/max_rot_vel (double, default: 1.0) 
  • 机器人的最大角速度的绝对值,单位为 rad/s 。
~<name>/min_rot_vel (double, default: 0.4) 
  • 机器人的最小角速度的绝对值,单位为 rad/s 。

( 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) 
  • 如果锁定目标公差且机器人到达目标xy位置,机器人将简单地旋转到位,即使它在目标公差的范围内结束。

  • 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 ) Forward Simulation Parameters

~<name>/sim_time (double, default: 1.7) 
  • 前向模拟轨迹的时间,单位为 seconds 。
~<name>/sim_granularity (double, default: 0.025) 
  • 给定轨迹上的点之间的间隔尺寸,单位为 meters 。
~<name>/vx_samples (integer, default: 3) 
  • x方向速度的样本数。

  • The number of samples to use when exploring the x velocity space .

~<name>/vy_samples (integer, default: 10) 
  • y方向速度的样本数。

  • The number of samples to use when exploring the y velocity space .

~<name>/vth_samples (integer, default: 20) 
  • 角速度的样本数。

  • The number of samples to use when exploring the theta velocity space .

~<name>/controller_frequency (double, default: 20.0) 
  • 调用该控制器的频率。

  • 当用move_base时,可以只设置controller_frequency参数,可以放心的忽略它。

  • Uses searchParam to read the parameter from parent namespaces if not set in the namespace of the controller. For use with move_base, this means that you only need to set its "controller_frequency" parameter and can safely leave this one unset.

( 2.4 ) Trajectory Scoring Parameters

      cost = 
  pdist_scale * (distance to path from the endpoint of the trajectory in map cells or meters depending on the meter_scoring parameter) 
  + gdist_scale * (distance to local goal from the endpoint of the trajectory in map cells or meters depending on the meter_scoring parameter) 
  + occdist_scale * (maximum obstacle cost along the trajectory in obstacle cost (0-254))
  • 该cost函数使用如上公式给每条轨迹评分
~<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 velocity 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.5 ) Oscillation Prevention Parameters

~<name>/oscillation_reset_dist (double, default: 0.05) 
  • 机器人必须运动多少米远后才能复位震荡标记。

( 2.6 ) Global Plan Parameters

~<name>/prune_plan (bool, default: true)
  • 定义当机器人是否边沿着路径移动时,边抹去已经走过的路径规划。 设置为true时,表示当机器人移动1米后,将1米之前的全局路径点一个一个清除。(包括全局的global path和局部的global path)

( 3 ) C++ API

  • 有关base_local_planner::TrajectoryPlannerROS 类的C ++ API文档,请参阅:DWAPlannerROS C++ API

DWAPlanner

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

( 1 ) API Stability

  • C ++ API是稳定的。

  • 但是,建议您使用DWAPlannerROS,而不是使用dwa_local_planner::TrajectoryPlanner。

( 2 ) C++ API

  • 有关dwa_local_planner :: DWAPlanner类中的C ++ API文档,请参阅:DWAPlanner C++ API

参考资料

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

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


标签: ros与navigation教程